diff --git a/rclrs/build.rs b/rclrs/build.rs index 930940ff..9cdb375d 100644 --- a/rclrs/build.rs +++ b/rclrs/build.rs @@ -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 diff --git a/rclrs/generate_bindings.py b/rclrs/generate_bindings.py index 833b90cf..991caf07 100755 --- a/rclrs/generate_bindings.py +++ b/rclrs/generate_bindings.py @@ -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') diff --git a/rclrs/src/rcl_bindings_generated_humble.rs b/rclrs/src/rcl_bindings_generated_humble.rs index d7c0b4c1..cfa2e949 100644 --- a/rclrs/src/rcl_bindings_generated_humble.rs +++ b/rclrs/src/rcl_bindings_generated_humble.rs @@ -1,4 +1,4 @@ -/* automatically generated by rust-bindgen 0.72.1 */ +/* automatically generated by rust-bindgen 0.72.0 */ pub type rcutils_ret_t = ::std::os::raw::c_int; #[repr(C)] @@ -3404,10 +3404,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence { pub size: usize, pub capacity: usize, } -unsafe 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 { @@ -3421,19 +3417,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence { pub size: usize, pub capacity: usize, } -unsafe 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, } -unsafe 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 { @@ -3445,18 +3433,6 @@ pub struct action_msgs__srv__CancelGoal_Response { pub return_code: i8, pub goals_canceling: action_msgs__msg__GoalInfo__Sequence, } -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response( - ) -> *const rosidl_message_type_support_t; -} -unsafe 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 { diff --git a/rclrs/src/rcl_bindings_generated_jazzy.rs b/rclrs/src/rcl_bindings_generated_jazzy.rs index a96db7fd..4c18f98d 100644 --- a/rclrs/src/rcl_bindings_generated_jazzy.rs +++ b/rclrs/src/rcl_bindings_generated_jazzy.rs @@ -1,4 +1,4 @@ -/* automatically generated by rust-bindgen 0.72.1 */ +/* automatically generated by rust-bindgen 0.72.0 */ pub type rcutils_ret_t = ::std::os::raw::c_int; #[repr(C)] @@ -526,6 +526,9 @@ unsafe extern "C" { unsafe extern "C" { pub fn rcutils_steady_time_now(now: *mut rcutils_time_point_value_t) -> rcutils_ret_t; } +unsafe extern "C" { + pub fn rcutils_raw_steady_time_now(now: *mut rcutils_time_point_value_t) -> rcutils_ret_t; +} unsafe extern "C" { pub fn rcutils_time_point_value_as_nanoseconds_string( time_point: *const rcutils_time_point_value_t, @@ -2776,22 +2779,6 @@ pub struct rosidl_action_type_support_t { pub get_type_description_func: rosidl_action_get_type_description_function, pub get_type_description_sources_func: rosidl_action_get_type_description_sources_function, } -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Request( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Response( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Event( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_service_type_support_handle__type_description_interfaces__srv__GetTypeDescription( - ) -> *const rosidl_service_type_support_t; -} unsafe extern "C" { pub fn rosidl_typesupport_c__create_service_event_message__type_description_interfaces__srv__GetTypeDescription( info: *const rosidl_service_introspection_info_t, @@ -8530,10 +8517,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence { pub size: usize, pub capacity: usize, } -unsafe 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 { @@ -8547,19 +8530,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence { pub size: usize, pub capacity: usize, } -unsafe 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, } -unsafe 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 { @@ -8571,22 +8546,6 @@ pub struct action_msgs__srv__CancelGoal_Response { pub return_code: i8, pub goals_canceling: action_msgs__msg__GoalInfo__Sequence, } -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal( - ) -> *const rosidl_service_type_support_t; -} unsafe extern "C" { pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal( info: *const rosidl_service_introspection_info_t, diff --git a/rclrs/src/rcl_bindings_generated_kilted.rs b/rclrs/src/rcl_bindings_generated_kilted.rs index 18f8bb96..3ade10d4 100644 --- a/rclrs/src/rcl_bindings_generated_kilted.rs +++ b/rclrs/src/rcl_bindings_generated_kilted.rs @@ -1,4 +1,4 @@ -/* automatically generated by rust-bindgen 0.72.1 */ +/* automatically generated by rust-bindgen 0.72.0 */ pub type rcutils_ret_t = ::std::os::raw::c_int; #[repr(C)] @@ -526,6 +526,9 @@ unsafe extern "C" { unsafe extern "C" { pub fn rcutils_steady_time_now(now: *mut rcutils_time_point_value_t) -> rcutils_ret_t; } +unsafe extern "C" { + pub fn rcutils_raw_steady_time_now(now: *mut rcutils_time_point_value_t) -> rcutils_ret_t; +} unsafe extern "C" { pub fn rcutils_time_point_value_as_nanoseconds_string( time_point: *const rcutils_time_point_value_t, @@ -2780,22 +2783,6 @@ pub struct rosidl_action_type_support_t { pub get_type_description_func: rosidl_action_get_type_description_function, pub get_type_description_sources_func: rosidl_action_get_type_description_sources_function, } -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Request( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Response( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Event( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_service_type_support_handle__type_description_interfaces__srv__GetTypeDescription( - ) -> *const rosidl_service_type_support_t; -} unsafe extern "C" { pub fn rosidl_typesupport_c__create_service_event_message__type_description_interfaces__srv__GetTypeDescription( info: *const rosidl_service_introspection_info_t, @@ -8392,10 +8379,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence { pub size: usize, pub capacity: usize, } -unsafe 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 { @@ -8409,19 +8392,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence { pub size: usize, pub capacity: usize, } -unsafe 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, } -unsafe 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 { @@ -8433,22 +8408,6 @@ pub struct action_msgs__srv__CancelGoal_Response { pub return_code: i8, pub goals_canceling: action_msgs__msg__GoalInfo__Sequence, } -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal( - ) -> *const rosidl_service_type_support_t; -} unsafe extern "C" { pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal( info: *const rosidl_service_introspection_info_t, diff --git a/rclrs/src/rcl_bindings_generated_rolling.rs b/rclrs/src/rcl_bindings_generated_rolling.rs index b95a38d0..bc067e76 100644 --- a/rclrs/src/rcl_bindings_generated_rolling.rs +++ b/rclrs/src/rcl_bindings_generated_rolling.rs @@ -1,4 +1,4 @@ -/* automatically generated by rust-bindgen 0.72.1 */ +/* automatically generated by rust-bindgen 0.72.0 */ pub type rcutils_ret_t = ::std::os::raw::c_int; #[repr(C)] @@ -529,6 +529,9 @@ unsafe extern "C" { unsafe extern "C" { pub fn rcutils_steady_time_now(now: *mut rcutils_time_point_value_t) -> rcutils_ret_t; } +unsafe extern "C" { + pub fn rcutils_raw_steady_time_now(now: *mut rcutils_time_point_value_t) -> rcutils_ret_t; +} unsafe extern "C" { pub fn rcutils_time_point_value_as_nanoseconds_string( time_point: *const rcutils_time_point_value_t, @@ -550,6 +553,11 @@ unsafe extern "C" { str_size: usize, ) -> rcutils_ret_t; } +unsafe extern "C" { + pub fn rcutils_logging_allocator_initialize( + allocator: *const rcutils_allocator_t, + ) -> rcutils_ret_t; +} unsafe extern "C" { pub fn rcutils_logging_initialize_with_allocator( allocator: rcutils_allocator_t, @@ -1004,6 +1012,8 @@ pub enum rmw_endpoint_type_e { RMW_ENDPOINT_INVALID = 0, RMW_ENDPOINT_PUBLISHER = 1, RMW_ENDPOINT_SUBSCRIPTION = 2, + RMW_ENDPOINT_CLIENT = 3, + RMW_ENDPOINT_SERVER = 4, } pub use self::rmw_endpoint_type_e as rmw_endpoint_type_t; #[repr(u32)] @@ -1307,6 +1317,113 @@ unsafe extern "C" { } #[repr(C)] #[derive(Debug)] +pub struct rmw_service_endpoint_info_s { + pub node_name: *const ::std::os::raw::c_char, + pub node_namespace: *const ::std::os::raw::c_char, + pub service_type: *const ::std::os::raw::c_char, + pub service_type_hash: rosidl_type_hash_t, + pub endpoint_type: rmw_endpoint_type_t, + pub endpoint_count: usize, + pub endpoint_gids: *mut [u8; 16usize], + pub qos_profiles: *mut rmw_qos_profile_t, +} +pub type rmw_service_endpoint_info_t = rmw_service_endpoint_info_s; +unsafe extern "C" { + pub fn rmw_get_zero_initialized_service_endpoint_info() -> rmw_service_endpoint_info_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_fini( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + allocator: *mut rcutils_allocator_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_set_service_type( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + service_type: *const ::std::os::raw::c_char, + allocator: *mut rcutils_allocator_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_set_service_type_hash( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + type_hash: *const rosidl_type_hash_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_set_node_name( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + node_name: *const ::std::os::raw::c_char, + allocator: *mut rcutils_allocator_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_set_node_namespace( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + node_namespace: *const ::std::os::raw::c_char, + allocator: *mut rcutils_allocator_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_set_endpoint_type( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + type_: rmw_endpoint_type_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_set_endpoint_count( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + endpoint_count: usize, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_set_gids( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + gids: *const u8, + endpoint_count: usize, + size: usize, + allocator: *mut rcutils_allocator_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_set_qos_profiles( + service_endpoint_info: *mut rmw_service_endpoint_info_t, + qos_profiles: *const rmw_qos_profile_t, + endpoint_count: usize, + allocator: *mut rcutils_allocator_t, + ) -> rmw_ret_t; +} +#[repr(C)] +#[derive(Debug)] +pub struct rmw_service_endpoint_info_array_s { + pub size: usize, + pub info_array: *mut rmw_service_endpoint_info_t, +} +pub type rmw_service_endpoint_info_array_t = rmw_service_endpoint_info_array_s; +unsafe extern "C" { + pub fn rmw_get_zero_initialized_service_endpoint_info_array( + ) -> rmw_service_endpoint_info_array_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_array_check_zero( + service_endpoint_info_array: *mut rmw_service_endpoint_info_array_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_array_init_with_size( + service_endpoint_info_array: *mut rmw_service_endpoint_info_array_t, + size: usize, + allocator: *mut rcutils_allocator_t, + ) -> rmw_ret_t; +} +unsafe extern "C" { + pub fn rmw_service_endpoint_info_array_fini( + service_endpoint_info_array: *mut rmw_service_endpoint_info_array_t, + allocator: *mut rcutils_allocator_t, + ) -> rmw_ret_t; +} +#[repr(C)] +#[derive(Debug)] pub struct rmw_topic_endpoint_info_s { pub node_name: *const ::std::os::raw::c_char, pub node_namespace: *const ::std::os::raw::c_char, @@ -2783,22 +2900,6 @@ pub struct rosidl_action_type_support_t { pub get_type_description_func: rosidl_action_get_type_description_function, pub get_type_description_sources_func: rosidl_action_get_type_description_sources_function, } -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Request( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Response( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__type_description_interfaces__srv__GetTypeDescription_Event( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_service_type_support_handle__type_description_interfaces__srv__GetTypeDescription( - ) -> *const rosidl_service_type_support_t; -} unsafe extern "C" { pub fn rosidl_typesupport_c__create_service_event_message__type_description_interfaces__srv__GetTypeDescription( info: *const rosidl_service_introspection_info_t, @@ -3302,6 +3403,8 @@ unsafe extern "C" { pub type rcl_names_and_types_t = rmw_names_and_types_t; pub type rcl_topic_endpoint_info_t = rmw_topic_endpoint_info_t; pub type rcl_topic_endpoint_info_array_t = rmw_topic_endpoint_info_array_t; +pub type rcl_service_endpoint_info_t = rmw_service_endpoint_info_t; +pub type rcl_service_endpoint_info_array_t = rmw_service_endpoint_info_array_t; unsafe extern "C" { pub fn rcl_get_publisher_names_and_types_by_node( node: *const rcl_node_t, @@ -3430,6 +3533,26 @@ unsafe extern "C" { success: *mut bool, ) -> rcl_ret_t; } +unsafe extern "C" { + pub fn rcl_wait_for_clients( + node: *const rcl_node_t, + allocator: *mut rcl_allocator_t, + service_name: *const ::std::os::raw::c_char, + count: usize, + timeout: rcutils_duration_value_t, + success: *mut bool, + ) -> rcl_ret_t; +} +unsafe extern "C" { + pub fn rcl_wait_for_servers( + node: *const rcl_node_t, + allocator: *mut rcl_allocator_t, + service_name: *const ::std::os::raw::c_char, + count: usize, + timeout: rcutils_duration_value_t, + success: *mut bool, + ) -> rcl_ret_t; +} unsafe extern "C" { pub fn rcl_get_publishers_info_by_topic( node: *const rcl_node_t, @@ -3448,6 +3571,24 @@ unsafe extern "C" { subscriptions_info: *mut rcl_topic_endpoint_info_array_t, ) -> rcl_ret_t; } +unsafe extern "C" { + pub fn rcl_get_clients_info_by_service( + node: *const rcl_node_t, + allocator: *mut rcutils_allocator_t, + service_name: *const ::std::os::raw::c_char, + no_mangle: bool, + clients_info: *mut rcl_service_endpoint_info_array_t, + ) -> rcl_ret_t; +} +unsafe extern "C" { + pub fn rcl_get_servers_info_by_service( + node: *const rcl_node_t, + allocator: *mut rcutils_allocator_t, + service_name: *const ::std::os::raw::c_char, + no_mangle: bool, + servers_info: *mut rcl_service_endpoint_info_array_t, + ) -> rcl_ret_t; +} unsafe extern "C" { pub fn rcl_service_server_is_available( node: *const rcl_node_t, @@ -8395,10 +8536,6 @@ pub struct action_msgs__msg__GoalInfo__Sequence { pub size: usize, pub capacity: usize, } -unsafe 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 { @@ -8412,19 +8549,11 @@ pub struct action_msgs__msg__GoalStatus__Sequence { pub size: usize, pub capacity: usize, } -unsafe 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, } -unsafe 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 { @@ -8436,22 +8565,6 @@ pub struct action_msgs__srv__CancelGoal_Response { pub return_code: i8, pub goals_canceling: action_msgs__msg__GoalInfo__Sequence, } -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Request( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Response( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_message_type_support_handle__action_msgs__srv__CancelGoal_Event( - ) -> *const rosidl_message_type_support_t; -} -unsafe extern "C" { - pub fn rosidl_typesupport_c__get_service_type_support_handle__action_msgs__srv__CancelGoal( - ) -> *const rosidl_service_type_support_t; -} unsafe extern "C" { pub fn rosidl_typesupport_c__create_service_event_message__action_msgs__srv__CancelGoal( info: *const rosidl_service_introspection_info_t, @@ -8757,6 +8870,11 @@ unsafe extern "C" { goal_handle: *const rcl_action_goal_handle_t, ) -> bool; } +unsafe extern "C" { + pub fn rcl_action_goal_handle_is_abortable( + goal_handle: *const rcl_action_goal_handle_t, + ) -> bool; +} unsafe extern "C" { pub fn rcl_action_goal_handle_is_valid(goal_handle: *const rcl_action_goal_handle_t) -> bool; }