Refresh bindings

This commit is contained in:
Martin Dahl 2023-06-26 12:05:55 +02:00
parent f19b256139
commit a54682ec93
32 changed files with 27210 additions and 5071 deletions

View File

@ -1 +1,30 @@
impl UntypedActionSupport { pub fn new_from (typename : & str) -> Result < Self > { # [allow (non_snake_case)] fn new_untyped_service_support_tf2_msgs_action_LookupTransform () -> UntypedActionSupport { UntypedActionSupport :: new :: < tf2_msgs :: action :: LookupTransform :: Action > () } static MAP : phf :: Map < & 'static str , fn () -> UntypedActionSupport > = phf :: phf_map ! { "tf2_msgs/action/LookupTransform" => new_untyped_service_support_tf2_msgs_action_LookupTransform } ; let func = MAP . get (typename) . ok_or_else (|| Error :: InvalidMessageType { msgtype : typename . into () }) ? ; Ok (func ()) } }
impl UntypedActionSupport {
pub fn new_from(typename: &str) -> Result<Self> {
#[allow(non_snake_case)]
fn new_untyped_service_support_test_msgs_action_Fibonacci() -> UntypedActionSupport {
UntypedActionSupport::new::<test_msgs::action::Fibonacci::Action>()
}
#[allow(non_snake_case)]
fn new_untyped_service_support_test_msgs_action_NestedMessage() -> UntypedActionSupport {
UntypedActionSupport::new::<test_msgs::action::NestedMessage::Action>()
}
#[allow(non_snake_case)]
fn new_untyped_service_support_tf2_msgs_action_LookupTransform() -> UntypedActionSupport {
UntypedActionSupport::new::<tf2_msgs::action::LookupTransform::Action>()
}
static MAP: phf::Map<&'static str, fn() -> UntypedActionSupport> = phf::phf_map! {
"test_msgs/action/Fibonacci" =>
new_untyped_service_support_test_msgs_action_Fibonacci,
"test_msgs/action/NestedMessage" =>
new_untyped_service_support_test_msgs_action_NestedMessage,
"tf2_msgs/action/LookupTransform" =>
new_untyped_service_support_tf2_msgs_action_LookupTransform
};
let func = MAP
.get(typename)
.ok_or_else(|| Error::InvalidMessageType {
msgtype: typename.into(),
})?;
Ok(func())
}
}

View File

@ -1 +1,54 @@
pub mod action_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/action_msgs.rs")) ; } pub mod builtin_interfaces { include ! (concat ! (env ! ("OUT_DIR") , "/builtin_interfaces.rs")) ; } pub mod diagnostic_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/diagnostic_msgs.rs")) ; } pub mod geometry_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/geometry_msgs.rs")) ; } pub mod lifecycle_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/lifecycle_msgs.rs")) ; } pub mod map_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/map_msgs.rs")) ; } pub mod nav_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/nav_msgs.rs")) ; } pub mod pendulum_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/pendulum_msgs.rs")) ; } pub mod rcl_interfaces { include ! (concat ! (env ! ("OUT_DIR") , "/rcl_interfaces.rs")) ; } pub mod rosgraph_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/rosgraph_msgs.rs")) ; } pub mod sensor_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/sensor_msgs.rs")) ; } pub mod shape_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/shape_msgs.rs")) ; } pub mod statistics_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/statistics_msgs.rs")) ; } pub mod std_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/std_msgs.rs")) ; } pub mod stereo_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/stereo_msgs.rs")) ; } pub mod tf2_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/tf2_msgs.rs")) ; } pub mod trajectory_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/trajectory_msgs.rs")) ; } pub mod unique_identifier_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/unique_identifier_msgs.rs")) ; } pub mod visualization_msgs { include ! (concat ! (env ! ("OUT_DIR") , "/visualization_msgs.rs")) ; }
pub mod action_msgs {
include!(concat!(env!("OUT_DIR"), "/action_msgs.rs"));
}
pub mod builtin_interfaces {
include!(concat!(env!("OUT_DIR"), "/builtin_interfaces.rs"));
}
pub mod diagnostic_msgs {
include!(concat!(env!("OUT_DIR"), "/diagnostic_msgs.rs"));
}
pub mod geometry_msgs {
include!(concat!(env!("OUT_DIR"), "/geometry_msgs.rs"));
}
pub mod lifecycle_msgs {
include!(concat!(env!("OUT_DIR"), "/lifecycle_msgs.rs"));
}
pub mod nav_msgs {
include!(concat!(env!("OUT_DIR"), "/nav_msgs.rs"));
}
pub mod rcl_interfaces {
include!(concat!(env!("OUT_DIR"), "/rcl_interfaces.rs"));
}
pub mod rosgraph_msgs {
include!(concat!(env!("OUT_DIR"), "/rosgraph_msgs.rs"));
}
pub mod sensor_msgs {
include!(concat!(env!("OUT_DIR"), "/sensor_msgs.rs"));
}
pub mod shape_msgs {
include!(concat!(env!("OUT_DIR"), "/shape_msgs.rs"));
}
pub mod statistics_msgs {
include!(concat!(env!("OUT_DIR"), "/statistics_msgs.rs"));
}
pub mod std_msgs {
include!(concat!(env!("OUT_DIR"), "/std_msgs.rs"));
}
pub mod stereo_msgs {
include!(concat!(env!("OUT_DIR"), "/stereo_msgs.rs"));
}
pub mod test_msgs {
include!(concat!(env!("OUT_DIR"), "/test_msgs.rs"));
}
pub mod tf2_msgs {
include!(concat!(env!("OUT_DIR"), "/tf2_msgs.rs"));
}
pub mod trajectory_msgs {
include!(concat!(env!("OUT_DIR"), "/trajectory_msgs.rs"));
}
pub mod unique_identifier_msgs {
include!(concat!(env!("OUT_DIR"), "/unique_identifier_msgs.rs"));
}
pub mod visualization_msgs {
include!(concat!(env!("OUT_DIR"), "/visualization_msgs.rs"));
}

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1 +1,83 @@
pub mod msg { use super :: super :: * ; # [derive (Clone , Debug , PartialEq , Serialize , Deserialize)] # [serde (default)] pub struct Duration { pub sec : i32 , pub nanosec : u32 } impl WrappedTypesupport for Duration { type CStruct = builtin_interfaces__msg__Duration ; fn get_ts () -> & 'static rosidl_message_type_support_t { unsafe { & * rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Duration () } } fn create_msg () -> * mut builtin_interfaces__msg__Duration { unsafe { builtin_interfaces__msg__Duration__create () } } fn destroy_msg (msg : * mut builtin_interfaces__msg__Duration) -> () { unsafe { builtin_interfaces__msg__Duration__destroy (msg) } ; } fn from_native (# [allow (unused)] msg : & Self :: CStruct) -> Duration { Duration { sec : msg . sec , nanosec : msg . nanosec , } } fn copy_to_native (& self , # [allow (unused)] msg : & mut Self :: CStruct) { msg . sec = self . sec ; msg . nanosec = self . nanosec ; } } impl Default for Duration { fn default () -> Self { let msg_native = WrappedNativeMsg :: < Duration > :: new () ; Duration :: from_native (& msg_native) } } # [derive (Clone , Debug , PartialEq , Serialize , Deserialize)] # [serde (default)] pub struct Time { pub sec : i32 , pub nanosec : u32 } impl WrappedTypesupport for Time { type CStruct = builtin_interfaces__msg__Time ; fn get_ts () -> & 'static rosidl_message_type_support_t { unsafe { & * rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Time () } } fn create_msg () -> * mut builtin_interfaces__msg__Time { unsafe { builtin_interfaces__msg__Time__create () } } fn destroy_msg (msg : * mut builtin_interfaces__msg__Time) -> () { unsafe { builtin_interfaces__msg__Time__destroy (msg) } ; } fn from_native (# [allow (unused)] msg : & Self :: CStruct) -> Time { Time { sec : msg . sec , nanosec : msg . nanosec , } } fn copy_to_native (& self , # [allow (unused)] msg : & mut Self :: CStruct) { msg . sec = self . sec ; msg . nanosec = self . nanosec ; } } impl Default for Time { fn default () -> Self { let msg_native = WrappedNativeMsg :: < Time > :: new () ; Time :: from_native (& msg_native) } } }
pub mod msg {
use super::super::*;
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
#[serde(default)]
pub struct Duration {
pub sec: i32,
pub nanosec: u32,
}
impl WrappedTypesupport for Duration {
type CStruct = builtin_interfaces__msg__Duration;
fn get_ts() -> &'static rosidl_message_type_support_t {
unsafe {
&*rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Duration()
}
}
fn create_msg() -> *mut builtin_interfaces__msg__Duration {
#[cfg(not(feature = "doc-only"))]
unsafe { builtin_interfaces__msg__Duration__create() }
#[cfg(feature = "doc-only")] builtin_interfaces__msg__Duration__create()
}
fn destroy_msg(msg: *mut builtin_interfaces__msg__Duration) -> () {
#[cfg(not(feature = "doc-only"))]
unsafe { builtin_interfaces__msg__Duration__destroy(msg) };
#[cfg(feature = "doc-only")] builtin_interfaces__msg__Duration__destroy(msg)
}
fn from_native(#[allow(unused)] msg: &Self::CStruct) -> Duration {
Duration {
sec: msg.sec,
nanosec: msg.nanosec,
}
}
fn copy_to_native(&self, #[allow(unused)] msg: &mut Self::CStruct) {
msg.sec = self.sec;
msg.nanosec = self.nanosec;
}
}
impl Default for Duration {
fn default() -> Self {
let msg_native = WrappedNativeMsg::<Duration>::new();
Duration::from_native(&msg_native)
}
}
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
#[serde(default)]
pub struct Time {
pub sec: i32,
pub nanosec: u32,
}
impl WrappedTypesupport for Time {
type CStruct = builtin_interfaces__msg__Time;
fn get_ts() -> &'static rosidl_message_type_support_t {
unsafe {
&*rosidl_typesupport_c__get_message_type_support_handle__builtin_interfaces__msg__Time()
}
}
fn create_msg() -> *mut builtin_interfaces__msg__Time {
#[cfg(not(feature = "doc-only"))]
unsafe { builtin_interfaces__msg__Time__create() }
#[cfg(feature = "doc-only")] builtin_interfaces__msg__Time__create()
}
fn destroy_msg(msg: *mut builtin_interfaces__msg__Time) -> () {
#[cfg(not(feature = "doc-only"))]
unsafe { builtin_interfaces__msg__Time__destroy(msg) };
#[cfg(feature = "doc-only")] builtin_interfaces__msg__Time__destroy(msg)
}
fn from_native(#[allow(unused)] msg: &Self::CStruct) -> Time {
Time {
sec: msg.sec,
nanosec: msg.nanosec,
}
}
fn copy_to_native(&self, #[allow(unused)] msg: &mut Self::CStruct) {
msg.sec = self.sec;
msg.nanosec = self.nanosec;
}
}
impl Default for Time {
fn default() -> Self {
let msg_native = WrappedNativeMsg::<Time>::new();
Time::from_native(&msg_native)
}
}
}

