Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion rclrs/build.rs
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ fn get_env_var_or_abort(env_var: &'static str) -> String {
fn main() {
println!(
"cargo:rustc-check-cfg=cfg(ros_distro, values(\"{}\"))",
vec!["humble", "jazzy", "kilted", "rolling"].join("\", \"")
["humble", "jazzy", "kilted", "rolling"].join("\", \"")
);
let ros_distro = if let Ok(value) = env::var(ROS_DISTRO) {
value
Expand Down
8 changes: 8 additions & 0 deletions rclrs/generate_bindings.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,14 @@ def main():
bindgen_command.append('rcutils_.*')
bindgen_command.append('--allowlist-var')
bindgen_command.append('rosidl_.*')
# Blocklist typesupport functions that are already declared in vendored message crates
# (rosidl_generator_rs generates these with *const c_void return type)
bindgen_command.append('--blocklist-function')
bindgen_command.append('rosidl_typesupport_.*__get_message_type_support_handle__.*')
bindgen_command.append('--blocklist-function')
bindgen_command.append('rosidl_typesupport_.*__get_service_type_support_handle__.*')
bindgen_command.append('--blocklist-function')
bindgen_command.append('rosidl_typesupport_.*__get_action_type_support_handle__.*')
bindgen_command.append('--no-layout-tests')
bindgen_command.append('--default-enum-style')
bindgen_command.append('rust')
Expand Down
24 changes: 0 additions & 24 deletions rclrs/src/rcl_bindings_generated_humble.rs
Original file line number Diff line number Diff line change
Expand Up @@ -3404,10 +3404,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence {
pub size: usize,
pub capacity: usize,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__msg__GoalStatus {
Expand All @@ -3421,19 +3417,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence {
pub size: usize,
pub capacity: usize,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__msg__GoalStatusArray {
pub status_list: action_msgs__msg__GoalStatus__Sequence,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__srv__CancelGoal_Request {
Expand All @@ -3445,18 +3433,6 @@ pub struct action_msgs__srv__CancelGoal_Response {
pub return_code: i8,
pub goals_canceling: action_msgs__msg__GoalInfo__Sequence,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal(
) -> *const rosidl_service_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct rosidl_action_type_support_t {
Expand Down
24 changes: 0 additions & 24 deletions rclrs/src/rcl_bindings_generated_jazzy.rs
Original file line number Diff line number Diff line change
Expand Up @@ -8530,10 +8530,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence {
pub size: usize,
pub capacity: usize,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__msg__GoalStatus {
Expand All @@ -8547,19 +8543,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence {
pub size: usize,
pub capacity: usize,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__msg__GoalStatusArray {
pub status_list: action_msgs__msg__GoalStatus__Sequence,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__srv__CancelGoal_Request {
Expand All @@ -8571,22 +8559,10 @@ pub struct action_msgs__srv__CancelGoal_Response {
pub return_code: i8,
pub goals_canceling: action_msgs__msg__GoalInfo__Sequence,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal(
) -> *const rosidl_service_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal(
info: *const rosidl_service_introspection_info_t,
Expand Down
24 changes: 0 additions & 24 deletions rclrs/src/rcl_bindings_generated_kilted.rs
Original file line number Diff line number Diff line change
Expand Up @@ -8392,10 +8392,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence {
pub size: usize,
pub capacity: usize,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__msg__GoalStatus {
Expand All @@ -8409,19 +8405,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence {
pub size: usize,
pub capacity: usize,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__msg__GoalStatusArray {
pub status_list: action_msgs__msg__GoalStatus__Sequence,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__srv__CancelGoal_Request {
Expand All @@ -8433,22 +8421,10 @@ pub struct action_msgs__srv__CancelGoal_Response {
pub return_code: i8,
pub goals_canceling: action_msgs__msg__GoalInfo__Sequence,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal(
) -> *const rosidl_service_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal(
info: *const rosidl_service_introspection_info_t,
Expand Down
24 changes: 0 additions & 24 deletions rclrs/src/rcl_bindings_generated_rolling.rs
Original file line number Diff line number Diff line change
Expand Up @@ -8395,10 +8395,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence {
pub size: usize,
pub capacity: usize,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalInfo(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__msg__GoalStatus {
Expand All @@ -8412,19 +8408,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence {
pub size: usize,
pub capacity: usize,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatus(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__msg__GoalStatusArray {
pub status_list: action_msgs__msg__GoalStatus__Sequence,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__msg__GoalStatusArray(
) -> *const rosidl_message_type_support_t;
}
#[repr(C)]
#[derive(Debug)]
pub struct action_msgs__srv__CancelGoal_Request {
Expand All @@ -8436,22 +8424,10 @@ pub struct action_msgs__srv__CancelGoal_Response {
pub return_code: i8,
pub goals_canceling: action_msgs__msg__GoalInfo__Sequence,
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event(
) -> *const rosidl_message_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal(
) -> *const rosidl_service_type_support_t;
}
extern "C" {
pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal(
info: *const rosidl_service_introspection_info_t,
Expand Down
Loading