Skip to content

Commit 6b7d897

Browse files
committed
fix: blocklist duplicate typesupport extern declarations
Add blocklist patterns to generate_bindings.py to prevent bindgen from generating typesupport function declarations that clash with vendored message crates (rosidl_generator_rs generates these with *const c_void). Remove existing duplicate extern declarations from all 4 generated binding files for: - rosidl_typesupport_c__get_message_type_support_handle__action_msgs__* - rosidl_typesupport_c__get_service_type_support_handle__action_msgs__* Also fix clippy useless_vec warning in build.rs. Closes #559
1 parent ed7bca6 commit 6b7d897

File tree

6 files changed

+9
-97
lines changed

6 files changed

+9
-97
lines changed

rclrs/build.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ fn get_env_var_or_abort(env_var: &'static str) -> String {
1616
fn main() {
1717
println!(
1818
"cargo:rustc-check-cfg=cfg(ros_distro, values(\"{}\"))",
19-
vec!["humble", "jazzy", "kilted", "rolling"].join("\", \"")
19+
["humble", "jazzy", "kilted", "rolling"].join("\", \"")
2020
);
2121
let ros_distro = if let Ok(value) = env::var(ROS_DISTRO) {
2222
value

rclrs/generate_bindings.py

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,14 @@ def main():
4646
bindgen_command.append('rcutils_.*')
4747
bindgen_command.append('--allowlist-var')
4848
bindgen_command.append('rosidl_.*')
49+
# Blocklist typesupport functions that are already declared in vendored message crates
50+
# (rosidl_generator_rs generates these with *const c_void return type)
51+
bindgen_command.append('--blocklist-function')
52+
bindgen_command.append('rosidl_typesupport_.*__get_message_type_support_handle__.*')
53+
bindgen_command.append('--blocklist-function')
54+
bindgen_command.append('rosidl_typesupport_.*__get_service_type_support_handle__.*')
55+
bindgen_command.append('--blocklist-function')
56+
bindgen_command.append('rosidl_typesupport_.*__get_action_type_support_handle__.*')
4957
bindgen_command.append('--no-layout-tests')
5058
bindgen_command.append('--default-enum-style')
5159
bindgen_command.append('rust')

rclrs/src/rcl_bindings_generated_humble.rs

Lines changed: 0 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -3404,10 +3404,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence {
34043404
pub size: usize,
34053405
pub capacity: usize,
34063406
}
3407-
extern "C" {
3408-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo(
3409-
) -> *const rosidl_message_type_support_t;
3410-
}
34113407
#[repr(C)]
34123408
#[derive(Debug)]
34133409
pub struct action_msgs__msg__GoalStatus {
@@ -3421,19 +3417,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence {
34213417
pub size: usize,
34223418
pub capacity: usize,
34233419
}
3424-
extern "C" {
3425-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus(
3426-
) -> *const rosidl_message_type_support_t;
3427-
}
34283420
#[repr(C)]
34293421
#[derive(Debug)]
34303422
pub struct action_msgs__msg__GoalStatusArray {
34313423
pub status_list: action_msgs__msg__GoalStatus__Sequence,
34323424
}
3433-
extern "C" {
3434-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray(
3435-
) -> *const rosidl_message_type_support_t;
3436-
}
34373425
#[repr(C)]
34383426
#[derive(Debug)]
34393427
pub struct action_msgs__srv__CancelGoal_Request {
@@ -3445,18 +3433,6 @@ pub struct action_msgs__srv__CancelGoal_Response {
34453433
pub return_code: i8,
34463434
pub goals_canceling: action_msgs__msg__GoalInfo__Sequence,
34473435
}
3448-
extern "C" {
3449-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request(
3450-
) -> *const rosidl_message_type_support_t;
3451-
}
3452-
extern "C" {
3453-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response(
3454-
) -> *const rosidl_message_type_support_t;
3455-
}
3456-
extern "C" {
3457-
pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal(
3458-
) -> *const rosidl_service_type_support_t;
3459-
}
34603436
#[repr(C)]
34613437
#[derive(Debug)]
34623438
pub struct rosidl_action_type_support_t {

rclrs/src/rcl_bindings_generated_jazzy.rs

Lines changed: 0 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -8530,10 +8530,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence {
85308530
pub size: usize,
85318531
pub capacity: usize,
85328532
}
8533-
extern "C" {
8534-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo(
8535-
) -> *const rosidl_message_type_support_t;
8536-
}
85378533
#[repr(C)]
85388534
#[derive(Debug)]
85398535
pub struct action_msgs__msg__GoalStatus {
@@ -8547,19 +8543,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence {
85478543
pub size: usize,
85488544
pub capacity: usize,
85498545
}
8550-
extern "C" {
8551-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus(
8552-
) -> *const rosidl_message_type_support_t;
8553-
}
85548546
#[repr(C)]
85558547
#[derive(Debug)]
85568548
pub struct action_msgs__msg__GoalStatusArray {
85578549
pub status_list: action_msgs__msg__GoalStatus__Sequence,
85588550
}
8559-
extern "C" {
8560-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray(
8561-
) -> *const rosidl_message_type_support_t;
8562-
}
85638551
#[repr(C)]
85648552
#[derive(Debug)]
85658553
pub struct action_msgs__srv__CancelGoal_Request {
@@ -8571,22 +8559,10 @@ pub struct action_msgs__srv__CancelGoal_Response {
85718559
pub return_code: i8,
85728560
pub goals_canceling: action_msgs__msg__GoalInfo__Sequence,
85738561
}
8574-
extern "C" {
8575-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request(
8576-
) -> *const rosidl_message_type_support_t;
8577-
}
8578-
extern "C" {
8579-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response(
8580-
) -> *const rosidl_message_type_support_t;
8581-
}
85828562
extern "C" {
85838563
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event(
85848564
) -> *const rosidl_message_type_support_t;
85858565
}
8586-
extern "C" {
8587-
pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal(
8588-
) -> *const rosidl_service_type_support_t;
8589-
}
85908566
extern "C" {
85918567
pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal(
85928568
info: *const rosidl_service_introspection_info_t,

rclrs/src/rcl_bindings_generated_kilted.rs

Lines changed: 0 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -8392,10 +8392,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence {
83928392
pub size: usize,
83938393
pub capacity: usize,
83948394
}
8395-
extern "C" {
8396-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo(
8397-
) -> *const rosidl_message_type_support_t;
8398-
}
83998395
#[repr(C)]
84008396
#[derive(Debug)]
84018397
pub struct action_msgs__msg__GoalStatus {
@@ -8409,19 +8405,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence {
84098405
pub size: usize,
84108406
pub capacity: usize,
84118407
}
8412-
extern "C" {
8413-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus(
8414-
) -> *const rosidl_message_type_support_t;
8415-
}
84168408
#[repr(C)]
84178409
#[derive(Debug)]
84188410
pub struct action_msgs__msg__GoalStatusArray {
84198411
pub status_list: action_msgs__msg__GoalStatus__Sequence,
84208412
}
8421-
extern "C" {
8422-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray(
8423-
) -> *const rosidl_message_type_support_t;
8424-
}
84258413
#[repr(C)]
84268414
#[derive(Debug)]
84278415
pub struct action_msgs__srv__CancelGoal_Request {
@@ -8433,22 +8421,10 @@ pub struct action_msgs__srv__CancelGoal_Response {
84338421
pub return_code: i8,
84348422
pub goals_canceling: action_msgs__msg__GoalInfo__Sequence,
84358423
}
8436-
extern "C" {
8437-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request(
8438-
) -> *const rosidl_message_type_support_t;
8439-
}
8440-
extern "C" {
8441-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response(
8442-
) -> *const rosidl_message_type_support_t;
8443-
}
84448424
extern "C" {
84458425
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event(
84468426
) -> *const rosidl_message_type_support_t;
84478427
}
8448-
extern "C" {
8449-
pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal(
8450-
) -> *const rosidl_service_type_support_t;
8451-
}
84528428
extern "C" {
84538429
pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal(
84548430
info: *const rosidl_service_introspection_info_t,

rclrs/src/rcl_bindings_generated_rolling.rs

Lines changed: 0 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -8395,10 +8395,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence {
83958395
pub size: usize,
83968396
pub capacity: usize,
83978397
}
8398-
extern "C" {
8399-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo(
8400-
) -> *const rosidl_message_type_support_t;
8401-
}
84028398
#[repr(C)]
84038399
#[derive(Debug)]
84048400
pub struct action_msgs__msg__GoalStatus {
@@ -8412,19 +8408,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence {
84128408
pub size: usize,
84138409
pub capacity: usize,
84148410
}
8415-
extern "C" {
8416-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus(
8417-
) -> *const rosidl_message_type_support_t;
8418-
}
84198411
#[repr(C)]
84208412
#[derive(Debug)]
84218413
pub struct action_msgs__msg__GoalStatusArray {
84228414
pub status_list: action_msgs__msg__GoalStatus__Sequence,
84238415
}
8424-
extern "C" {
8425-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray(
8426-
) -> *const rosidl_message_type_support_t;
8427-
}
84288416
#[repr(C)]
84298417
#[derive(Debug)]
84308418
pub struct action_msgs__srv__CancelGoal_Request {
@@ -8436,22 +8424,10 @@ pub struct action_msgs__srv__CancelGoal_Response {
84368424
pub return_code: i8,
84378425
pub goals_canceling: action_msgs__msg__GoalInfo__Sequence,
84388426
}
8439-
extern "C" {
8440-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request(
8441-
) -> *const rosidl_message_type_support_t;
8442-
}
8443-
extern "C" {
8444-
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response(
8445-
) -> *const rosidl_message_type_support_t;
8446-
}
84478427
extern "C" {
84488428
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event(
84498429
) -> *const rosidl_message_type_support_t;
84508430
}
8451-
extern "C" {
8452-
pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal(
8453-
) -> *const rosidl_service_type_support_t;
8454-
}
84558431
extern "C" {
84568432
pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal(
84578433
info: *const rosidl_service_introspection_info_t,

0 commit comments

Comments
 (0)