File diff suppressed because one or more lines are too long

View File

@ -1,22 +1,21 @@
diagnostic_msgs.rs
statistics_msgs.rs
map_msgs.rs
stereo_msgs.rs
rosgraph_msgs.rs
trajectory_msgs.rs
lifecycle_msgs.rs
nav_msgs.rs
builtin_interfaces.rs
action_msgs.rs
tf2_msgs.rs
rcl_interfaces.rs
visualization_msgs.rs
shape_msgs.rs
std_msgs.rs
sensor_msgs.rs
pendulum_msgs.rs
geometry_msgs.rs
unique_identifier_msgs.rs
builtin_interfaces.rs
diagnostic_msgs.rs
shape_msgs.rs
lifecycle_msgs.rs
trajectory_msgs.rs
rcl_interfaces.rs
test_msgs.rs
tf2_msgs.rs
nav_msgs.rs
visualization_msgs.rs
sensor_msgs.rs
rosgraph_msgs.rs
statistics_msgs.rs
std_msgs.rs
action_msgs.rs
geometry_msgs.rs
_r2r_generated_msgs.rs
_r2r_generated_untyped_helper.rs
_r2r_generated_service_helper.rs

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1 +1,144 @@
pub mod msg { use super :: super :: * ; # [derive (Clone , Debug , PartialEq , Serialize , Deserialize)] # [serde (default)] pub struct JointCommand { pub position : f64 } impl WrappedTypesupport for JointCommand { type CStruct = pendulum_msgs__msg__JointCommand ; fn get_ts () -> & 'static rosidl_message_type_support_t { unsafe { & * rosidl_typesupport_c__get_message_type_support_handle__pendulum_msgs__msg__JointCommand () } } fn create_msg () -> * mut pendulum_msgs__msg__JointCommand { unsafe { pendulum_msgs__msg__JointCommand__create () } } fn destroy_msg (msg : * mut pendulum_msgs__msg__JointCommand) -> () { unsafe { pendulum_msgs__msg__JointCommand__destroy (msg) } ; } fn from_native (# [allow (unused)] msg : & Self :: CStruct) -> JointCommand { JointCommand { position : msg . position , } } fn copy_to_native (& self , # [allow (unused)] msg : & mut Self :: CStruct) { msg . position = self . position ; } } impl Default for JointCommand { fn default () -> Self { let msg_native = WrappedNativeMsg :: < JointCommand > :: new () ; JointCommand :: from_native (& msg_native) } } # [derive (Clone , Debug , PartialEq , Serialize , Deserialize)] # [serde (default)] pub struct JointState { pub position : f64 , pub velocity : f64 , pub effort : f64 } impl WrappedTypesupport for JointState { type CStruct = pendulum_msgs__msg__JointState ; fn get_ts () -> & 'static rosidl_message_type_support_t { unsafe { & * rosidl_typesupport_c__get_message_type_support_handle__pendulum_msgs__msg__JointState () } } fn create_msg () -> * mut pendulum_msgs__msg__JointState { unsafe { pendulum_msgs__msg__JointState__create () } } fn destroy_msg (msg : * mut pendulum_msgs__msg__JointState) -> () { unsafe { pendulum_msgs__msg__JointState__destroy (msg) } ; } fn from_native (# [allow (unused)] msg : & Self :: CStruct) -> JointState { JointState { position : msg . position , velocity : msg . velocity , effort : msg . effort , } } fn copy_to_native (& self , # [allow (unused)] msg : & mut Self :: CStruct) { msg . position = self . position ; msg . velocity = self . velocity ; msg . effort = self . effort ; } } impl Default for JointState { fn default () -> Self { let msg_native = WrappedNativeMsg :: < JointState > :: new () ; JointState :: from_native (& msg_native) } } # [derive (Clone , Debug , PartialEq , Serialize , Deserialize)] # [serde (default)] pub struct RttestResults { pub stamp : builtin_interfaces :: msg :: Time , pub command : pendulum_msgs :: msg :: JointCommand , pub state : pendulum_msgs :: msg :: JointState , pub cur_latency : u64 , pub mean_latency : f64 , pub min_latency : u64 , pub max_latency : u64 , pub minor_pagefaults : u64 , pub major_pagefaults : u64 } impl WrappedTypesupport for RttestResults { type CStruct = pendulum_msgs__msg__RttestResults ; fn get_ts () -> & 'static rosidl_message_type_support_t { unsafe { & * rosidl_typesupport_c__get_message_type_support_handle__pendulum_msgs__msg__RttestResults () } } fn create_msg () -> * mut pendulum_msgs__msg__RttestResults { unsafe { pendulum_msgs__msg__RttestResults__create () } } fn destroy_msg (msg : * mut pendulum_msgs__msg__RttestResults) -> () { unsafe { pendulum_msgs__msg__RttestResults__destroy (msg) } ; } fn from_native (# [allow (unused)] msg : & Self :: CStruct) -> RttestResults { RttestResults { stamp : builtin_interfaces :: msg :: Time :: from_native (& msg . stamp) , command : pendulum_msgs :: msg :: JointCommand :: from_native (& msg . command) , state : pendulum_msgs :: msg :: JointState :: from_native (& msg . state) , cur_latency : msg . cur_latency , mean_latency : msg . mean_latency , min_latency : msg . min_latency , max_latency : msg . max_latency , minor_pagefaults : msg . minor_pagefaults , major_pagefaults : msg . major_pagefaults , } } fn copy_to_native (& self , # [allow (unused)] msg : & mut Self :: CStruct) { self . stamp . copy_to_native (& mut msg . stamp) ; self . command . copy_to_native (& mut msg . command) ; self . state . copy_to_native (& mut msg . state) ; msg . cur_latency = self . cur_latency ; msg . mean_latency = self . mean_latency ; msg . min_latency = self . min_latency ; msg . max_latency = self . max_latency ; msg . minor_pagefaults = self . minor_pagefaults ; msg . major_pagefaults = self . major_pagefaults ; } } impl Default for RttestResults { fn default () -> Self { let msg_native = WrappedNativeMsg :: < RttestResults > :: new () ; RttestResults :: from_native (& msg_native) } } }
pub mod msg {
use super::super::*;
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
#[serde(default)]
pub struct JointCommand {
pub position: f64,
}
impl WrappedTypesupport for JointCommand {
type CStruct = pendulum_msgs__msg__JointCommand;
fn get_ts() -> &'static rosidl_message_type_support_t {
unsafe {
&*rosidl_typesupport_c__get_message_type_support_handle__pendulum_msgs__msg__JointCommand()
}
}
fn create_msg() -> *mut pendulum_msgs__msg__JointCommand {
#[cfg(not(feature = "doc-only"))]
unsafe { pendulum_msgs__msg__JointCommand__create() }
#[cfg(feature = "doc-only")] pendulum_msgs__msg__JointCommand__create()
}
fn destroy_msg(msg: *mut pendulum_msgs__msg__JointCommand) -> () {
#[cfg(not(feature = "doc-only"))]
unsafe { pendulum_msgs__msg__JointCommand__destroy(msg) };
#[cfg(feature = "doc-only")] pendulum_msgs__msg__JointCommand__destroy(msg)
}
fn from_native(#[allow(unused)] msg: &Self::CStruct) -> JointCommand {
JointCommand {
position: msg.position,
}
}
fn copy_to_native(&self, #[allow(unused)] msg: &mut Self::CStruct) {
msg.position = self.position;
}
}
impl Default for JointCommand {
fn default() -> Self {
let msg_native = WrappedNativeMsg::<JointCommand>::new();
JointCommand::from_native(&msg_native)
}
}
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
#[serde(default)]
pub struct JointState {
pub position: f64,
pub velocity: f64,
pub effort: f64,
}
impl WrappedTypesupport for JointState {
type CStruct = pendulum_msgs__msg__JointState;
fn get_ts() -> &'static rosidl_message_type_support_t {
unsafe {
&*rosidl_typesupport_c__get_message_type_support_handle__pendulum_msgs__msg__JointState()
}
}
fn create_msg() -> *mut pendulum_msgs__msg__JointState {
#[cfg(not(feature = "doc-only"))]
unsafe { pendulum_msgs__msg__JointState__create() }
#[cfg(feature = "doc-only")] pendulum_msgs__msg__JointState__create()
}
fn destroy_msg(msg: *mut pendulum_msgs__msg__JointState) -> () {
#[cfg(not(feature = "doc-only"))]
unsafe { pendulum_msgs__msg__JointState__destroy(msg) };
#[cfg(feature = "doc-only")] pendulum_msgs__msg__JointState__destroy(msg)
}
fn from_native(#[allow(unused)] msg: &Self::CStruct) -> JointState {
JointState {
position: msg.position,
velocity: msg.velocity,
effort: msg.effort,
}
}
fn copy_to_native(&self, #[allow(unused)] msg: &mut Self::CStruct) {
msg.position = self.position;
msg.velocity = self.velocity;
msg.effort = self.effort;
}
}
impl Default for JointState {
fn default() -> Self {
let msg_native = WrappedNativeMsg::<JointState>::new();
JointState::from_native(&msg_native)
}
}
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
#[serde(default)]
pub struct RttestResults {
pub stamp: builtin_interfaces::msg::Time,
pub command: pendulum_msgs::msg::JointCommand,
pub state: pendulum_msgs::msg::JointState,
pub cur_latency: u64,
pub mean_latency: f64,
pub min_latency: u64,
pub max_latency: u64,
pub minor_pagefaults: u64,
pub major_pagefaults: u64,
}
impl WrappedTypesupport for RttestResults {
type CStruct = pendulum_msgs__msg__RttestResults;
fn get_ts() -> &'static rosidl_message_type_support_t {
unsafe {
&*rosidl_typesupport_c__get_message_type_support_handle__pendulum_msgs__msg__RttestResults()
}
}
fn create_msg() -> *mut pendulum_msgs__msg__RttestResults {
#[cfg(not(feature = "doc-only"))]
unsafe { pendulum_msgs__msg__RttestResults__create() }
#[cfg(feature = "doc-only")] pendulum_msgs__msg__RttestResults__create()
}
fn destroy_msg(msg: *mut pendulum_msgs__msg__RttestResults) -> () {
#[cfg(not(feature = "doc-only"))]
unsafe { pendulum_msgs__msg__RttestResults__destroy(msg) };
#[cfg(feature = "doc-only")] pendulum_msgs__msg__RttestResults__destroy(msg)
}
fn from_native(#[allow(unused)] msg: &Self::CStruct) -> RttestResults {
RttestResults {
stamp: builtin_interfaces::msg::Time::from_native(&msg.stamp),
command: pendulum_msgs::msg::JointCommand::from_native(&msg.command),
state: pendulum_msgs::msg::JointState::from_native(&msg.state),
cur_latency: msg.cur_latency,
mean_latency: msg.mean_latency,
min_latency: msg.min_latency,
max_latency: msg.max_latency,
minor_pagefaults: msg.minor_pagefaults,
major_pagefaults: msg.major_pagefaults,
}
}
fn copy_to_native(&self, #[allow(unused)] msg: &mut Self::CStruct) {
self.stamp.copy_to_native(&mut msg.stamp);
self.command.copy_to_native(&mut msg.command);
self.state.copy_to_native(&mut msg.state);
msg.cur_latency = self.cur_latency;
msg.mean_latency = self.mean_latency;
msg.min_latency = self.min_latency;
msg.max_latency = self.max_latency;
msg.minor_pagefaults = self.minor_pagefaults;
msg.major_pagefaults = self.major_pagefaults;
}
}
impl Default for RttestResults {
fn default() -> Self {
let msg_native = WrappedNativeMsg::<RttestResults>::new();
RttestResults::from_native(&msg_native)
}
}
}

File diff suppressed because one or more lines are too long

View File

@ -1 +1,40 @@
pub mod msg { use super :: super :: * ; # [derive (Clone , Debug , PartialEq , Serialize , Deserialize)] # [serde (default)] pub struct Clock { pub clock : builtin_interfaces :: msg :: Time } impl WrappedTypesupport for Clock { type CStruct = rosgraph_msgs__msg__Clock ; fn get_ts () -> & 'static rosidl_message_type_support_t { unsafe { & * rosidl_typesupport_c__get_message_type_support_handle__rosgraph_msgs__msg__Clock () } } fn create_msg () -> * mut rosgraph_msgs__msg__Clock { unsafe { rosgraph_msgs__msg__Clock__create () } } fn destroy_msg (msg : * mut rosgraph_msgs__msg__Clock) -> () { unsafe { rosgraph_msgs__msg__Clock__destroy (msg) } ; } fn from_native (# [allow (unused)] msg : & Self :: CStruct) -> Clock { Clock { clock : builtin_interfaces :: msg :: Time :: from_native (& msg . clock) , } } fn copy_to_native (& self , # [allow (unused)] msg : & mut Self :: CStruct) { self . clock . copy_to_native (& mut msg . clock) ; } } impl Default for Clock { fn default () -> Self { let msg_native = WrappedNativeMsg :: < Clock > :: new () ; Clock :: from_native (& msg_native) } } }
pub mod msg {
use super::super::*;
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
#[serde(default)]
pub struct Clock {
pub clock: builtin_interfaces::msg::Time,
}
impl WrappedTypesupport for Clock {
type CStruct = rosgraph_msgs__msg__Clock;
fn get_ts() -> &'static rosidl_message_type_support_t {
unsafe {
&*rosidl_typesupport_c__get_message_type_support_handle__rosgraph_msgs__msg__Clock()
}
}
fn create_msg() -> *mut rosgraph_msgs__msg__Clock {
#[cfg(not(feature = "doc-only"))]
unsafe { rosgraph_msgs__msg__Clock__create() }
#[cfg(feature = "doc-only")] rosgraph_msgs__msg__Clock__create()
}
fn destroy_msg(msg: *mut rosgraph_msgs__msg__Clock) -> () {
#[cfg(not(feature = "doc-only"))]
unsafe { rosgraph_msgs__msg__Clock__destroy(msg) };
#[cfg(feature = "doc-only")] rosgraph_msgs__msg__Clock__destroy(msg)
}
fn from_native(#[allow(unused)] msg: &Self::CStruct) -> Clock {
Clock {
clock: builtin_interfaces::msg::Time::from_native(&msg.clock),
}
}
fn copy_to_native(&self, #[allow(unused)] msg: &mut Self::CStruct) {
self.clock.copy_to_native(&mut msg.clock);
}
}
impl Default for Clock {
fn default() -> Self {
let msg_native = WrappedNativeMsg::<Clock>::new();
Clock::from_native(&msg_native)
}
}
}

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1 +1,63 @@
pub mod msg { use super :: super :: * ; # [derive (Clone , Debug , PartialEq , Serialize , Deserialize)] # [serde (default)] pub struct DisparityImage { pub header : std_msgs :: msg :: Header , pub image : sensor_msgs :: msg :: Image , pub f : f32 , pub t : f32 , pub valid_window : sensor_msgs :: msg :: RegionOfInterest , pub min_disparity : f32 , pub max_disparity : f32 , pub delta_d : f32 } impl WrappedTypesupport for DisparityImage { type CStruct = stereo_msgs__msg__DisparityImage ; fn get_ts () -> & 'static rosidl_message_type_support_t { unsafe { & * rosidl_typesupport_c__get_message_type_support_handle__stereo_msgs__msg__DisparityImage () } } fn create_msg () -> * mut stereo_msgs__msg__DisparityImage { unsafe { stereo_msgs__msg__DisparityImage__create () } } fn destroy_msg (msg : * mut stereo_msgs__msg__DisparityImage) -> () { unsafe { stereo_msgs__msg__DisparityImage__destroy (msg) } ; } fn from_native (# [allow (unused)] msg : & Self :: CStruct) -> DisparityImage { DisparityImage { header : std_msgs :: msg :: Header :: from_native (& msg . header) , image : sensor_msgs :: msg :: Image :: from_native (& msg . image) , f : msg . f , t : msg . t , valid_window : sensor_msgs :: msg :: RegionOfInterest :: from_native (& msg . valid_window) , min_disparity : msg . min_disparity , max_disparity : msg . max_disparity , delta_d : msg . delta_d , } } fn copy_to_native (& self , # [allow (unused)] msg : & mut Self :: CStruct) { self . header . copy_to_native (& mut msg . header) ; self . image . copy_to_native (& mut msg . image) ; msg . f = self . f ; msg . t = self . t ; self . valid_window . copy_to_native (& mut msg . valid_window) ; msg . min_disparity = self . min_disparity ; msg . max_disparity = self . max_disparity ; msg . delta_d = self . delta_d ; } } impl Default for DisparityImage { fn default () -> Self { let msg_native = WrappedNativeMsg :: < DisparityImage > :: new () ; DisparityImage :: from_native (& msg_native) } } }
pub mod msg {
use super::super::*;
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
#[serde(default)]
pub struct DisparityImage {
pub header: std_msgs::msg::Header,
pub image: sensor_msgs::msg::Image,
pub f: f32,
pub t: f32,
pub valid_window: sensor_msgs::msg::RegionOfInterest,
pub min_disparity: f32,
pub max_disparity: f32,
pub delta_d: f32,
}
impl WrappedTypesupport for DisparityImage {
type CStruct = stereo_msgs__msg__DisparityImage;
fn get_ts() -> &'static rosidl_message_type_support_t {
unsafe {
&*rosidl_typesupport_c__get_message_type_support_handle__stereo_msgs__msg__DisparityImage()
}
}
fn create_msg() -> *mut stereo_msgs__msg__DisparityImage {
#[cfg(not(feature = "doc-only"))]
unsafe { stereo_msgs__msg__DisparityImage__create() }
#[cfg(feature = "doc-only")] stereo_msgs__msg__DisparityImage__create()
}
fn destroy_msg(msg: *mut stereo_msgs__msg__DisparityImage) -> () {
#[cfg(not(feature = "doc-only"))]
unsafe { stereo_msgs__msg__DisparityImage__destroy(msg) };
#[cfg(feature = "doc-only")] stereo_msgs__msg__DisparityImage__destroy(msg)
}
fn from_native(#[allow(unused)] msg: &Self::CStruct) -> DisparityImage {
DisparityImage {
header: std_msgs::msg::Header::from_native(&msg.header),
image: sensor_msgs::msg::Image::from_native(&msg.image),
f: msg.f,
t: msg.t,
valid_window: sensor_msgs::msg::RegionOfInterest::from_native(
&msg.valid_window,
),
min_disparity: msg.min_disparity,
max_disparity: msg.max_disparity,
delta_d: msg.delta_d,
}
}
fn copy_to_native(&self, #[allow(unused)] msg: &mut Self::CStruct) {
self.header.copy_to_native(&mut msg.header);
self.image.copy_to_native(&mut msg.image);
msg.f = self.f;
msg.t = self.t;
self.valid_window.copy_to_native(&mut msg.valid_window);
msg.min_disparity = self.min_disparity;
msg.max_disparity = self.max_disparity;
msg.delta_d = self.delta_d;
}
}
impl Default for DisparityImage {
fn default() -> Self {
let msg_native = WrappedNativeMsg::<DisparityImage>::new();
DisparityImage::from_native(&msg_native)
}
}
}

3769
r2r/bindings/test_msgs.rs Normal file

File diff suppressed because it is too large Load Diff

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -1 +1,42 @@
pub mod msg { use super :: super :: * ; # [derive (Clone , Debug , PartialEq , Serialize , Deserialize)] # [serde (default)] pub struct UUID { pub uuid : Vec < u8 > } impl WrappedTypesupport for UUID { type CStruct = unique_identifier_msgs__msg__UUID ; fn get_ts () -> & 'static rosidl_message_type_support_t { unsafe { & * rosidl_typesupport_c__get_message_type_support_handle__unique_identifier_msgs__msg__UUID () } } fn create_msg () -> * mut unique_identifier_msgs__msg__UUID { unsafe { unique_identifier_msgs__msg__UUID__create () } } fn destroy_msg (msg : * mut unique_identifier_msgs__msg__UUID) -> () { unsafe { unique_identifier_msgs__msg__UUID__destroy (msg) } ; } fn from_native (# [allow (unused)] msg : & Self :: CStruct) -> UUID { UUID { uuid : msg . uuid . to_vec () , } } fn copy_to_native (& self , # [allow (unused)] msg : & mut Self :: CStruct) { assert_eq ! (self . uuid . len () , 16usize , "Field {} is fixed size of {}!" , "uuid" , 16usize) ; msg . uuid . copy_from_slice (& self . uuid [.. 16usize]) ; } } impl Default for UUID { fn default () -> Self { let msg_native = WrappedNativeMsg :: < UUID > :: new () ; UUID :: from_native (& msg_native) } } }
pub mod msg {
use super::super::*;
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
#[serde(default)]
pub struct UUID {
pub uuid: Vec<u8>,
}
impl WrappedTypesupport for UUID {
type CStruct = unique_identifier_msgs__msg__UUID;
fn get_ts() -> &'static rosidl_message_type_support_t {
unsafe {
&*rosidl_typesupport_c__get_message_type_support_handle__unique_identifier_msgs__msg__UUID()
}
}
fn create_msg() -> *mut unique_identifier_msgs__msg__UUID {
#[cfg(not(feature = "doc-only"))]
unsafe { unique_identifier_msgs__msg__UUID__create() }
#[cfg(feature = "doc-only")] unique_identifier_msgs__msg__UUID__create()
}
fn destroy_msg(msg: *mut unique_identifier_msgs__msg__UUID) -> () {
#[cfg(not(feature = "doc-only"))]
unsafe { unique_identifier_msgs__msg__UUID__destroy(msg) };
#[cfg(feature = "doc-only")] unique_identifier_msgs__msg__UUID__destroy(msg)
}
fn from_native(#[allow(unused)] msg: &Self::CStruct) -> UUID {
UUID { uuid: msg.uuid.to_vec() }
}
fn copy_to_native(&self, #[allow(unused)] msg: &mut Self::CStruct) {
assert_eq!(
self.uuid.len(), 16usize, "Field {} is fixed size of {}!", "uuid",
16usize
);
msg.uuid.copy_from_slice(&self.uuid[..16usize]);
}
}
impl Default for UUID {
fn default() -> Self {
let msg_native = WrappedNativeMsg::<UUID>::new();
UUID::from_native(&msg_native)
}
}
}

File diff suppressed because one or more lines are too long

View File

@ -10,52 +10,34 @@ pub const RCL_RET_ACTION_SERVER_TAKE_FAILED: u32 = 2201;
pub const RCL_RET_ACTION_GOAL_HANDLE_INVALID: u32 = 2300;
pub const RCL_RET_ACTION_GOAL_EVENT_INVALID: u32 = 2301;
pub type rcl_action_goal_info_t = action_msgs__msg__GoalInfo;
#[repr(C)]
#[repr(align(8))]
#[derive(Debug, Copy, Clone, PartialEq)]
pub struct rcl_action_goal_status_array_t {
pub _bindgen_opaque_blob: [u64; 8usize],
}
#[test]
fn bindgen_test_layout_rcl_action_goal_status_array_t() {
assert_eq!(
::std::mem::size_of::<rcl_action_goal_status_array_t>(),
64usize,
concat!("Size of: ", stringify!(rcl_action_goal_status_array_t))
);
assert_eq!(
::std::mem::align_of::<rcl_action_goal_status_array_t>(),
8usize,
concat!("Alignment of ", stringify!(rcl_action_goal_status_array_t))
);
}
pub type rcl_action_goal_status_array_t = [u64; 8usize];
pub type rcl_action_cancel_request_t = action_msgs__srv__CancelGoal_Request;
#[repr(C)]
pub struct rcl_action_cancel_response_t {
pub struct rcl_action_cancel_response_s {
pub msg: action_msgs__srv__CancelGoal_Response,
pub allocator: rcl_allocator_t,
}
#[test]
fn bindgen_test_layout_rcl_action_cancel_response_t() {
const UNINIT: ::std::mem::MaybeUninit<rcl_action_cancel_response_t> =
fn bindgen_test_layout_rcl_action_cancel_response_s() {
const UNINIT: ::std::mem::MaybeUninit<rcl_action_cancel_response_s> =
::std::mem::MaybeUninit::uninit();
let ptr = UNINIT.as_ptr();
assert_eq!(
::std::mem::size_of::<rcl_action_cancel_response_t>(),
::std::mem::size_of::<rcl_action_cancel_response_s>(),
72usize,
concat!("Size of: ", stringify!(rcl_action_cancel_response_t))
concat!("Size of: ", stringify!(rcl_action_cancel_response_s))
);
assert_eq!(
::std::mem::align_of::<rcl_action_cancel_response_t>(),
::std::mem::align_of::<rcl_action_cancel_response_s>(),
8usize,
concat!("Alignment of ", stringify!(rcl_action_cancel_response_t))
concat!("Alignment of ", stringify!(rcl_action_cancel_response_s))
);
assert_eq!(
unsafe { ::std::ptr::addr_of!((*ptr).msg) as usize - ptr as usize },
0usize,
concat!(
"Offset of field: ",
stringify!(rcl_action_cancel_response_t),
stringify!(rcl_action_cancel_response_s),
"::",
stringify!(msg)
)
@ -65,16 +47,17 @@ fn bindgen_test_layout_rcl_action_cancel_response_t() {
32usize,
concat!(
"Offset of field: ",
stringify!(rcl_action_cancel_response_t),
stringify!(rcl_action_cancel_response_s),
"::",
stringify!(allocator)
)
);
}
pub type rcl_action_cancel_response_t = rcl_action_cancel_response_s;
pub type rcl_action_goal_state_t = u8;
#[repr(u32)]
#[derive(Debug, Copy, Clone, Hash, PartialEq, Eq)]
pub enum rcl_action_goal_event_t {
pub enum rcl_action_goal_event_e {
GOAL_EVENT_EXECUTE = 0,
GOAL_EVENT_CANCEL_GOAL = 1,
GOAL_EVENT_SUCCEED = 2,
@ -82,6 +65,7 @@ pub enum rcl_action_goal_event_t {
GOAL_EVENT_CANCELED = 4,
GOAL_EVENT_NUM_EVENTS = 5,
}
pub use self::rcl_action_goal_event_e as rcl_action_goal_event_t;
extern "C" {
pub fn rcl_action_get_zero_initialized_goal_info() -> rcl_action_goal_info_t;
}
@ -118,43 +102,8 @@ extern "C" {
cancel_response: *mut rcl_action_cancel_response_t,
) -> rcl_ret_t;
}
#[repr(C)]
#[repr(align(8))]
#[derive(Debug, Copy, Clone, PartialEq)]
pub struct rcl_action_client_t {
pub _bindgen_opaque_blob: u64,
}
#[test]
fn bindgen_test_layout_rcl_action_client_t() {
assert_eq!(
::std::mem::size_of::<rcl_action_client_t>(),
8usize,
concat!("Size of: ", stringify!(rcl_action_client_t))
);
assert_eq!(
::std::mem::align_of::<rcl_action_client_t>(),
8usize,
concat!("Alignment of ", stringify!(rcl_action_client_t))
);
}
#[repr(C)]
#[repr(align(8))]
pub struct rcl_action_client_options_t {
pub _bindgen_opaque_blob: [u64; 60usize],
}
#[test]
fn bindgen_test_layout_rcl_action_client_options_t() {
assert_eq!(
::std::mem::size_of::<rcl_action_client_options_t>(),
480usize,
concat!("Size of: ", stringify!(rcl_action_client_options_t))
);
assert_eq!(
::std::mem::align_of::<rcl_action_client_options_t>(),
8usize,
concat!("Alignment of ", stringify!(rcl_action_client_options_t))
);
}
pub type rcl_action_client_t = u64;
pub type rcl_action_client_options_t = [u64; 60usize];
extern "C" {
pub fn rcl_action_get_zero_initialized_client() -> rcl_action_client_t;
}
@ -250,31 +199,48 @@ extern "C" {
extern "C" {
pub fn rcl_action_client_is_valid(action_client: *const rcl_action_client_t) -> bool;
}
extern "C" {
pub fn rcl_action_client_set_goal_client_callback(
action_client: *const rcl_action_client_t,
callback: rcl_event_callback_t,
user_data: *const ::std::os::raw::c_void,
) -> rcl_ret_t;
}
extern "C" {
pub fn rcl_action_client_set_cancel_client_callback(
action_client: *const rcl_action_client_t,
callback: rcl_event_callback_t,
user_data: *const ::std::os::raw::c_void,
) -> rcl_ret_t;
}
extern "C" {
pub fn rcl_action_client_set_result_client_callback(
action_client: *const rcl_action_client_t,
callback: rcl_event_callback_t,
user_data: *const ::std::os::raw::c_void,
) -> rcl_ret_t;
}
extern "C" {
pub fn rcl_action_client_set_feedback_subscription_callback(
action_client: *const rcl_action_client_t,
callback: rcl_event_callback_t,
user_data: *const ::std::os::raw::c_void,
) -> rcl_ret_t;
}
extern "C" {
pub fn rcl_action_client_set_status_subscription_callback(
action_client: *const rcl_action_client_t,
callback: rcl_event_callback_t,
user_data: *const ::std::os::raw::c_void,
) -> rcl_ret_t;
}
extern "C" {
pub fn rcl_action_transition_goal_state(
state: rcl_action_goal_state_t,
event: rcl_action_goal_event_t,
) -> rcl_action_goal_state_t;
}
#[repr(C)]
#[repr(align(8))]
#[derive(Debug, Copy, Clone, PartialEq)]
pub struct rcl_action_goal_handle_t {
pub _bindgen_opaque_blob: u64,
}
#[test]
fn bindgen_test_layout_rcl_action_goal_handle_t() {
assert_eq!(
::std::mem::size_of::<rcl_action_goal_handle_t>(),
8usize,
concat!("Size of: ", stringify!(rcl_action_goal_handle_t))
);
assert_eq!(
::std::mem::align_of::<rcl_action_goal_handle_t>(),
8usize,
concat!("Alignment of ", stringify!(rcl_action_goal_handle_t))
);
}
pub type rcl_action_goal_handle_t = u64;
extern "C" {
pub fn rcl_action_get_zero_initialized_goal_handle() -> rcl_action_goal_handle_t;
}
@ -317,43 +283,8 @@ extern "C" {
extern "C" {
pub fn rcl_action_goal_handle_is_valid(goal_handle: *const rcl_action_goal_handle_t) -> bool;
}
#[repr(C)]
#[repr(align(8))]
#[derive(Debug, Copy, Clone, PartialEq)]
pub struct rcl_action_server_t {
pub _bindgen_opaque_blob: u64,
}
#[test]
fn bindgen_test_layout_rcl_action_server_t() {
assert_eq!(
::std::mem::size_of::<rcl_action_server_t>(),
8usize,
concat!("Size of: ", stringify!(rcl_action_server_t))
);
assert_eq!(
::std::mem::align_of::<rcl_action_server_t>(),
8usize,
concat!("Alignment of ", stringify!(rcl_action_server_t))
);
}
#[repr(C)]
#[repr(align(8))]
pub struct rcl_action_server_options_t {
pub _bindgen_opaque_blob: [u64; 61usize],
}
#[test]
fn bindgen_test_layout_rcl_action_server_options_t() {
assert_eq!(
::std::mem::size_of::<rcl_action_server_options_t>(),
488usize,
concat!("Size of: ", stringify!(rcl_action_server_options_t))
);
assert_eq!(
::std::mem::align_of::<rcl_action_server_options_t>(),
8usize,
concat!("Alignment of ", stringify!(rcl_action_server_options_t))
);
}
pub type rcl_action_server_t = u64;
pub type rcl_action_server_options_t = [u64; 61usize];
extern "C" {
pub fn rcl_action_get_zero_initialized_server() -> rcl_action_server_t;
}
@ -491,6 +422,27 @@ extern "C" {
action_server: *const rcl_action_server_t,
) -> bool;
}
extern "C" {
pub fn rcl_action_server_set_goal_service_callback(
action_server: *const rcl_action_server_t,
callback: rcl_event_callback_t,
user_data: *const ::std::os::raw::c_void,
) -> rcl_ret_t;
}
extern "C" {
pub fn rcl_action_server_set_cancel_service_callback(
action_server: *const rcl_action_server_t,
callback: rcl_event_callback_t,
user_data: *const ::std::os::raw::c_void,
) -> rcl_ret_t;
}
extern "C" {
pub fn rcl_action_server_set_result_service_callback(
action_server: *const rcl_action_server_t,
callback: rcl_event_callback_t,
user_data: *const ::std::os::raw::c_void,
) -> rcl_ret_t;
}
extern "C" {
pub fn rcl_action_get_client_names_and_types_by_node(
node: *const rcl_node_t,

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because it is too large Load Diff

File diff suppressed because one or more lines are too long

View File

@ -94,26 +94,6 @@
#include <lifecycle_msgs/srv/get_available_states.h>
#include <lifecycle_msgs/srv/get_available_transitions.h>
#include <lifecycle_msgs/srv/get_state.h>
#include <map_msgs/msg/detail/occupancy_grid_update__rosidl_typesupport_introspection_c.h>
#include <map_msgs/msg/detail/point_cloud2_update__rosidl_typesupport_introspection_c.h>
#include <map_msgs/msg/detail/projected_map__rosidl_typesupport_introspection_c.h>
#include <map_msgs/msg/detail/projected_map_info__rosidl_typesupport_introspection_c.h>
#include <map_msgs/msg/occupancy_grid_update.h>
#include <map_msgs/msg/point_cloud2_update.h>
#include <map_msgs/msg/projected_map.h>
#include <map_msgs/msg/projected_map_info.h>
#include <map_msgs/srv/detail/get_map_roi__rosidl_typesupport_introspection_c.h>
#include <map_msgs/srv/detail/get_point_map__rosidl_typesupport_introspection_c.h>
#include <map_msgs/srv/detail/get_point_map_roi__rosidl_typesupport_introspection_c.h>
#include <map_msgs/srv/detail/projected_maps_info__rosidl_typesupport_introspection_c.h>
#include <map_msgs/srv/detail/save_map__rosidl_typesupport_introspection_c.h>
#include <map_msgs/srv/detail/set_map_projections__rosidl_typesupport_introspection_c.h>
#include <map_msgs/srv/get_map_roi.h>
#include <map_msgs/srv/get_point_map.h>
#include <map_msgs/srv/get_point_map_roi.h>
#include <map_msgs/srv/projected_maps_info.h>
#include <map_msgs/srv/save_map.h>
#include <map_msgs/srv/set_map_projections.h>
#include <nav_msgs/msg/detail/grid_cells__rosidl_typesupport_introspection_c.h>
#include <nav_msgs/msg/detail/map_meta_data__rosidl_typesupport_introspection_c.h>
#include <nav_msgs/msg/detail/occupancy_grid__rosidl_typesupport_introspection_c.h>
@ -132,12 +112,6 @@
#include <nav_msgs/srv/get_plan.h>
#include <nav_msgs/srv/load_map.h>
#include <nav_msgs/srv/set_map.h>
#include <pendulum_msgs/msg/detail/joint_command__rosidl_typesupport_introspection_c.h>
#include <pendulum_msgs/msg/detail/joint_state__rosidl_typesupport_introspection_c.h>
#include <pendulum_msgs/msg/detail/rttest_results__rosidl_typesupport_introspection_c.h>
#include <pendulum_msgs/msg/joint_command.h>
#include <pendulum_msgs/msg/joint_state.h>
#include <pendulum_msgs/msg/rttest_results.h>
#include <rcl_interfaces/msg/detail/floating_point_range__rosidl_typesupport_introspection_c.h>
#include <rcl_interfaces/msg/detail/integer_range__rosidl_typesupport_introspection_c.h>
#include <rcl_interfaces/msg/detail/list_parameters_result__rosidl_typesupport_introspection_c.h>
@ -306,6 +280,42 @@
#include <std_msgs/msg/u_int8_multi_array.h>
#include <stereo_msgs/msg/detail/disparity_image__rosidl_typesupport_introspection_c.h>
#include <stereo_msgs/msg/disparity_image.h>
#include <test_msgs/action/detail/fibonacci__rosidl_typesupport_introspection_c.h>
#include <test_msgs/action/detail/nested_message__rosidl_typesupport_introspection_c.h>
#include <test_msgs/action/fibonacci.h>
#include <test_msgs/action/nested_message.h>
#include <test_msgs/msg/arrays.h>
#include <test_msgs/msg/basic_types.h>
#include <test_msgs/msg/bounded_plain_sequences.h>
#include <test_msgs/msg/bounded_sequences.h>
#include <test_msgs/msg/builtins.h>
#include <test_msgs/msg/constants.h>
#include <test_msgs/msg/defaults.h>
#include <test_msgs/msg/detail/arrays__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/basic_types__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/bounded_plain_sequences__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/bounded_sequences__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/builtins__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/constants__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/defaults__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/empty__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/multi_nested__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/nested__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/strings__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/unbounded_sequences__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/detail/w_strings__rosidl_typesupport_introspection_c.h>
#include <test_msgs/msg/empty.h>
#include <test_msgs/msg/multi_nested.h>
#include <test_msgs/msg/nested.h>
#include <test_msgs/msg/strings.h>
#include <test_msgs/msg/unbounded_sequences.h>
#include <test_msgs/msg/w_strings.h>
#include <test_msgs/srv/arrays.h>
#include <test_msgs/srv/basic_types.h>
#include <test_msgs/srv/detail/arrays__rosidl_typesupport_introspection_c.h>
#include <test_msgs/srv/detail/basic_types__rosidl_typesupport_introspection_c.h>
#include <test_msgs/srv/detail/empty__rosidl_typesupport_introspection_c.h>
#include <test_msgs/srv/empty.h>
#include <tf2_msgs/action/detail/lookup_transform__rosidl_typesupport_introspection_c.h>
#include <tf2_msgs/action/lookup_transform.h>
#include <tf2_msgs/msg/detail/tf2_error__rosidl_typesupport_introspection_c.h>
@ -334,6 +344,8 @@
#include <visualization_msgs/msg/detail/marker__rosidl_typesupport_introspection_c.h>
#include <visualization_msgs/msg/detail/marker_array__rosidl_typesupport_introspection_c.h>
#include <visualization_msgs/msg/detail/menu_entry__rosidl_typesupport_introspection_c.h>
#include <visualization_msgs/msg/detail/mesh_file__rosidl_typesupport_introspection_c.h>
#include <visualization_msgs/msg/detail/uv_coordinate__rosidl_typesupport_introspection_c.h>
#include <visualization_msgs/msg/image_marker.h>
#include <visualization_msgs/msg/interactive_marker.h>
#include <visualization_msgs/msg/interactive_marker_control.h>
@ -344,5 +356,7 @@
#include <visualization_msgs/msg/marker.h>
#include <visualization_msgs/msg/marker_array.h>
#include <visualization_msgs/msg/menu_entry.h>
#include <visualization_msgs/msg/mesh_file.h>
#include <visualization_msgs/msg/uv_coordinate.h>
#include <visualization_msgs/srv/detail/get_interactive_markers__rosidl_typesupport_introspection_c.h>
#include <visualization_msgs/srv/get_interactive_markers.h>

File diff suppressed because it is too large Load Diff