diff --git a/CHANGELOG.md b/CHANGELOG.md index 8c7182c3..043ae171 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -24,7 +24,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ### Added ### Fixed -- Bug with ros1 native publishers not parsing connection headers correctly +- Bug with message_definitions provided by Publisher in the connection header not being the fully expanded definition. ### Changed diff --git a/roslibrust/examples/ros1_talker.rs b/roslibrust/examples/ros1_talker.rs index 315e03ab..b8736b9a 100644 --- a/roslibrust/examples/ros1_talker.rs +++ b/roslibrust/examples/ros1_talker.rs @@ -1,4 +1,4 @@ -roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces/std_msgs"); +roslibrust_codegen_macro::find_and_generate_ros_messages!("assets/ros1_common_interfaces"); #[cfg(feature = "ros1")] #[tokio::main] @@ -14,14 +14,14 @@ async fn main() -> Result<(), anyhow::Error> { let nh = NodeHandle::new("http://localhost:11311", "talker_rs") .await .map_err(|err| err)?; - let publisher = nh.advertise::("/chatter", 1).await?; + let publisher = nh + .advertise::("/my_point", 1) + .await?; for count in 0..50 { - publisher - .publish(&std_msgs::String { - data: format!("hello world from rust {count}"), - }) - .await?; + let mut msg = geometry_msgs::PointStamped::default(); + msg.point.x = count as f64; + publisher.publish(&msg).await?; tokio::time::sleep(tokio::time::Duration::from_secs(1)).await; } diff --git a/roslibrust/src/ros1/publisher.rs b/roslibrust/src/ros1/publisher.rs index f9db4129..4ae40171 100644 --- a/roslibrust/src/ros1/publisher.rs +++ b/roslibrust/src/ros1/publisher.rs @@ -10,7 +10,7 @@ use std::{ sync::Arc, }; use tokio::{ - io::{AsyncReadExt, AsyncWriteExt}, + io::AsyncWriteExt, sync::{mpsc, RwLock}, }; @@ -82,6 +82,7 @@ impl Publication { tcp_nodelay: false, service: None, }; + log::trace!("Publisher connection header: {responding_conn_header:?}"); let subscriber_streams = Arc::new(RwLock::new(Vec::new())); diff --git a/roslibrust/src/ros1/tcpros.rs b/roslibrust/src/ros1/tcpros.rs index 1c90ce64..acb325bb 100644 --- a/roslibrust/src/ros1/tcpros.rs +++ b/roslibrust/src/ros1/tcpros.rs @@ -176,7 +176,7 @@ pub async fn establish_connection( server_uri: &str, conn_header: ConnectionHeader, ) -> Result { - use tokio::io::{AsyncReadExt, AsyncWriteExt}; + use tokio::io::AsyncWriteExt; // Okay in Shane's version of this the server_uri is coming in as "rosrpc://localhost:41105" // which is causing this to break... diff --git a/roslibrust_codegen/src/gen.rs b/roslibrust_codegen/src/gen.rs index 118eef11..ffc369db 100644 --- a/roslibrust_codegen/src/gen.rs +++ b/roslibrust_codegen/src/gen.rs @@ -50,6 +50,12 @@ pub fn generate_service(service: ServiceFile) -> Result { }) } +/// Turns a string into a TokenStream that represents a raw string literal of the string +pub fn generate_raw_string_literal(value: &str) -> TokenStream { + let wrapped = format!("r#\"{}\"#", value); + TokenStream::from_str(&wrapped).unwrap() +} + pub fn generate_struct(msg: MessageFile) -> Result { let ros_type_name = msg.get_full_name(); let attrs = derive_attrs(); @@ -80,7 +86,10 @@ pub fn generate_struct(msg: MessageFile) -> Result { let struct_name = format_ident!("{}", msg.parsed.name); let md5sum = msg.md5sum; - let definition = msg.parsed.source.trim(); + let definition = msg.definition; + + // Raw here is only used to make the generated code look better. + let raw_message_definition = generate_raw_string_literal(&definition); let mut base = quote! { #[allow(non_snake_case)] @@ -92,7 +101,7 @@ pub fn generate_struct(msg: MessageFile) -> Result { impl ::roslibrust_codegen::RosMessageType for #struct_name { const ROS_TYPE_NAME: &'static str = #ros_type_name; const MD5SUM: &'static str = #md5sum; - const DEFINITION: &'static str = #definition; + const DEFINITION: &'static str = #raw_message_definition; } }; diff --git a/roslibrust_codegen/src/lib.rs b/roslibrust_codegen/src/lib.rs index 77914266..c9b3b2e7 100644 --- a/roslibrust_codegen/src/lib.rs +++ b/roslibrust_codegen/src/lib.rs @@ -2,7 +2,7 @@ use log::*; use proc_macro2::TokenStream; use quote::quote; use simple_error::{bail, SimpleError as Error}; -use std::collections::{BTreeMap, VecDeque}; +use std::collections::{BTreeMap, BTreeSet, VecDeque}; use std::fmt::{Debug, Display}; use std::path::PathBuf; use utils::Package; @@ -68,16 +68,23 @@ pub trait RosServiceType { pub struct MessageFile { pub(crate) parsed: ParsedMessageFile, pub(crate) md5sum: String, + // This is the expanded definition of the message for use in message_definition field of + // a connection header. + // See how https://wiki.ros.org/ROS/TCPROS references gendeps --cat + // See https://wiki.ros.org/roslib/gentools for an example of the output + pub(crate) definition: String, pub(crate) is_fixed_length: bool, } impl MessageFile { fn resolve(parsed: ParsedMessageFile, graph: &BTreeMap) -> Option { let md5sum = Self::compute_md5sum(&parsed, graph)?; + let definition = Self::compute_full_definition(&parsed, graph)?; let is_fixed_length = Self::determine_if_fixed_length(&parsed, graph)?; Some(MessageFile { parsed, md5sum, + definition, is_fixed_length, }) } @@ -111,7 +118,7 @@ impl MessageFile { } pub fn get_definition(&self) -> &str { - &self.parsed.source + &self.definition } fn compute_md5sum( @@ -159,6 +166,54 @@ impl MessageFile { Some(md5sum_content) } + /// Returns the set of all referenced non-intrinsic field types in this type or any of its dependencies + fn get_unique_field_types( + parsed: &ParsedMessageFile, + graph: &BTreeMap, + ) -> Option> { + let mut unique_field_types = BTreeSet::new(); + for field in &parsed.fields { + let field_type = field.field_type.field_type.as_str(); + if is_intrinsic_type(parsed.version.unwrap_or(RosVersion::ROS1), field_type) { + continue; + } + let sub_message = graph.get(field.get_full_name().as_str())?; + // Note: need to add both the field that is referenced AND its sub-dependencies + unique_field_types.insert(field.get_full_name()); + let mut sub_deps = Self::get_unique_field_types(&sub_message.parsed, graph)?; + unique_field_types.append(&mut sub_deps); + } + Some(unique_field_types) + } + + /// Computes the full definition of the message, including all referenced custom types + /// For reference see: https://wiki.ros.org/roslib/gentools + /// Implementation in gentools: https://github.com/strawlab/ros/blob/c3a8785f9d9551cc05cd74000c6536e2244bb1b1/core/roslib/src/roslib/gentools.py#L245 + fn compute_full_definition( + parsed: &ParsedMessageFile, + graph: &BTreeMap, + ) -> Option { + let mut definition_content = String::new(); + definition_content.push_str(&format!("{}\n", parsed.source.trim())); + let sep: &str = + "================================================================================\n"; + for field in Self::get_unique_field_types(parsed, graph)? { + let Some(sub_message) = graph.get(&field) else { + log::error!( + "Unable to find message type: {field:?}, while computing full definition of {}", + parsed.get_full_name() + ); + return None; + }; + definition_content.push_str(sep); + definition_content.push_str(&format!("MSG: {}\n", sub_message.get_full_name())); + definition_content.push_str(&format!("{}\n", sub_message.get_definition().trim())); + } + // Remove trailing \n added by concatenation logic + definition_content.pop(); + Some(definition_content) + } + fn determine_if_fixed_length( parsed: &ParsedMessageFile, graph: &BTreeMap, @@ -278,8 +333,11 @@ impl From for RosLiteral { #[derive(PartialEq, Eq, Hash, Debug, Clone)] pub struct FieldType { // Present when an externally referenced package is used - // Note: support for messages within same package is spotty... pub package_name: Option, + // Redundantly store the name of the package the field is in + // This is so that when an external package_name is not present + // we can still construct the full name of the field "package/field_type" + pub source_package: String, // Explicit text of type without array specifier pub field_type: String, // Metadata indicating whether the field is a collection. @@ -321,7 +379,7 @@ impl FieldInfo { .field_type .package_name .as_ref() - .expect(&format!("Expected package name for field {self:#?}")); + .unwrap_or(&self.field_type.source_package); format!("{field_package}/{}", self.field_type.field_type) } } @@ -648,7 +706,6 @@ fn parse_ros_files( "srv" => { let srv_file = parse_ros_service_file(&contents, name, &pkg, &path)?; parsed_services.push(srv_file); - // TODO ask shane, shouldn't we be pushing request and response to messages here? } "msg" => { let msg = parse_ros_message_file(&contents, name, &pkg, &path)?; diff --git a/roslibrust_codegen/src/parse/mod.rs b/roslibrust_codegen/src/parse/mod.rs index 5859c027..ee716014 100644 --- a/roslibrust_codegen/src/parse/mod.rs +++ b/roslibrust_codegen/src/parse/mod.rs @@ -156,6 +156,7 @@ fn parse_field_type(type_str: &str, array_info: Option>, pkg: &Pac Some(pkg.name.clone()) } }, + source_package: pkg.name.clone(), field_type: items[0].to_string(), array_info, } @@ -166,12 +167,14 @@ fn parse_field_type(type_str: &str, array_info: Option>, pkg: &Pac if items[0] == "builtin_interfaces" { FieldType { package_name: None, + source_package: pkg.name.clone(), field_type: type_str.to_string(), array_info, } } else { FieldType { package_name: Some(items[0].to_string()), + source_package: pkg.name.clone(), field_type: items[1].to_string(), array_info, } diff --git a/roslibrust_genmsg/test_package/include/geometry_msgs/Polygon.h b/roslibrust_genmsg/test_package/include/geometry_msgs/Polygon.h index a6352eaa..7ea9c0c5 100644 --- a/roslibrust_genmsg/test_package/include/geometry_msgs/Polygon.h +++ b/roslibrust_genmsg/test_package/include/geometry_msgs/Polygon.h @@ -133,7 +133,19 @@ struct Definition< ::geometry_msgs::Polygon_> { return "#A specification of a polygon where the first and last points are assumed to be connected" "Point32[] points" -""; +"================================================================================" +"MSG: geometry_msgs/Point32" +"# This contains the position of a point in free space(with 32 bits of precision)." +"# It is recommeded to use Point wherever possible instead of Point32. " +"# " +"# This recommendation is to promote interoperability. " +"#" +"# This message is designed to take up less space when sending" +"# lots of points at once, as in the case of a PointCloud. " +"" +"float32 x" +"float32 y" +"float32 z"; } static const char* value(const ::geometry_msgs::Polygon_&) { return value(); } diff --git a/roslibrust_genmsg/test_package/include/sensor_msgs/BatteryState.h b/roslibrust_genmsg/test_package/include/sensor_msgs/BatteryState.h index 34bfac35..9a25fa09 100644 --- a/roslibrust_genmsg/test_package/include/sensor_msgs/BatteryState.h +++ b/roslibrust_genmsg/test_package/include/sensor_msgs/BatteryState.h @@ -244,8 +244,7 @@ struct Definition< ::sensor_msgs::BatteryState_> { static constexpr char const* value() { - return "" -"# Constants are chosen to match the enums in the linux kernel" + return "# Constants are chosen to match the enums in the linux kernel" "# defined in include/linux/power_supply.h as of version 3.7" "# The one difference is for style reasons the constants are" "# all uppercase not mixed case." @@ -296,7 +295,21 @@ struct Definition< ::sensor_msgs::BatteryState_> " # If individual temperatures unknown but number of cells known set each to NaN" "string location # The location into which the battery is inserted. (slot number or plug)" "string serial_number # The best approximation of the battery serial number" -""; +"================================================================================" +"MSG: std_msgs/Header" +"# Standard metadata for higher-level stamped data types." +"# This is generally used to communicate timestamped data " +"# in a particular coordinate frame." +"# " +"# sequence ID: consecutively increasing ID " +"uint32 seq" +"#Two-integer timestamp that is expressed as:" +"# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')" +"# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')" +"# time-handling sugar is provided by the client library" +"time stamp" +"#Frame this data is associated with" +"string frame_id"; } static const char* value(const ::sensor_msgs::BatteryState_&) { return value(); } diff --git a/roslibrust_genmsg/test_package/include/sensor_msgs/CameraInfo.h b/roslibrust_genmsg/test_package/include/sensor_msgs/CameraInfo.h index fbd40fe2..fa7f1dd8 100644 --- a/roslibrust_genmsg/test_package/include/sensor_msgs/CameraInfo.h +++ b/roslibrust_genmsg/test_package/include/sensor_msgs/CameraInfo.h @@ -323,7 +323,42 @@ struct Definition< ::sensor_msgs::CameraInfo_> "# The default setting of roi (all values 0) is considered the same as" "# full resolution (roi.width = width, roi.height = height)." "RegionOfInterest roi" -""; +"================================================================================" +"MSG: sensor_msgs/RegionOfInterest" +"# This message is used to specify a region of interest within an image." +"#" +"# When used to specify the ROI setting of the camera when the image was" +"# taken, the height and width fields should either match the height and" +"# width fields for the associated image; or height = width = 0" +"# indicates that the full resolution image was captured." +"" +"uint32 x_offset # Leftmost pixel of the ROI" +" # (0 if the ROI includes the left edge of the image)" +"uint32 y_offset # Topmost pixel of the ROI" +" # (0 if the ROI includes the top edge of the image)" +"uint32 height # Height of ROI" +"uint32 width # Width of ROI" +"" +"# True if a distinct rectified ROI should be calculated from the \"raw\"" +"# ROI in this message. Typically this should be False if the full image" +"# is captured (ROI not used), and True if a subwindow is captured (ROI" +"# used)." +"bool do_rectify" +"================================================================================" +"MSG: std_msgs/Header" +"# Standard metadata for higher-level stamped data types." +"# This is generally used to communicate timestamped data " +"# in a particular coordinate frame." +"# " +"# sequence ID: consecutively increasing ID " +"uint32 seq" +"#Two-integer timestamp that is expressed as:" +"# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')" +"# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')" +"# time-handling sugar is provided by the client library" +"time stamp" +"#Frame this data is associated with" +"string frame_id"; } static const char* value(const ::sensor_msgs::CameraInfo_&) { return value(); } diff --git a/roslibrust_genmsg/test_package/include/std_msgs/Header.h b/roslibrust_genmsg/test_package/include/std_msgs/Header.h index eeda03b0..f429d1a1 100644 --- a/roslibrust_genmsg/test_package/include/std_msgs/Header.h +++ b/roslibrust_genmsg/test_package/include/std_msgs/Header.h @@ -154,8 +154,7 @@ struct Definition< ::std_msgs::Header_> "# time-handling sugar is provided by the client library" "time stamp" "#Frame this data is associated with" -"string frame_id" -""; +"string frame_id"; } static const char* value(const ::std_msgs::Header_&) { return value(); } diff --git a/roslibrust_genmsg/test_package/include/std_srvs/TriggerResponse.h b/roslibrust_genmsg/test_package/include/std_srvs/TriggerResponse.h index f77af60b..67a6d39b 100644 --- a/roslibrust_genmsg/test_package/include/std_srvs/TriggerResponse.h +++ b/roslibrust_genmsg/test_package/include/std_srvs/TriggerResponse.h @@ -137,8 +137,7 @@ struct Definition< ::std_srvs::TriggerResponse_> static constexpr char const* value() { return "bool success # indicate successful run of triggered service" -"string message # informational, e.g. for error messages" -""; +"string message # informational, e.g. for error messages"; } static const char* value(const ::std_srvs::TriggerResponse_&) { return value(); } diff --git a/roslibrust_genmsg/test_package/include/test_package/Test.h b/roslibrust_genmsg/test_package/include/test_package/Test.h index ba3d3ef2..c24c732b 100644 --- a/roslibrust_genmsg/test_package/include/test_package/Test.h +++ b/roslibrust_genmsg/test_package/include/test_package/Test.h @@ -162,7 +162,35 @@ struct Definition< ::test_package::Test_> "string STOPPED_STATE = \"STOPPED\"" "" "string test_a" -"Header header"; +"Header header" +"================================================================================" +"MSG: geometry_msgs/Point32" +"# This contains the position of a point in free space(with 32 bits of precision)." +"# It is recommeded to use Point wherever possible instead of Point32. " +"# " +"# This recommendation is to promote interoperability. " +"#" +"# This message is designed to take up less space when sending" +"# lots of points at once, as in the case of a PointCloud. " +"" +"float32 x" +"float32 y" +"float32 z" +"================================================================================" +"MSG: std_msgs/Header" +"# Standard metadata for higher-level stamped data types." +"# This is generally used to communicate timestamped data " +"# in a particular coordinate frame." +"# " +"# sequence ID: consecutively increasing ID " +"uint32 seq" +"#Two-integer timestamp that is expressed as:" +"# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')" +"# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')" +"# time-handling sugar is provided by the client library" +"time stamp" +"#Frame this data is associated with" +"string frame_id"; } static const char* value(const ::test_package::Test_&) { return value(); } diff --git a/roslibrust_test/src/ros1.rs b/roslibrust_test/src/ros1.rs index 355954ec..1f2e3b56 100644 --- a/roslibrust_test/src/ros1.rs +++ b/roslibrust_test/src/ros1.rs @@ -30,7 +30,15 @@ pub mod actionlib_msgs { impl ::roslibrust_codegen::RosMessageType for GoalID { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalID"; const MD5SUM: &'static str = "302881f31927c1df708a2dbab0e80ee8"; - const DEFINITION : & 'static str = "# The stamp should store the time at which this goal was requested.\n# It is used by an action server when it tries to preempt all\n# goals that were requested before a certain time\ntime stamp\n\n# The id provides a way to associate feedback and\n# result message with specific goal requests. The id\n# specified must be unique.\nstring id" ; + const DEFINITION: &'static str = r#"# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id"#; } #[allow(non_snake_case)] #[derive( @@ -50,7 +58,39 @@ pub mod actionlib_msgs { impl ::roslibrust_codegen::RosMessageType for GoalStatus { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalStatus"; const MD5SUM: &'static str = "d388f9b87b3c471f784434d671988d4a"; - const DEFINITION : & 'static str = "GoalID goal_id\nuint8 status\nuint8 PENDING = 0 # The goal has yet to be processed by the action server\nuint8 ACTIVE = 1 # The goal is currently being processed by the action server\nuint8 PREEMPTED = 2 # The goal received a cancel request after it started executing\n # and has since completed its execution (Terminal State)\nuint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)\nuint8 ABORTED = 4 # The goal was aborted during execution by the action server due\n # to some failure (Terminal State)\nuint8 REJECTED = 5 # The goal was rejected by the action server without being processed,\n # because the goal was unattainable or invalid (Terminal State)\nuint8 PREEMPTING = 6 # The goal received a cancel request after it started executing\n # and has not yet completed execution\nuint8 RECALLING = 7 # The goal received a cancel request before it started executing,\n # but the action server has not yet confirmed that the goal is canceled\nuint8 RECALLED = 8 # The goal received a cancel request before it started executing\n # and was successfully cancelled (Terminal State)\nuint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be\n # sent over the wire by an action server\n\n#Allow for the user to associate a string with GoalStatus for debugging\nstring text" ; + const DEFINITION: &'static str = r#"GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server +uint8 ACTIVE = 1 # The goal is currently being processed by the action server +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State) +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State) +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State) +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, + # but the action server has not yet confirmed that the goal is canceled +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State) +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be + # sent over the wire by an action server + +#Allow for the user to associate a string with GoalStatus for debugging +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id"#; } impl GoalStatus { pub const r#PENDING: u8 = 0u8; @@ -81,7 +121,71 @@ pub mod actionlib_msgs { impl ::roslibrust_codegen::RosMessageType for GoalStatusArray { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalStatusArray"; const MD5SUM: &'static str = "8b2b82f13216d0a8ea88bd3af735e619"; - const DEFINITION : & 'static str = "# Stores the statuses for goals that are currently being tracked\n# by an action server\nHeader header\nGoalStatus[] status_list" ; + const DEFINITION: &'static str = r#"# Stores the statuses for goals that are currently being tracked +# by an action server +Header header +GoalStatus[] status_list +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: actionlib_msgs/GoalStatus +GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server +uint8 ACTIVE = 1 # The goal is currently being processed by the action server +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State) +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State) +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State) +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, + # but the action server has not yet confirmed that the goal is canceled +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State) +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be + # sent over the wire by an action server + +#Allow for the user to associate a string with GoalStatus for debugging +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } } #[allow(unused_imports)] @@ -116,7 +220,48 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for DiagnosticArray { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/DiagnosticArray"; const MD5SUM: &'static str = "60810da900de1dd6ddd437c3503511da"; - const DEFINITION : & 'static str = "# This message is used to send diagnostic information about the state of the robot\nHeader header #for timestamp\nDiagnosticStatus[] status # an array of components being reported on" ; + const DEFINITION: &'static str = r#"# This message is used to send diagnostic information about the state of the robot +Header header #for timestamp +DiagnosticStatus[] status # an array of components being reported on +================================================================================ +MSG: diagnostic_msgs/DiagnosticStatus +# This message holds the status of an individual component of the robot. +# + +# Possible levels of operations +byte OK=0 +byte WARN=1 +byte ERROR=2 +byte STALE=3 + +byte level # level of operation enumerated above +string name # a description of the test/component reporting +string message # a description of the status +string hardware_id # a hardware unique string +KeyValue[] values # an array of values associated with the status +================================================================================ +MSG: diagnostic_msgs/KeyValue +string key # what to label this value when viewing +string value # a value to track over time +================================================================================ +MSG: diagnostic_msgs/KeyValue +string key # what to label this value when viewing +string value # a value to track over time +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -138,7 +283,24 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for DiagnosticStatus { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/DiagnosticStatus"; const MD5SUM: &'static str = "d0ce08bc6e5ba34c7754f563a9cabaf1"; - const DEFINITION : & 'static str = "# This message holds the status of an individual component of the robot.\n# \n\n# Possible levels of operations\nbyte OK=0\nbyte WARN=1\nbyte ERROR=2\nbyte STALE=3\n\nbyte level # level of operation enumerated above \nstring name # a description of the test/component reporting\nstring message # a description of the status\nstring hardware_id # a hardware unique string\nKeyValue[] values # an array of values associated with the status" ; + const DEFINITION: &'static str = r#"# This message holds the status of an individual component of the robot. +# + +# Possible levels of operations +byte OK=0 +byte WARN=1 +byte ERROR=2 +byte STALE=3 + +byte level # level of operation enumerated above +string name # a description of the test/component reporting +string message # a description of the status +string hardware_id # a hardware unique string +KeyValue[] values # an array of values associated with the status +================================================================================ +MSG: diagnostic_msgs/KeyValue +string key # what to label this value when viewing +string value # a value to track over time"#; } impl DiagnosticStatus { pub const r#OK: u8 = 0u8; @@ -163,7 +325,8 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for KeyValue { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/KeyValue"; const MD5SUM: &'static str = "cf57fdc6617a881a88c16e768132149c"; - const DEFINITION : & 'static str = "string key # what to label this value when viewing\nstring value # a value to track over time" ; + const DEFINITION: &'static str = r#"string key # what to label this value when viewing +string value # a value to track over time"#; } #[allow(non_snake_case)] #[derive( @@ -181,7 +344,23 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for AddDiagnosticsRequest { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/AddDiagnosticsRequest"; const MD5SUM: &'static str = "c26cf6e164288fbc6050d74f838bcdf0"; - const DEFINITION : & 'static str = "# This service is used as part of the process for loading analyzers at runtime,\n# and should be used by a loader script or program, not as a standalone service.\n# Information about dynamic addition of analyzers can be found at\n# http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime\n\n# The load_namespace parameter defines the namespace where parameters for the\n# initialization of analyzers in the diagnostic aggregator have been loaded. The\n# value should be a global name (i.e. /my/name/space), not a relative\n# (my/name/space) or private (~my/name/space) name. Analyzers will not be added\n# if a non-global name is used. The call will also fail if the namespace\n# contains parameters that follow a namespace structure that does not conform to\n# that expected by the analyzer definitions. See\n# http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators\n# and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer\n# for examples of the structure of yaml files which are expected to have been\n# loaded into the namespace.\nstring load_namespace" ; + const DEFINITION: &'static str = r#"# This service is used as part of the process for loading analyzers at runtime, +# and should be used by a loader script or program, not as a standalone service. +# Information about dynamic addition of analyzers can be found at +# http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime + +# The load_namespace parameter defines the namespace where parameters for the +# initialization of analyzers in the diagnostic aggregator have been loaded. The +# value should be a global name (i.e. /my/name/space), not a relative +# (my/name/space) or private (~my/name/space) name. Analyzers will not be added +# if a non-global name is used. The call will also fail if the namespace +# contains parameters that follow a namespace structure that does not conform to +# that expected by the analyzer definitions. See +# http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators +# and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer +# for examples of the structure of yaml files which are expected to have been +# loaded into the namespace. +string load_namespace"#; } #[allow(non_snake_case)] #[derive( @@ -200,7 +379,14 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for AddDiagnosticsResponse { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/AddDiagnosticsResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; - const DEFINITION : & 'static str = "# True if diagnostic aggregator was updated with new diagnostics, False\n# otherwise. A false return value means that either there is a bond in the\n# aggregator which already used the requested namespace, or the initialization\n# of analyzers failed.\nbool success\n\n# Message with additional information about the success or failure\nstring message" ; + const DEFINITION: &'static str = r#"# True if diagnostic aggregator was updated with new diagnostics, False +# otherwise. A false return value means that either there is a bond in the +# aggregator which already used the requested namespace, or the initialization +# of analyzers failed. +bool success + +# Message with additional information about the success or failure +string message"#; } pub struct AddDiagnostics {} impl ::roslibrust_codegen::RosServiceType for AddDiagnostics { @@ -223,7 +409,7 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for SelfTestRequest { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/SelfTestRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -243,7 +429,33 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for SelfTestResponse { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/SelfTestResponse"; const MD5SUM: &'static str = "ac21b1bab7ab17546986536c22eb34e9"; - const DEFINITION: &'static str = "string id\nbyte passed\nDiagnosticStatus[] status"; + const DEFINITION: &'static str = r#"string id +byte passed +DiagnosticStatus[] status +================================================================================ +MSG: diagnostic_msgs/DiagnosticStatus +# This message holds the status of an individual component of the robot. +# + +# Possible levels of operations +byte OK=0 +byte WARN=1 +byte ERROR=2 +byte STALE=3 + +byte level # level of operation enumerated above +string name # a description of the test/component reporting +string message # a description of the status +string hardware_id # a hardware unique string +KeyValue[] values # an array of values associated with the status +================================================================================ +MSG: diagnostic_msgs/KeyValue +string key # what to label this value when viewing +string value # a value to track over time +================================================================================ +MSG: diagnostic_msgs/KeyValue +string key # what to label this value when viewing +string value # a value to track over time"#; } pub struct SelfTest {} impl ::roslibrust_codegen::RosServiceType for SelfTest { @@ -285,7 +497,21 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Accel { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Accel"; const MD5SUM: &'static str = "9f195f881246fdfa2798d1d3eebca84a"; - const DEFINITION : & 'static str = "# This expresses acceleration in free space broken into its linear and angular parts.\nVector3 linear\nVector3 angular" ; + const DEFINITION: &'static str = r#"# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -304,8 +530,53 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for AccelStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelStamped"; const MD5SUM: &'static str = "d8a98a5d81351b6eb0578c78557e7659"; - const DEFINITION: &'static str = - "# An accel with reference coordinate frame and timestamp\nHeader header\nAccel accel"; + const DEFINITION: &'static str = r#"# An accel with reference coordinate frame and timestamp +Header header +Accel accel +================================================================================ +MSG: geometry_msgs/Accel +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -326,7 +597,44 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for AccelWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovariance"; const MD5SUM: &'static str = "ad5a718d699c6be72a02b8d6a139f334"; - const DEFINITION : & 'static str = "# This expresses acceleration in free space with uncertainty.\n\nAccel accel\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance" ; + const DEFINITION: &'static str = r#"# This expresses acceleration in free space with uncertainty. + +Accel accel + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Accel +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -345,7 +653,93 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for AccelWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovarianceStamped"; const MD5SUM: &'static str = "96adb295225031ec8d57fb4251b0a886"; - const DEFINITION : & 'static str = "# This represents an estimated accel with reference coordinate frame and timestamp.\nHeader header\nAccelWithCovariance accel" ; + const DEFINITION: &'static str = r#"# This represents an estimated accel with reference coordinate frame and timestamp. +Header header +AccelWithCovariance accel +================================================================================ +MSG: geometry_msgs/Accel +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/AccelWithCovariance +# This expresses acceleration in free space with uncertainty. + +Accel accel + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Accel +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -370,7 +764,34 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Inertia { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Inertia"; const MD5SUM: &'static str = "1d26e4bb6c83ff141c5cf0d883c2b0fe"; - const DEFINITION : & 'static str = "# Mass [kg]\nfloat64 m\n\n# Center of mass [m]\ngeometry_msgs/Vector3 com\n\n# Inertia Tensor [kg-m^2]\n# | ixx ixy ixz |\n# I = | ixy iyy iyz |\n# | ixz iyz izz |\nfloat64 ixx\nfloat64 ixy\nfloat64 ixz\nfloat64 iyy\nfloat64 iyz\nfloat64 izz" ; + const DEFINITION: &'static str = r#"# Mass [kg] +float64 m + +# Center of mass [m] +geometry_msgs/Vector3 com + +# Inertia Tensor [kg-m^2] +# | ixx ixy ixz | +# I = | ixy iyy iyz | +# | ixz iyz izz | +float64 ixx +float64 ixy +float64 ixz +float64 iyy +float64 iyz +float64 izz +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -389,7 +810,65 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for InertiaStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/InertiaStamped"; const MD5SUM: &'static str = "ddee48caeab5a966c5e8d166654a9ac7"; - const DEFINITION: &'static str = "Header header\nInertia inertia"; + const DEFINITION: &'static str = r#"Header header +Inertia inertia +================================================================================ +MSG: geometry_msgs/Inertia +# Mass [kg] +float64 m + +# Center of mass [m] +geometry_msgs/Vector3 com + +# Inertia Tensor [kg-m^2] +# | ixx ixy ixz | +# I = | ixy iyy iyz | +# | ixz iyz izz | +float64 ixx +float64 ixy +float64 ixz +float64 iyy +float64 iyz +float64 izz +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -409,7 +888,10 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Point { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Point"; const MD5SUM: &'static str = "4a842b65f413084dc2b10fb484ea7f17"; - const DEFINITION : & 'static str = "# This contains the position of a point in free space\nfloat64 x\nfloat64 y\nfloat64 z" ; + const DEFINITION: &'static str = r#"# This contains the position of a point in free space +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -429,7 +911,17 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Point32 { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Point32"; const MD5SUM: &'static str = "cc153912f1453b708d221682bc23d9ac"; - const DEFINITION : & 'static str = "# This contains the position of a point in free space(with 32 bits of precision).\n# It is recommeded to use Point wherever possible instead of Point32. \n# \n# This recommendation is to promote interoperability. \n#\n# This message is designed to take up less space when sending\n# lots of points at once, as in the case of a PointCloud. \n\nfloat32 x\nfloat32 y\nfloat32 z" ; + const DEFINITION: &'static str = r#"# This contains the position of a point in free space(with 32 bits of precision). +# It is recommeded to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z"#; } #[allow(non_snake_case)] #[derive( @@ -448,7 +940,30 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PointStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PointStamped"; const MD5SUM: &'static str = "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; - const DEFINITION : & 'static str = "# This represents a Point with reference coordinate frame and timestamp\nHeader header\nPoint point" ; + const DEFINITION: &'static str = r#"# This represents a Point with reference coordinate frame and timestamp +Header header +Point point +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -466,7 +981,21 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Polygon { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Polygon"; const MD5SUM: &'static str = "cd60a26494a087f577976f0329fa120e"; - const DEFINITION : & 'static str = "#A specification of a polygon where the first and last points are assumed to be connected\nPoint32[] points" ; + const DEFINITION: &'static str = r#"#A specification of a polygon where the first and last points are assumed to be connected +Point32[] points +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommeded to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z"#; } #[allow(non_snake_case)] #[derive( @@ -485,7 +1014,54 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PolygonStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PolygonStamped"; const MD5SUM: &'static str = "c6be8f7dc3bee7fe9e8d296070f53340"; - const DEFINITION : & 'static str = "# This represents a Polygon with reference coordinate frame and timestamp\nHeader header\nPolygon polygon" ; + const DEFINITION: &'static str = r#"# This represents a Polygon with reference coordinate frame and timestamp +Header header +Polygon polygon +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommeded to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z +================================================================================ +MSG: geometry_msgs/Polygon +#A specification of a polygon where the first and last points are assumed to be connected +Point32[] points +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommeded to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -504,7 +1080,23 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Pose { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Pose"; const MD5SUM: &'static str = "e45d45a5a1ce597b249e23fb30fc871f"; - const DEFINITION : & 'static str = "# A representation of pose in free space, composed of position and orientation. \nPoint position\nQuaternion orientation" ; + const DEFINITION: &'static str = r#"# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w"#; } #[allow(non_snake_case)] #[derive( @@ -524,7 +1116,19 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Pose2D { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Pose2D"; const MD5SUM: &'static str = "938fa65709584ad8e77d238529be13b8"; - const DEFINITION : & 'static str = "# Deprecated\n# Please use the full 3D pose.\n\n# In general our recommendation is to use a full 3D representation of everything and for 2D specific applications make the appropriate projections into the plane for their calculations but optimally will preserve the 3D information during processing.\n\n# If we have parallel copies of 2D datatypes every UI and other pipeline will end up needing to have dual interfaces to plot everything. And you will end up with not being able to use 3D tools for 2D use cases even if they're completely valid, as you'd have to reimplement it with different inputs and outputs. It's not particularly hard to plot the 2D pose or compute the yaw error for the Pose message and there are already tools and libraries that can do this for you.\n\n\n# This expresses a position and orientation on a 2D manifold.\n\nfloat64 x\nfloat64 y\nfloat64 theta" ; + const DEFINITION: &'static str = r#"# Deprecated +# Please use the full 3D pose. + +# In general our recommendation is to use a full 3D representation of everything and for 2D specific applications make the appropriate projections into the plane for their calculations but optimally will preserve the 3D information during processing. + +# If we have parallel copies of 2D datatypes every UI and other pipeline will end up needing to have dual interfaces to plot everything. And you will end up with not being able to use 3D tools for 2D use cases even if they're completely valid, as you'd have to reimplement it with different inputs and outputs. It's not particularly hard to plot the 2D pose or compute the yaw error for the Pose message and there are already tools and libraries that can do this for you. + + +# This expresses a position and orientation on a 2D manifold. + +float64 x +float64 y +float64 theta"#; } #[allow(non_snake_case)] #[derive( @@ -543,7 +1147,59 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PoseArray { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseArray"; const MD5SUM: &'static str = "916c28c5764443f268b296bb671b9d97"; - const DEFINITION : & 'static str = "# An array of poses with a header for global reference.\n\nHeader header\n\nPose[] poses" ; + const DEFINITION: &'static str = r#"# An array of poses with a header for global reference. + +Header header + +Pose[] poses +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -562,8 +1218,57 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PoseStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseStamped"; const MD5SUM: &'static str = "d3812c3cbc69362b77dc0b19b345f8f5"; - const DEFINITION: &'static str = - "# A Pose with reference coordinate frame and timestamp\nHeader header\nPose pose"; + const DEFINITION: &'static str = r#"# A Pose with reference coordinate frame and timestamp +Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -584,7 +1289,48 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PoseWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovariance"; const MD5SUM: &'static str = "c23e848cf1b7533a8d7c259073a97e6f"; - const DEFINITION : & 'static str = "# This represents a pose in free space with uncertainty.\n\nPose pose\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance" ; + const DEFINITION: &'static str = r#"# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w"#; } #[allow(non_snake_case)] #[derive( @@ -603,7 +1349,102 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PoseWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovarianceStamped"; const MD5SUM: &'static str = "953b798c0f514ff060a53a3498ce6246"; - const DEFINITION : & 'static str = "# This expresses an estimated pose with a reference coordinate frame and timestamp\n\nHeader header\nPoseWithCovariance pose" ; + const DEFINITION: &'static str = r#"# This expresses an estimated pose with a reference coordinate frame and timestamp + +Header header +PoseWithCovariance pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -624,7 +1465,12 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Quaternion { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Quaternion"; const MD5SUM: &'static str = "a779879fadf0160734f906b8c19c7004"; - const DEFINITION : & 'static str = "# This represents an orientation in free space in quaternion form.\n\nfloat64 x\nfloat64 y\nfloat64 z\nfloat64 w" ; + const DEFINITION: &'static str = r#"# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w"#; } #[allow(non_snake_case)] #[derive( @@ -643,7 +1489,33 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for QuaternionStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/QuaternionStamped"; const MD5SUM: &'static str = "e57f1e547e0e1fd13504588ffc8334e2"; - const DEFINITION : & 'static str = "# This represents an orientation with reference coordinate frame and timestamp.\n\nHeader header\nQuaternion quaternion" ; + const DEFINITION: &'static str = r#"# This represents an orientation with reference coordinate frame and timestamp. + +Header header +Quaternion quaternion +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -662,7 +1534,30 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Transform { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Transform"; const MD5SUM: &'static str = "ac9eff44abf714214112b05d54a3cf9b"; - const DEFINITION : & 'static str = "# This represents the transform between two coordinate frames in free space.\n\nVector3 translation\nQuaternion rotation" ; + const DEFINITION: &'static str = r#"# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -682,7 +1577,77 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for TransformStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TransformStamped"; const MD5SUM: &'static str = "b5764a33bfeb3588febc2682852579b0"; - const DEFINITION : & 'static str = "# This expresses a transform from coordinate frame header.frame_id\n# to the coordinate frame child_frame_id\n#\n# This message is mostly used by the \n# tf package. \n# See its documentation for more information.\n\nHeader header\nstring child_frame_id # the frame id of the child frame\nTransform transform" ; + const DEFINITION: &'static str = r#"# This expresses a transform from coordinate frame header.frame_id +# to the coordinate frame child_frame_id +# +# This message is mostly used by the +# tf package. +# See its documentation for more information. + +Header header +string child_frame_id # the frame id of the child frame +Transform transform +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -701,7 +1666,21 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Twist { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Twist"; const MD5SUM: &'static str = "9f195f881246fdfa2798d1d3eebca84a"; - const DEFINITION : & 'static str = "# This expresses velocity in free space broken into its linear and angular parts.\nVector3 linear\nVector3 angular" ; + const DEFINITION: &'static str = r#"# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -720,8 +1699,53 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for TwistStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistStamped"; const MD5SUM: &'static str = "98d34b0043a2093cf9d9345ab6eef12e"; - const DEFINITION: &'static str = - "# A twist with reference coordinate frame and timestamp\nHeader header\nTwist twist"; + const DEFINITION: &'static str = r#"# A twist with reference coordinate frame and timestamp +Header header +Twist twist +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -742,7 +1766,44 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for TwistWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovariance"; const MD5SUM: &'static str = "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; - const DEFINITION : & 'static str = "# This expresses velocity in free space with uncertainty.\n\nTwist twist\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance" ; + const DEFINITION: &'static str = r#"# This expresses velocity in free space with uncertainty. + +Twist twist + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -761,7 +1822,93 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for TwistWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovarianceStamped"; const MD5SUM: &'static str = "8927a1a12fb2607ceea095b2dc440a96"; - const DEFINITION : & 'static str = "# This represents an estimated twist with reference coordinate frame and timestamp.\nHeader header\nTwistWithCovariance twist" ; + const DEFINITION: &'static str = r#"# This represents an estimated twist with reference coordinate frame and timestamp. +Header header +TwistWithCovariance twist +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/TwistWithCovariance +# This expresses velocity in free space with uncertainty. + +Twist twist + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -781,7 +1928,16 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Vector3 { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Vector3"; const MD5SUM: &'static str = "4a842b65f413084dc2b10fb484ea7f17"; - const DEFINITION : & 'static str = "# This represents a vector in free space. \n# It is only meant to represent a direction. Therefore, it does not\n# make sense to apply a translation to it (e.g., when applying a \n# generic rigid transformation to a Vector3, tf2 will only apply the\n# rotation). If you want your data to be translatable too, use the\n# geometry_msgs/Point message instead.\n\nfloat64 x\nfloat64 y\nfloat64 z" ; + const DEFINITION: &'static str = r#"# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -800,7 +1956,36 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Vector3Stamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Vector3Stamped"; const MD5SUM: &'static str = "7b324c7325e683bf02a9b14b01090ec7"; - const DEFINITION : & 'static str = "# This represents a Vector3 with reference coordinate frame and timestamp\nHeader header\nVector3 vector" ; + const DEFINITION: &'static str = r#"# This represents a Vector3 with reference coordinate frame and timestamp +Header header +Vector3 vector +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -819,7 +2004,22 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Wrench { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Wrench"; const MD5SUM: &'static str = "4f539cf138b23283b520fd271b567936"; - const DEFINITION : & 'static str = "# This represents force in free space, separated into\n# its linear and angular parts.\nVector3 force\nVector3 torque" ; + const DEFINITION: &'static str = r#"# This represents force in free space, separated into +# its linear and angular parts. +Vector3 force +Vector3 torque +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -838,7 +2038,54 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for WrenchStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/WrenchStamped"; const MD5SUM: &'static str = "d78d3cb249ce23087ade7e7d0c40cfa7"; - const DEFINITION : & 'static str = "# A wrench with reference coordinate frame and timestamp\nHeader header\nWrench wrench" ; + const DEFINITION: &'static str = r#"# A wrench with reference coordinate frame and timestamp +Header header +Wrench wrench +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Wrench +# This represents force in free space, separated into +# its linear and angular parts. +Vector3 force +Vector3 torque +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } } #[allow(unused_imports)] @@ -874,7 +2121,1041 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapAction { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapAction"; const MD5SUM: &'static str = "e611ad23fbf237c031b7536416dc7cd7"; - const DEFINITION : & 'static str = "GetMapActionGoal action_goal\nGetMapActionResult action_result\nGetMapActionFeedback action_feedback" ; + const DEFINITION: &'static str = r#"GetMapActionGoal action_goal +GetMapActionResult action_result +GetMapActionFeedback action_feedback +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: actionlib_msgs/GoalStatus +GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server +uint8 ACTIVE = 1 # The goal is currently being processed by the action server +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State) +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State) +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State) +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, + # but the action server has not yet confirmed that the goal is canceled +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State) +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be + # sent over the wire by an action server + +#Allow for the user to associate a string with GoalStatus for debugging +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/GetMapActionFeedback +Header header +actionlib_msgs/GoalStatus status +GetMapFeedback feedback +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: actionlib_msgs/GoalStatus +GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server +uint8 ACTIVE = 1 # The goal is currently being processed by the action server +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State) +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State) +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State) +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, + # but the action server has not yet confirmed that the goal is canceled +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State) +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be + # sent over the wire by an action server + +#Allow for the user to associate a string with GoalStatus for debugging +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: nav_msgs/GetMapFeedback +# no feedback +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: nav_msgs/GetMapActionGoal +Header header +actionlib_msgs/GoalID goal_id +GetMapGoal goal +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: nav_msgs/GetMapGoal +# Get the map as a nav_msgs/OccupancyGrid +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: nav_msgs/GetMapActionResult +Header header +actionlib_msgs/GoalStatus status +GetMapResult result +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: actionlib_msgs/GoalStatus +GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server +uint8 ACTIVE = 1 # The goal is currently being processed by the action server +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State) +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State) +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State) +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, + # but the action server has not yet confirmed that the goal is canceled +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State) +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be + # sent over the wire by an action server + +#Allow for the user to associate a string with GoalStatus for debugging +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/GetMapResult +nav_msgs/OccupancyGrid map +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: nav_msgs/GetMapFeedback +# no feedback +================================================================================ +MSG: nav_msgs/GetMapGoal +# Get the map as a nav_msgs/OccupancyGrid +================================================================================ +MSG: nav_msgs/GetMapResult +nav_msgs/OccupancyGrid map +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -894,8 +3175,73 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapActionFeedback { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapActionFeedback"; const MD5SUM: &'static str = "aae20e09065c3809e8a8e87c4c8953fd"; - const DEFINITION: &'static str = - "Header header\nactionlib_msgs/GoalStatus status\nGetMapFeedback feedback"; + const DEFINITION: &'static str = r#"Header header +actionlib_msgs/GoalStatus status +GetMapFeedback feedback +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: actionlib_msgs/GoalStatus +GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server +uint8 ACTIVE = 1 # The goal is currently being processed by the action server +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State) +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State) +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State) +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, + # but the action server has not yet confirmed that the goal is canceled +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State) +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be + # sent over the wire by an action server + +#Allow for the user to associate a string with GoalStatus for debugging +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: nav_msgs/GetMapFeedback +# no feedback +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -915,8 +3261,38 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapActionGoal { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapActionGoal"; const MD5SUM: &'static str = "4b30be6cd12b9e72826df56b481f40e0"; - const DEFINITION: &'static str = - "Header header\nactionlib_msgs/GoalID goal_id\nGetMapGoal goal"; + const DEFINITION: &'static str = r#"Header header +actionlib_msgs/GoalID goal_id +GetMapGoal goal +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: nav_msgs/GetMapGoal +# Get the map as a nav_msgs/OccupancyGrid +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -936,8 +3312,468 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapActionResult { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapActionResult"; const MD5SUM: &'static str = "ac66e5b9a79bb4bbd33dab245236c892"; - const DEFINITION: &'static str = - "Header header\nactionlib_msgs/GoalStatus status\nGetMapResult result"; + const DEFINITION: &'static str = r#"Header header +actionlib_msgs/GoalStatus status +GetMapResult result +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: actionlib_msgs/GoalStatus +GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server +uint8 ACTIVE = 1 # The goal is currently being processed by the action server +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State) +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State) +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State) +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, + # but the action server has not yet confirmed that the goal is canceled +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State) +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be + # sent over the wire by an action server + +#Allow for the user to associate a string with GoalStatus for debugging +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/GetMapResult +nav_msgs/OccupancyGrid map +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -953,7 +3789,7 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapFeedback { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapFeedback"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = "# no feedback"; + const DEFINITION: &'static str = r#"# no feedback"#; } #[allow(non_snake_case)] #[derive( @@ -969,7 +3805,7 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapGoal { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapGoal"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = "# Get the map as a nav_msgs/OccupancyGrid"; + const DEFINITION: &'static str = r#"# Get the map as a nav_msgs/OccupancyGrid"#; } #[allow(non_snake_case)] #[derive( @@ -987,7 +3823,212 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapResult { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapResult"; const MD5SUM: &'static str = "6cdd0a18e0aff5b0a3ca2326a89b54ff"; - const DEFINITION: &'static str = "nav_msgs/OccupancyGrid map"; + const DEFINITION: &'static str = r#"nav_msgs/OccupancyGrid map +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1008,7 +4049,32 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GridCells { const ROS_TYPE_NAME: &'static str = "nav_msgs/GridCells"; const MD5SUM: &'static str = "b9e4f5df6d28e272ebde00a3994830f5"; - const DEFINITION : & 'static str = "#an array of cells in a 2D grid\nHeader header\nfloat32 cell_width\nfloat32 cell_height\ngeometry_msgs/Point[] cells" ; + const DEFINITION: &'static str = r#"#an array of cells in a 2D grid +Header header +float32 cell_width +float32 cell_height +geometry_msgs/Point[] cells +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1030,7 +4096,52 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for MapMetaData { const ROS_TYPE_NAME: &'static str = "nav_msgs/MapMetaData"; const MD5SUM: &'static str = "10cfc8a2818024d3248802c00c95f11b"; - const DEFINITION : & 'static str = "# This hold basic information about the characterists of the OccupancyGrid\n\n# The time at which the map was loaded\ntime map_load_time\n# The map resolution [m/cell]\nfloat32 resolution\n# Map width [cells]\nuint32 width\n# Map height [cells]\nuint32 height\n# The origin of the map [m, m, rad]. This is the real-world pose of the\n# cell (0,0) in the map.\ngeometry_msgs/Pose origin" ; + const DEFINITION: &'static str = r#"# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w"#; } #[allow(non_snake_case)] #[derive( @@ -1050,7 +4161,113 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for OccupancyGrid { const ROS_TYPE_NAME: &'static str = "nav_msgs/OccupancyGrid"; const MD5SUM: &'static str = "3381f2d731d4076ec5c71b0759edbe4e"; - const DEFINITION : & 'static str = "# This represents a 2-D grid map, in which each cell represents the probability of\n# occupancy.\n\nHeader header \n\n#MetaData for the map\nMapMetaData info\n\n# The map data, in row-major order, starting with (0,0). Occupancy\n# probabilities are in the range [0,100]. Unknown is -1.\nint8[] data" ; + const DEFINITION: &'static str = r#"# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1071,7 +4288,174 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for Odometry { const ROS_TYPE_NAME: &'static str = "nav_msgs/Odometry"; const MD5SUM: &'static str = "cd5e73d190d741a2f92e81eda573aca7"; - const DEFINITION : & 'static str = "# This represents an estimate of a position and velocity in free space. \n# The pose in this message should be specified in the coordinate frame given by header.frame_id.\n# The twist in this message should be specified in the coordinate frame given by the child_frame_id\nHeader header\nstring child_frame_id\ngeometry_msgs/PoseWithCovariance pose\ngeometry_msgs/TwistWithCovariance twist" ; + const DEFINITION: &'static str = r#"# This represents an estimate of a position and velocity in free space. +# The pose in this message should be specified in the coordinate frame given by header.frame_id. +# The twist in this message should be specified in the coordinate frame given by the child_frame_id +Header header +string child_frame_id +geometry_msgs/PoseWithCovariance pose +geometry_msgs/TwistWithCovariance twist +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/TwistWithCovariance +# This expresses velocity in free space with uncertainty. + +Twist twist + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1090,7 +4474,110 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for Path { const ROS_TYPE_NAME: &'static str = "nav_msgs/Path"; const MD5SUM: &'static str = "6227e2b7e9cce15051f669a5e197bbf7"; - const DEFINITION : & 'static str = "#An array of poses that represents a Path for a robot to follow\nHeader header\ngeometry_msgs/PoseStamped[] poses" ; + const DEFINITION: &'static str = r#"#An array of poses that represents a Path for a robot to follow +Header header +geometry_msgs/PoseStamped[] poses +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseStamped +# A Pose with reference coordinate frame and timestamp +Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1106,7 +4593,7 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = "# Get the map as a nav_msgs/OccupancyGrid"; + const DEFINITION: &'static str = r#"# Get the map as a nav_msgs/OccupancyGrid"#; } #[allow(non_snake_case)] #[derive( @@ -1124,7 +4611,212 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapResponse"; const MD5SUM: &'static str = "6cdd0a18e0aff5b0a3ca2326a89b54ff"; - const DEFINITION: &'static str = "nav_msgs/OccupancyGrid map"; + const DEFINITION: &'static str = r#"nav_msgs/OccupancyGrid map +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } pub struct GetMap {} impl ::roslibrust_codegen::RosServiceType for GetMap { @@ -1151,7 +4843,118 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetPlanRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetPlanRequest"; const MD5SUM: &'static str = "e25a43e0752bcca599a8c2eef8282df8"; - const DEFINITION : & 'static str = "# Get a plan from the current position to the goal Pose \n\n# The start pose for the plan\ngeometry_msgs/PoseStamped start\n\n# The final pose of the goal position\ngeometry_msgs/PoseStamped goal\n\n# If the goal is obstructed, how many meters the planner can \n# relax the constraint in x and y before failing. \nfloat32 tolerance" ; + const DEFINITION: &'static str = r#"# Get a plan from the current position to the goal Pose + +# The start pose for the plan +geometry_msgs/PoseStamped start + +# The final pose of the goal position +geometry_msgs/PoseStamped goal + +# If the goal is obstructed, how many meters the planner can +# relax the constraint in x and y before failing. +float32 tolerance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseStamped +# A Pose with reference coordinate frame and timestamp +Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1169,7 +4972,214 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetPlanResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetPlanResponse"; const MD5SUM: &'static str = "0002bc113c0259d71f6cf8cbc9430e18"; - const DEFINITION: &'static str = "nav_msgs/Path plan"; + const DEFINITION: &'static str = r#"nav_msgs/Path plan +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseStamped +# A Pose with reference coordinate frame and timestamp +Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/Path +#An array of poses that represents a Path for a robot to follow +Header header +geometry_msgs/PoseStamped[] poses +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseStamped +# A Pose with reference coordinate frame and timestamp +Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } pub struct GetPlan {} impl ::roslibrust_codegen::RosServiceType for GetPlan { @@ -1194,7 +5204,10 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for LoadMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/LoadMapRequest"; const MD5SUM: &'static str = "3813ba1ae85fbcd4dc88c90f1426b90b"; - const DEFINITION : & 'static str = "# URL of map resource\n# Can be an absolute path to a file: file:///path/to/maps/floor1.yaml\n# Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml\nstring map_url" ; + const DEFINITION: &'static str = r#"# URL of map resource +# Can be an absolute path to a file: file:///path/to/maps/floor1.yaml +# Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml +string map_url"#; } #[allow(non_snake_case)] #[derive( @@ -1213,7 +5226,221 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for LoadMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/LoadMapResponse"; const MD5SUM: &'static str = "079b9c828e9f7c1918bf86932fd7267e"; - const DEFINITION : & 'static str = "# Result code defintions\nuint8 RESULT_SUCCESS=0\nuint8 RESULT_MAP_DOES_NOT_EXIST=1\nuint8 RESULT_INVALID_MAP_DATA=2\nuint8 RESULT_INVALID_MAP_METADATA=3\nuint8 RESULT_UNDEFINED_FAILURE=255\n\n# Returned map is only valid if result equals RESULT_SUCCESS\nnav_msgs/OccupancyGrid map\nuint8 result" ; + const DEFINITION: &'static str = r#"# Result code defintions +uint8 RESULT_SUCCESS=0 +uint8 RESULT_MAP_DOES_NOT_EXIST=1 +uint8 RESULT_INVALID_MAP_DATA=2 +uint8 RESULT_INVALID_MAP_METADATA=3 +uint8 RESULT_UNDEFINED_FAILURE=255 + +# Returned map is only valid if result equals RESULT_SUCCESS +nav_msgs/OccupancyGrid map +uint8 result +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl LoadMapResponse { pub const r#RESULT_SUCCESS: u8 = 0u8; @@ -1246,7 +5473,356 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for SetMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/SetMapRequest"; const MD5SUM: &'static str = "91149a20d7be299b87c340df8cc94fd4"; - const DEFINITION : & 'static str = "# Set a new map together with an initial pose\nnav_msgs/OccupancyGrid map\ngeometry_msgs/PoseWithCovarianceStamped initial_pose" ; + const DEFINITION: &'static str = r#"# Set a new map together with an initial pose +nav_msgs/OccupancyGrid map +geometry_msgs/PoseWithCovarianceStamped initial_pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseWithCovarianceStamped +# This expresses an estimated pose with a reference coordinate frame and timestamp + +Header header +PoseWithCovariance pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1264,7 +5840,7 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for SetMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/SetMapResponse"; const MD5SUM: &'static str = "358e233cde0c8a8bcfea4ce193f8fc15"; - const DEFINITION: &'static str = "bool success"; + const DEFINITION: &'static str = r#"bool success"#; } pub struct SetMap {} impl ::roslibrust_codegen::RosServiceType for SetMap { @@ -1311,7 +5887,13 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TypeDef { const ROS_TYPE_NAME: &'static str = "rosapi/TypeDef"; const MD5SUM: &'static str = "80597571d79bbeef6c9c4d98f30116a0"; - const DEFINITION : & 'static str = "string type\nstring[] fieldnames\nstring[] fieldtypes\nint32[] fieldarraylen\nstring[] examples\nstring[] constnames\nstring[] constvalues" ; + const DEFINITION: &'static str = r#"string type +string[] fieldnames +string[] fieldtypes +int32[] fieldarraylen +string[] examples +string[] constnames +string[] constvalues"#; } #[allow(non_snake_case)] #[derive( @@ -1329,7 +5911,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for DeleteParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/DeleteParamRequest"; const MD5SUM: &'static str = "c1f3d28f1b044c871e6eff2e9fc3c667"; - const DEFINITION: &'static str = "string name"; + const DEFINITION: &'static str = r#"string name"#; } #[allow(non_snake_case)] #[derive( @@ -1345,7 +5927,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for DeleteParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/DeleteParamResponse"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } pub struct DeleteParam {} impl ::roslibrust_codegen::RosServiceType for DeleteParam { @@ -1368,7 +5950,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for GetActionServersRequest { const ROS_TYPE_NAME: &'static str = "rosapi/GetActionServersRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -1386,7 +5968,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for GetActionServersResponse { const ROS_TYPE_NAME: &'static str = "rosapi/GetActionServersResponse"; const MD5SUM: &'static str = "46807ba271844ac5ba4730a47556b236"; - const DEFINITION: &'static str = "string[] action_servers"; + const DEFINITION: &'static str = r#"string[] action_servers"#; } pub struct GetActionServers {} impl ::roslibrust_codegen::RosServiceType for GetActionServers { @@ -1412,7 +5994,8 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for GetParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/GetParamRequest"; const MD5SUM: &'static str = "1cc3f281ee24ba9406c3e498e4da686f"; - const DEFINITION: &'static str = "string name\nstring default"; + const DEFINITION: &'static str = r#"string name +string default"#; } #[allow(non_snake_case)] #[derive( @@ -1430,7 +6013,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for GetParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/GetParamResponse"; const MD5SUM: &'static str = "64e58419496c7248b4ef25731f88b8c3"; - const DEFINITION: &'static str = "string value"; + const DEFINITION: &'static str = r#"string value"#; } pub struct GetParam {} impl ::roslibrust_codegen::RosServiceType for GetParam { @@ -1453,7 +6036,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for GetParamNamesRequest { const ROS_TYPE_NAME: &'static str = "rosapi/GetParamNamesRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -1471,7 +6054,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for GetParamNamesResponse { const ROS_TYPE_NAME: &'static str = "rosapi/GetParamNamesResponse"; const MD5SUM: &'static str = "dc7ae3609524b18034e49294a4ce670e"; - const DEFINITION: &'static str = "string[] names"; + const DEFINITION: &'static str = r#"string[] names"#; } pub struct GetParamNames {} impl ::roslibrust_codegen::RosServiceType for GetParamNames { @@ -1494,7 +6077,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for GetTimeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/GetTimeRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -1512,7 +6095,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for GetTimeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/GetTimeResponse"; const MD5SUM: &'static str = "556a4fb76023a469987922359d08a844"; - const DEFINITION: &'static str = "time time"; + const DEFINITION: &'static str = r#"time time"#; } pub struct GetTime {} impl ::roslibrust_codegen::RosServiceType for GetTime { @@ -1537,7 +6120,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for HasParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/HasParamRequest"; const MD5SUM: &'static str = "c1f3d28f1b044c871e6eff2e9fc3c667"; - const DEFINITION: &'static str = "string name"; + const DEFINITION: &'static str = r#"string name"#; } #[allow(non_snake_case)] #[derive( @@ -1555,7 +6138,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for HasParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/HasParamResponse"; const MD5SUM: &'static str = "e8c90de4adc1219c86af9c2874c0c1b5"; - const DEFINITION: &'static str = "bool exists"; + const DEFINITION: &'static str = r#"bool exists"#; } pub struct HasParam {} impl ::roslibrust_codegen::RosServiceType for HasParam { @@ -1580,7 +6163,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for MessageDetailsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/MessageDetailsRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; - const DEFINITION: &'static str = "string type"; + const DEFINITION: &'static str = r#"string type"#; } #[allow(non_snake_case)] #[derive( @@ -1598,7 +6181,16 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for MessageDetailsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/MessageDetailsResponse"; const MD5SUM: &'static str = "a6b8995777f214f2ed97a1e4890feb10"; - const DEFINITION: &'static str = "TypeDef[] typedefs"; + const DEFINITION: &'static str = r#"TypeDef[] typedefs +================================================================================ +MSG: rosapi/TypeDef +string type +string[] fieldnames +string[] fieldtypes +int32[] fieldarraylen +string[] examples +string[] constnames +string[] constvalues"#; } pub struct MessageDetails {} impl ::roslibrust_codegen::RosServiceType for MessageDetails { @@ -1623,7 +6215,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for NodeDetailsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/NodeDetailsRequest"; const MD5SUM: &'static str = "a94c40e70a4b82863e6e52ec16732447"; - const DEFINITION: &'static str = "string node"; + const DEFINITION: &'static str = r#"string node"#; } #[allow(non_snake_case)] #[derive( @@ -1643,8 +6235,9 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for NodeDetailsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/NodeDetailsResponse"; const MD5SUM: &'static str = "3da1cb16c6ec5885ad291735b6244a48"; - const DEFINITION: &'static str = - "string[] subscribing\nstring[] publishing\nstring[] services"; + const DEFINITION: &'static str = r#"string[] subscribing +string[] publishing +string[] services"#; } pub struct NodeDetails {} impl ::roslibrust_codegen::RosServiceType for NodeDetails { @@ -1667,7 +6260,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for NodesRequest { const ROS_TYPE_NAME: &'static str = "rosapi/NodesRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -1685,7 +6278,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for NodesResponse { const ROS_TYPE_NAME: &'static str = "rosapi/NodesResponse"; const MD5SUM: &'static str = "3d07bfda1268b4f76b16b7ba8a82665d"; - const DEFINITION: &'static str = "string[] nodes"; + const DEFINITION: &'static str = r#"string[] nodes"#; } pub struct Nodes {} impl ::roslibrust_codegen::RosServiceType for Nodes { @@ -1710,7 +6303,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for PublishersRequest { const ROS_TYPE_NAME: &'static str = "rosapi/PublishersRequest"; const MD5SUM: &'static str = "d8f94bae31b356b24d0427f80426d0c3"; - const DEFINITION: &'static str = "string topic"; + const DEFINITION: &'static str = r#"string topic"#; } #[allow(non_snake_case)] #[derive( @@ -1728,7 +6321,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for PublishersResponse { const ROS_TYPE_NAME: &'static str = "rosapi/PublishersResponse"; const MD5SUM: &'static str = "167d8030c4ca4018261dff8ae5083dc8"; - const DEFINITION: &'static str = "string[] publishers"; + const DEFINITION: &'static str = r#"string[] publishers"#; } pub struct Publishers {} impl ::roslibrust_codegen::RosServiceType for Publishers { @@ -1753,7 +6346,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for SearchParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/SearchParamRequest"; const MD5SUM: &'static str = "c1f3d28f1b044c871e6eff2e9fc3c667"; - const DEFINITION: &'static str = "string name"; + const DEFINITION: &'static str = r#"string name"#; } #[allow(non_snake_case)] #[derive( @@ -1771,7 +6364,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for SearchParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/SearchParamResponse"; const MD5SUM: &'static str = "87c264f142c2aeca13349d90aeec0386"; - const DEFINITION: &'static str = "string global_name"; + const DEFINITION: &'static str = r#"string global_name"#; } pub struct SearchParam {} impl ::roslibrust_codegen::RosServiceType for SearchParam { @@ -1796,7 +6389,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceHostRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceHostRequest"; const MD5SUM: &'static str = "1cbcfa13b08f6d36710b9af8741e6112"; - const DEFINITION: &'static str = "string service"; + const DEFINITION: &'static str = r#"string service"#; } #[allow(non_snake_case)] #[derive( @@ -1814,7 +6407,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceHostResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceHostResponse"; const MD5SUM: &'static str = "092ff9f63242a37704ce411703ec5eaf"; - const DEFINITION: &'static str = "string host"; + const DEFINITION: &'static str = r#"string host"#; } pub struct ServiceHost {} impl ::roslibrust_codegen::RosServiceType for ServiceHost { @@ -1839,7 +6432,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceNodeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceNodeRequest"; const MD5SUM: &'static str = "1cbcfa13b08f6d36710b9af8741e6112"; - const DEFINITION: &'static str = "string service"; + const DEFINITION: &'static str = r#"string service"#; } #[allow(non_snake_case)] #[derive( @@ -1857,7 +6450,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceNodeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceNodeResponse"; const MD5SUM: &'static str = "a94c40e70a4b82863e6e52ec16732447"; - const DEFINITION: &'static str = "string node"; + const DEFINITION: &'static str = r#"string node"#; } pub struct ServiceNode {} impl ::roslibrust_codegen::RosServiceType for ServiceNode { @@ -1882,7 +6475,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceProvidersRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceProvidersRequest"; const MD5SUM: &'static str = "1cbcfa13b08f6d36710b9af8741e6112"; - const DEFINITION: &'static str = "string service"; + const DEFINITION: &'static str = r#"string service"#; } #[allow(non_snake_case)] #[derive( @@ -1900,7 +6493,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceProvidersResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceProvidersResponse"; const MD5SUM: &'static str = "945f6849f44f061c178ab393b12c1358"; - const DEFINITION: &'static str = "string[] providers"; + const DEFINITION: &'static str = r#"string[] providers"#; } pub struct ServiceProviders {} impl ::roslibrust_codegen::RosServiceType for ServiceProviders { @@ -1925,7 +6518,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceRequestDetailsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceRequestDetailsRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; - const DEFINITION: &'static str = "string type"; + const DEFINITION: &'static str = r#"string type"#; } #[allow(non_snake_case)] #[derive( @@ -1943,7 +6536,16 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceRequestDetailsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceRequestDetailsResponse"; const MD5SUM: &'static str = "a6b8995777f214f2ed97a1e4890feb10"; - const DEFINITION: &'static str = "TypeDef[] typedefs"; + const DEFINITION: &'static str = r#"TypeDef[] typedefs +================================================================================ +MSG: rosapi/TypeDef +string type +string[] fieldnames +string[] fieldtypes +int32[] fieldarraylen +string[] examples +string[] constnames +string[] constvalues"#; } pub struct ServiceRequestDetails {} impl ::roslibrust_codegen::RosServiceType for ServiceRequestDetails { @@ -1968,7 +6570,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceResponseDetailsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceResponseDetailsRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; - const DEFINITION: &'static str = "string type"; + const DEFINITION: &'static str = r#"string type"#; } #[allow(non_snake_case)] #[derive( @@ -1986,7 +6588,16 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceResponseDetailsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceResponseDetailsResponse"; const MD5SUM: &'static str = "a6b8995777f214f2ed97a1e4890feb10"; - const DEFINITION: &'static str = "TypeDef[] typedefs"; + const DEFINITION: &'static str = r#"TypeDef[] typedefs +================================================================================ +MSG: rosapi/TypeDef +string type +string[] fieldnames +string[] fieldtypes +int32[] fieldarraylen +string[] examples +string[] constnames +string[] constvalues"#; } pub struct ServiceResponseDetails {} impl ::roslibrust_codegen::RosServiceType for ServiceResponseDetails { @@ -2011,7 +6622,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceTypeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceTypeRequest"; const MD5SUM: &'static str = "1cbcfa13b08f6d36710b9af8741e6112"; - const DEFINITION: &'static str = "string service"; + const DEFINITION: &'static str = r#"string service"#; } #[allow(non_snake_case)] #[derive( @@ -2029,7 +6640,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServiceTypeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServiceTypeResponse"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; - const DEFINITION: &'static str = "string type"; + const DEFINITION: &'static str = r#"string type"#; } pub struct ServiceType {} impl ::roslibrust_codegen::RosServiceType for ServiceType { @@ -2052,7 +6663,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServicesRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServicesRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -2070,7 +6681,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServicesResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServicesResponse"; const MD5SUM: &'static str = "e44a7e7bcb900acadbcc28b132378f0c"; - const DEFINITION: &'static str = "string[] services"; + const DEFINITION: &'static str = r#"string[] services"#; } pub struct Services {} impl ::roslibrust_codegen::RosServiceType for Services { @@ -2095,7 +6706,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServicesForTypeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/ServicesForTypeRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; - const DEFINITION: &'static str = "string type"; + const DEFINITION: &'static str = r#"string type"#; } #[allow(non_snake_case)] #[derive( @@ -2113,7 +6724,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for ServicesForTypeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/ServicesForTypeResponse"; const MD5SUM: &'static str = "e44a7e7bcb900acadbcc28b132378f0c"; - const DEFINITION: &'static str = "string[] services"; + const DEFINITION: &'static str = r#"string[] services"#; } pub struct ServicesForType {} impl ::roslibrust_codegen::RosServiceType for ServicesForType { @@ -2139,7 +6750,8 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for SetParamRequest { const ROS_TYPE_NAME: &'static str = "rosapi/SetParamRequest"; const MD5SUM: &'static str = "bc6ccc4a57f61779c8eaae61e9f422e0"; - const DEFINITION: &'static str = "string name\nstring value"; + const DEFINITION: &'static str = r#"string name +string value"#; } #[allow(non_snake_case)] #[derive( @@ -2155,7 +6767,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for SetParamResponse { const ROS_TYPE_NAME: &'static str = "rosapi/SetParamResponse"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } pub struct SetParam {} impl ::roslibrust_codegen::RosServiceType for SetParam { @@ -2180,7 +6792,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for SubscribersRequest { const ROS_TYPE_NAME: &'static str = "rosapi/SubscribersRequest"; const MD5SUM: &'static str = "d8f94bae31b356b24d0427f80426d0c3"; - const DEFINITION: &'static str = "string topic"; + const DEFINITION: &'static str = r#"string topic"#; } #[allow(non_snake_case)] #[derive( @@ -2198,7 +6810,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for SubscribersResponse { const ROS_TYPE_NAME: &'static str = "rosapi/SubscribersResponse"; const MD5SUM: &'static str = "22418cab5ba9531d8c2b738b4e56153b"; - const DEFINITION: &'static str = "string[] subscribers"; + const DEFINITION: &'static str = r#"string[] subscribers"#; } pub struct Subscribers {} impl ::roslibrust_codegen::RosServiceType for Subscribers { @@ -2223,7 +6835,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TopicTypeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/TopicTypeRequest"; const MD5SUM: &'static str = "d8f94bae31b356b24d0427f80426d0c3"; - const DEFINITION: &'static str = "string topic"; + const DEFINITION: &'static str = r#"string topic"#; } #[allow(non_snake_case)] #[derive( @@ -2241,7 +6853,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TopicTypeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/TopicTypeResponse"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; - const DEFINITION: &'static str = "string type"; + const DEFINITION: &'static str = r#"string type"#; } pub struct TopicType {} impl ::roslibrust_codegen::RosServiceType for TopicType { @@ -2264,7 +6876,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TopicsRequest { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -2283,7 +6895,8 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TopicsResponse { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsResponse"; const MD5SUM: &'static str = "d966d98fc333fa1f3135af765eac1ba8"; - const DEFINITION: &'static str = "string[] topics\nstring[] types"; + const DEFINITION: &'static str = r#"string[] topics +string[] types"#; } pub struct Topics {} impl ::roslibrust_codegen::RosServiceType for Topics { @@ -2306,7 +6919,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TopicsAndRawTypesRequest { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsAndRawTypesRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -2326,8 +6939,9 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TopicsAndRawTypesResponse { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsAndRawTypesResponse"; const MD5SUM: &'static str = "e1432466c8f64316723276ba07c59d12"; - const DEFINITION: &'static str = - "string[] topics\nstring[] types\nstring[] typedefs_full_text"; + const DEFINITION: &'static str = r#"string[] topics +string[] types +string[] typedefs_full_text"#; } pub struct TopicsAndRawTypes {} impl ::roslibrust_codegen::RosServiceType for TopicsAndRawTypes { @@ -2352,7 +6966,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TopicsForTypeRequest { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsForTypeRequest"; const MD5SUM: &'static str = "dc67331de85cf97091b7d45e5c64ab75"; - const DEFINITION: &'static str = "string type"; + const DEFINITION: &'static str = r#"string type"#; } #[allow(non_snake_case)] #[derive( @@ -2370,7 +6984,7 @@ pub mod rosapi { impl ::roslibrust_codegen::RosMessageType for TopicsForTypeResponse { const ROS_TYPE_NAME: &'static str = "rosapi/TopicsForTypeResponse"; const MD5SUM: &'static str = "b0eef9a05d4e829092fc2f2c3c2aad3d"; - const DEFINITION: &'static str = "string[] topics"; + const DEFINITION: &'static str = r#"string[] topics"#; } pub struct TopicsForType {} impl ::roslibrust_codegen::RosServiceType for TopicsForType { @@ -2411,7 +7025,10 @@ pub mod rosgraph_msgs { impl ::roslibrust_codegen::RosMessageType for Clock { const ROS_TYPE_NAME: &'static str = "rosgraph_msgs/Clock"; const MD5SUM: &'static str = "a9c97c1d230cfc112e270351a944ee47"; - const DEFINITION : & 'static str = "# roslib/Clock is used for publishing simulated time in ROS. \n# This message simply communicates the current time.\n# For more information, see http://www.ros.org/wiki/Clock\ntime clock" ; + const DEFINITION: &'static str = r#"# roslib/Clock is used for publishing simulated time in ROS. +# This message simply communicates the current time. +# For more information, see http://www.ros.org/wiki/Clock +time clock"#; } #[allow(non_snake_case)] #[derive( @@ -2436,7 +7053,40 @@ pub mod rosgraph_msgs { impl ::roslibrust_codegen::RosMessageType for Log { const ROS_TYPE_NAME: &'static str = "rosgraph_msgs/Log"; const MD5SUM: &'static str = "acffd30cd6b6de30f120938c17c593fb"; - const DEFINITION : & 'static str = "##\n## Severity level constants\n##\nbyte DEBUG=1 #debug level\nbyte INFO=2 #general level\nbyte WARN=4 #warning level\nbyte ERROR=8 #error level\nbyte FATAL=16 #fatal/critical level\n##\n## Fields\n##\nHeader header\nbyte level\nstring name # name of the node\nstring msg # message \nstring file # file the message came from\nstring function # function the message came from\nuint32 line # line the message came from\nstring[] topics # topic names that the node publishes" ; + const DEFINITION: &'static str = r#"## +## Severity level constants +## +byte DEBUG=1 #debug level +byte INFO=2 #general level +byte WARN=4 #warning level +byte ERROR=8 #error level +byte FATAL=16 #fatal/critical level +## +## Fields +## +Header header +byte level +string name # name of the node +string msg # message +string file # file the message came from +string function # function the message came from +uint32 line # line the message came from +string[] topics # topic names that the node publishes +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl Log { pub const r#DEBUG: u8 = 1u8; @@ -2474,7 +7124,38 @@ pub mod rosgraph_msgs { impl ::roslibrust_codegen::RosMessageType for TopicStatistics { const ROS_TYPE_NAME: &'static str = "rosgraph_msgs/TopicStatistics"; const MD5SUM: &'static str = "10152ed868c5097a5e2e4a89d7daa710"; - const DEFINITION : & 'static str = "# name of the topic\nstring topic\n\n# node id of the publisher\nstring node_pub\n\n# node id of the subscriber\nstring node_sub\n\n# the statistics apply to this time window\ntime window_start\ntime window_stop\n\n# number of messages delivered during the window\nint32 delivered_msgs\n# numbers of messages dropped during the window\nint32 dropped_msgs\n\n# traffic during the window, in bytes\nint32 traffic\n\n# mean/stddev/max period between two messages\nduration period_mean\nduration period_stddev\nduration period_max\n\n# mean/stddev/max age of the message based on the\n# timestamp in the message header. In case the\n# message does not have a header, it will be 0.\nduration stamp_age_mean\nduration stamp_age_stddev\nduration stamp_age_max" ; + const DEFINITION: &'static str = r#"# name of the topic +string topic + +# node id of the publisher +string node_pub + +# node id of the subscriber +string node_sub + +# the statistics apply to this time window +time window_start +time window_stop + +# number of messages delivered during the window +int32 delivered_msgs +# numbers of messages dropped during the window +int32 dropped_msgs + +# traffic during the window, in bytes +int32 traffic + +# mean/stddev/max period between two messages +duration period_mean +duration period_stddev +duration period_max + +# mean/stddev/max age of the message based on the +# timestamp in the message header. In case the +# message does not have a header, it will be 0. +duration stamp_age_mean +duration stamp_age_stddev +duration stamp_age_max"#; } } #[allow(unused_imports)] @@ -2523,7 +7204,72 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for BatteryState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/BatteryState"; const MD5SUM: &'static str = "4ddae7f048e32fda22cac764685e3974"; - const DEFINITION : & 'static str = "# Constants are chosen to match the enums in the linux kernel\n# defined in include/linux/power_supply.h as of version 3.7\n# The one difference is for style reasons the constants are\n# all uppercase not mixed case.\n\n# Power supply status constants\nuint8 POWER_SUPPLY_STATUS_UNKNOWN = 0\nuint8 POWER_SUPPLY_STATUS_CHARGING = 1\nuint8 POWER_SUPPLY_STATUS_DISCHARGING = 2\nuint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3\nuint8 POWER_SUPPLY_STATUS_FULL = 4\n\n# Power supply health constants\nuint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0\nuint8 POWER_SUPPLY_HEALTH_GOOD = 1\nuint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2\nuint8 POWER_SUPPLY_HEALTH_DEAD = 3\nuint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4\nuint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5\nuint8 POWER_SUPPLY_HEALTH_COLD = 6\nuint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7\nuint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8\n\n# Power supply technology (chemistry) constants\nuint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0\nuint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1\nuint8 POWER_SUPPLY_TECHNOLOGY_LION = 2\nuint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3\nuint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4\nuint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5\nuint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6\n\nHeader header\nfloat32 voltage # Voltage in Volts (Mandatory)\nfloat32 temperature # Temperature in Degrees Celsius (If unmeasured NaN)\nfloat32 current # Negative when discharging (A) (If unmeasured NaN)\nfloat32 charge # Current charge in Ah (If unmeasured NaN)\nfloat32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN)\nfloat32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN)\nfloat32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN)\nuint8 power_supply_status # The charging status as reported. Values defined above\nuint8 power_supply_health # The battery health metric. Values defined above\nuint8 power_supply_technology # The battery chemistry. Values defined above\nbool present # True if the battery is present\n\nfloat32[] cell_voltage # An array of individual cell voltages for each cell in the pack\n # If individual voltages unknown but number of cells known set each to NaN\nfloat32[] cell_temperature # An array of individual cell temperatures for each cell in the pack\n # If individual temperatures unknown but number of cells known set each to NaN\nstring location # The location into which the battery is inserted. (slot number or plug)\nstring serial_number # The best approximation of the battery serial number" ; + const DEFINITION: &'static str = r#"# Constants are chosen to match the enums in the linux kernel +# defined in include/linux/power_supply.h as of version 3.7 +# The one difference is for style reasons the constants are +# all uppercase not mixed case. + +# Power supply status constants +uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0 +uint8 POWER_SUPPLY_STATUS_CHARGING = 1 +uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2 +uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3 +uint8 POWER_SUPPLY_STATUS_FULL = 4 + +# Power supply health constants +uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0 +uint8 POWER_SUPPLY_HEALTH_GOOD = 1 +uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2 +uint8 POWER_SUPPLY_HEALTH_DEAD = 3 +uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 +uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 +uint8 POWER_SUPPLY_HEALTH_COLD = 6 +uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 +uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 + +# Power supply technology (chemistry) constants +uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 +uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1 +uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2 +uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3 +uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4 +uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5 +uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6 + +Header header +float32 voltage # Voltage in Volts (Mandatory) +float32 temperature # Temperature in Degrees Celsius (If unmeasured NaN) +float32 current # Negative when discharging (A) (If unmeasured NaN) +float32 charge # Current charge in Ah (If unmeasured NaN) +float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN) +float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN) +float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN) +uint8 power_supply_status # The charging status as reported. Values defined above +uint8 power_supply_health # The battery health metric. Values defined above +uint8 power_supply_technology # The battery chemistry. Values defined above +bool present # True if the battery is present + +float32[] cell_voltage # An array of individual cell voltages for each cell in the pack + # If individual voltages unknown but number of cells known set each to NaN +float32[] cell_temperature # An array of individual cell temperatures for each cell in the pack + # If individual temperatures unknown but number of cells known set each to NaN +string location # The location into which the battery is inserted. (slot number or plug) +string serial_number # The best approximation of the battery serial number +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl BatteryState { pub const r#POWER_SUPPLY_STATUS_UNKNOWN: u8 = 0u8; @@ -2574,7 +7320,173 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for CameraInfo { const ROS_TYPE_NAME: &'static str = "sensor_msgs/CameraInfo"; const MD5SUM: &'static str = "c9a58c1b0b154e0e6da7578cb991d214"; - const DEFINITION : & 'static str = "# This message defines meta information for a camera. It should be in a\n# camera namespace on topic \"camera_info\" and accompanied by up to five\n# image topics named:\n#\n# image_raw - raw data from the camera driver, possibly Bayer encoded\n# image - monochrome, distorted\n# image_color - color, distorted\n# image_rect - monochrome, rectified\n# image_rect_color - color, rectified\n#\n# The image_pipeline contains packages (image_proc, stereo_image_proc)\n# for producing the four processed image topics from image_raw and\n# camera_info. The meaning of the camera parameters are described in\n# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n#\n# The image_geometry package provides a user-friendly interface to\n# common operations using this meta information. If you want to, e.g.,\n# project a 3d point into image coordinates, we strongly recommend\n# using image_geometry.\n#\n# If the camera is uncalibrated, the matrices D, K, R, P should be left\n# zeroed out. In particular, clients may assume that K[0] == 0.0\n# indicates an uncalibrated camera.\n\n#######################################################################\n# Image acquisition info #\n#######################################################################\n\n# Time of image acquisition, camera coordinate frame ID\nHeader header # Header timestamp should be acquisition time of image\n # Header frame_id should be optical frame of camera\n # origin of frame should be optical center of camera\n # +x should point to the right in the image\n # +y should point down in the image\n # +z should point into the plane of the image\n\n\n#######################################################################\n# Calibration Parameters #\n#######################################################################\n# These are fixed during camera calibration. Their values will be the #\n# same in all messages until the camera is recalibrated. Note that #\n# self-calibrating systems may \"recalibrate\" frequently. #\n# #\n# The internal parameters can be used to warp a raw (distorted) image #\n# to: #\n# 1. An undistorted image (requires D and K) #\n# 2. A rectified image (requires D, K, R) #\n# The projection matrix P projects 3D points into the rectified image.#\n#######################################################################\n\n# The image dimensions with which the camera was calibrated. Normally\n# this will be the full camera resolution in pixels.\nuint32 height\nuint32 width\n\n# The distortion model used. Supported models are listed in\n# sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n# simple model of radial and tangential distortion - is sufficient.\nstring distortion_model\n\n# The distortion parameters, size depending on the distortion model.\n# For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\nfloat64[] D\n\n# Intrinsic camera matrix for the raw (distorted) images.\n# [fx 0 cx]\n# K = [ 0 fy cy]\n# [ 0 0 1]\n# Projects 3D points in the camera coordinate frame to 2D pixel\n# coordinates using the focal lengths (fx, fy) and principal point\n# (cx, cy).\nfloat64[9] K # 3x3 row-major matrix\n\n# Rectification matrix (stereo cameras only)\n# A rotation matrix aligning the camera coordinate system to the ideal\n# stereo image plane so that epipolar lines in both stereo images are\n# parallel.\nfloat64[9] R # 3x3 row-major matrix\n\n# Projection/camera matrix\n# [fx' 0 cx' Tx]\n# P = [ 0 fy' cy' Ty]\n# [ 0 0 1 0]\n# By convention, this matrix specifies the intrinsic (camera) matrix\n# of the processed (rectified) image. That is, the left 3x3 portion\n# is the normal camera intrinsic matrix for the rectified image.\n# It projects 3D points in the camera coordinate frame to 2D pixel\n# coordinates using the focal lengths (fx', fy') and principal point\n# (cx', cy') - these may differ from the values in K.\n# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n# also have R = the identity and P[1:3,1:3] = K.\n# For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n# position of the optical center of the second camera in the first\n# camera's frame. We assume Tz = 0 so both cameras are in the same\n# stereo image plane. The first camera always has Tx = Ty = 0. For\n# the right (second) camera of a horizontal stereo pair, Ty = 0 and\n# Tx = -fx' * B, where B is the baseline between the cameras.\n# Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n# the rectified image is given by:\n# [u v w]' = P * [X Y Z 1]'\n# x = u / w\n# y = v / w\n# This holds for both images of a stereo pair.\nfloat64[12] P # 3x4 row-major matrix\n\n\n#######################################################################\n# Operational Parameters #\n#######################################################################\n# These define the image region actually captured by the camera #\n# driver. Although they affect the geometry of the output image, they #\n# may be changed freely without recalibrating the camera. #\n#######################################################################\n\n# Binning refers here to any camera setting which combines rectangular\n# neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n# resolution of the output image to\n# (width / binning_x) x (height / binning_y).\n# The default values binning_x = binning_y = 0 is considered the same\n# as binning_x = binning_y = 1 (no subsampling).\nuint32 binning_x\nuint32 binning_y\n\n# Region of interest (subwindow of full camera resolution), given in\n# full resolution (unbinned) image coordinates. A particular ROI\n# always denotes the same window of pixels on the camera sensor,\n# regardless of binning settings.\n# The default setting of roi (all values 0) is considered the same as\n# full resolution (roi.width = width, roi.height = height).\nRegionOfInterest roi" ; + const DEFINITION: &'static str = r#"# This message defines meta information for a camera. It should be in a +# camera namespace on topic "camera_info" and accompanied by up to five +# image topics named: +# +# image_raw - raw data from the camera driver, possibly Bayer encoded +# image - monochrome, distorted +# image_color - color, distorted +# image_rect - monochrome, rectified +# image_rect_color - color, rectified +# +# The image_pipeline contains packages (image_proc, stereo_image_proc) +# for producing the four processed image topics from image_raw and +# camera_info. The meaning of the camera parameters are described in +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. +# +# The image_geometry package provides a user-friendly interface to +# common operations using this meta information. If you want to, e.g., +# project a 3d point into image coordinates, we strongly recommend +# using image_geometry. +# +# If the camera is uncalibrated, the matrices D, K, R, P should be left +# zeroed out. In particular, clients may assume that K[0] == 0.0 +# indicates an uncalibrated camera. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, camera coordinate frame ID +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into the plane of the image + + +####################################################################### +# Calibration Parameters # +####################################################################### +# These are fixed during camera calibration. Their values will be the # +# same in all messages until the camera is recalibrated. Note that # +# self-calibrating systems may "recalibrate" frequently. # +# # +# The internal parameters can be used to warp a raw (distorted) image # +# to: # +# 1. An undistorted image (requires D and K) # +# 2. A rectified image (requires D, K, R) # +# The projection matrix P projects 3D points into the rectified image.# +####################################################################### + +# The image dimensions with which the camera was calibrated. Normally +# this will be the full camera resolution in pixels. +uint32 height +uint32 width + +# The distortion model used. Supported models are listed in +# sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a +# simple model of radial and tangential distortion - is sufficient. +string distortion_model + +# The distortion parameters, size depending on the distortion model. +# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). +float64[] D + +# Intrinsic camera matrix for the raw (distorted) images. +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy). +float64[9] K # 3x3 row-major matrix + +# Rectification matrix (stereo cameras only) +# A rotation matrix aligning the camera coordinate system to the ideal +# stereo image plane so that epipolar lines in both stereo images are +# parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# [fx' 0 cx' Tx] +# P = [ 0 fy' cy' Ty] +# [ 0 0 1 0] +# By convention, this matrix specifies the intrinsic (camera) matrix +# of the processed (rectified) image. That is, the left 3x3 portion +# is the normal camera intrinsic matrix for the rectified image. +# It projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx', fy') and principal point +# (cx', cy') - these may differ from the values in K. +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will +# also have R = the identity and P[1:3,1:3] = K. +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the +# position of the optical center of the second camera in the first +# camera's frame. We assume Tz = 0 so both cameras are in the same +# stereo image plane. The first camera always has Tx = Ty = 0. For +# the right (second) camera of a horizontal stereo pair, Ty = 0 and +# Tx = -fx' * B, where B is the baseline between the cameras. +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto +# the rectified image is given by: +# [u v w]' = P * [X Y Z 1]' +# x = u / w +# y = v / w +# This holds for both images of a stereo pair. +float64[12] P # 3x4 row-major matrix + + +####################################################################### +# Operational Parameters # +####################################################################### +# These define the image region actually captured by the camera # +# driver. Although they affect the geometry of the output image, they # +# may be changed freely without recalibrating the camera. # +####################################################################### + +# Binning refers here to any camera setting which combines rectangular +# neighborhoods of pixels into larger "super-pixels." It reduces the +# resolution of the output image to +# (width / binning_x) x (height / binning_y). +# The default values binning_x = binning_y = 0 is considered the same +# as binning_x = binning_y = 1 (no subsampling). +uint32 binning_x +uint32 binning_y + +# Region of interest (subwindow of full camera resolution), given in +# full resolution (unbinned) image coordinates. A particular ROI +# always denotes the same window of pixels on the camera sensor, +# regardless of binning settings. +# The default setting of roi (all values 0) is considered the same as +# full resolution (roi.width = width, roi.height = height). +RegionOfInterest roi +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2593,7 +7505,30 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for ChannelFloat32 { const ROS_TYPE_NAME: &'static str = "sensor_msgs/ChannelFloat32"; const MD5SUM: &'static str = "3d40139cdd33dfedcb71ffeeeb42ae7f"; - const DEFINITION : & 'static str = "# This message is used by the PointCloud message to hold optional data\n# associated with each point in the cloud. The length of the values\n# array should be the same as the length of the points array in the\n# PointCloud, and each value should be associated with the corresponding\n# point.\n\n# Channel names in existing practice include:\n# \"u\", \"v\" - row and column (respectively) in the left stereo image.\n# This is opposite to usual conventions but remains for\n# historical reasons. The newer PointCloud2 message has no\n# such problem.\n# \"rgb\" - For point clouds produced by color stereo cameras. uint8\n# (R,G,B) values packed into the least significant 24 bits,\n# in order.\n# \"intensity\" - laser or pixel intensity.\n# \"distance\"\n\n# The channel name should give semantics of the channel (e.g.\n# \"intensity\" instead of \"value\").\nstring name\n\n# The values array should be 1-1 with the elements of the associated\n# PointCloud.\nfloat32[] values" ; + const DEFINITION: &'static str = r#"# This message is used by the PointCloud message to hold optional data +# associated with each point in the cloud. The length of the values +# array should be the same as the length of the points array in the +# PointCloud, and each value should be associated with the corresponding +# point. + +# Channel names in existing practice include: +# "u", "v" - row and column (respectively) in the left stereo image. +# This is opposite to usual conventions but remains for +# historical reasons. The newer PointCloud2 message has no +# such problem. +# "rgb" - For point clouds produced by color stereo cameras. uint8 +# (R,G,B) values packed into the least significant 24 bits, +# in order. +# "intensity" - laser or pixel intensity. +# "distance" + +# The channel name should give semantics of the channel (e.g. +# "intensity" instead of "value"). +string name + +# The values array should be 1-1 with the elements of the associated +# PointCloud. +float32[] values"#; } #[allow(non_snake_case)] #[derive( @@ -2613,7 +7548,34 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for CompressedImage { const ROS_TYPE_NAME: &'static str = "sensor_msgs/CompressedImage"; const MD5SUM: &'static str = "8f7a12909da2c9d3332d540a0977563f"; - const DEFINITION : & 'static str = "# This message contains a compressed image\n\nHeader header # Header timestamp should be acquisition time of image\n # Header frame_id should be optical frame of camera\n # origin of frame should be optical center of camera\n # +x should point to the right in the image\n # +y should point down in the image\n # +z should point into to plane of the image\n\nstring format # Specifies the format of the data\n # Acceptable values:\n # jpeg, png\nuint8[] data # Compressed image buffer" ; + const DEFINITION: &'static str = r#"# This message contains a compressed image + +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2633,7 +7595,33 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for FluidPressure { const ROS_TYPE_NAME: &'static str = "sensor_msgs/FluidPressure"; const MD5SUM: &'static str = "804dc5cea1c5306d6a2eb80b9833befe"; - const DEFINITION : & 'static str = "# Single pressure reading. This message is appropriate for measuring the\n # pressure inside of a fluid (air, water, etc). This also includes\n # atmospheric or barometric pressure.\n\n # This message is not appropriate for force/pressure contact sensors.\n\n Header header # timestamp of the measurement\n # frame_id is the location of the pressure sensor\n\n float64 fluid_pressure # Absolute pressure reading in Pascals.\n\n float64 variance # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Single pressure reading. This message is appropriate for measuring the + # pressure inside of a fluid (air, water, etc). This also includes + # atmospheric or barometric pressure. + + # This message is not appropriate for force/pressure contact sensors. + + Header header # timestamp of the measurement + # frame_id is the location of the pressure sensor + + float64 fluid_pressure # Absolute pressure reading in Pascals. + + float64 variance # 0 is interpreted as variance unknown +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2653,7 +7641,42 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Illuminance { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Illuminance"; const MD5SUM: &'static str = "8cf5febb0952fca9d650c3d11a81a188"; - const DEFINITION : & 'static str = "# Single photometric illuminance measurement. Light should be assumed to be\n # measured along the sensor's x-axis (the area of detection is the y-z plane).\n # The illuminance should have a 0 or positive value and be received with\n # the sensor's +X axis pointing toward the light source.\n\n # Photometric illuminance is the measure of the human eye's sensitivity of the\n # intensity of light encountering or passing through a surface.\n\n # All other Photometric and Radiometric measurements should\n # not use this message.\n # This message cannot represent:\n # Luminous intensity (candela/light source output)\n # Luminance (nits/light output per area)\n # Irradiance (watt/area), etc.\n\n Header header # timestamp is the time the illuminance was measured\n # frame_id is the location and direction of the reading\n\n float64 illuminance # Measurement of the Photometric Illuminance in Lux.\n\n float64 variance # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Single photometric illuminance measurement. Light should be assumed to be + # measured along the sensor's x-axis (the area of detection is the y-z plane). + # The illuminance should have a 0 or positive value and be received with + # the sensor's +X axis pointing toward the light source. + + # Photometric illuminance is the measure of the human eye's sensitivity of the + # intensity of light encountering or passing through a surface. + + # All other Photometric and Radiometric measurements should + # not use this message. + # This message cannot represent: + # Luminous intensity (candela/light source output) + # Luminance (nits/light output per area) + # Irradiance (watt/area), etc. + + Header header # timestamp is the time the illuminance was measured + # frame_id is the location and direction of the reading + + float64 illuminance # Measurement of the Photometric Illuminance in Lux. + + float64 variance # 0 is interpreted as variance unknown +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2677,7 +7700,48 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Image { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Image"; const MD5SUM: &'static str = "060021388200f6f0f447d0fcd9c64743"; - const DEFINITION : & 'static str = "# This message contains an uncompressed image\n# (0, 0) is at top-left corner of image\n#\n\nHeader header # Header timestamp should be acquisition time of image\n # Header frame_id should be optical frame of camera\n # origin of frame should be optical center of camera\n # +x should point to the right in the image\n # +y should point down in the image\n # +z should point into to plane of the image\n # If the frame_id here and the frame_id of the CameraInfo\n # message associated with the image conflict\n # the behavior is undefined\n\nuint32 height # image height, that is, number of rows\nuint32 width # image width, that is, number of columns\n\n# The legal values for encoding are in file src/image_encodings.cpp\n# If you want to standardize a new string format, join\n# ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\nstring encoding # Encoding of pixels -- channel meaning, ordering, size\n # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\nuint8 is_bigendian # is this data bigendian?\nuint32 step # Full row length in bytes\nuint8[] data # actual matrix data, size is (step * rows)" ; + const DEFINITION: &'static str = r#"# This message contains an uncompressed image +# (0, 0) is at top-left corner of image +# + +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + # If the frame_id here and the frame_id of the CameraInfo + # message associated with the image conflict + # the behavior is undefined + +uint32 height # image height, that is, number of rows +uint32 width # image width, that is, number of columns + +# The legal values for encoding are in file src/image_encodings.cpp +# If you want to standardize a new string format, join +# ros-users@lists.sourceforge.net and send an email proposing a new encoding. + +string encoding # Encoding of pixels -- channel meaning, ordering, size + # taken from the list of strings in include/sensor_msgs/image_encodings.h + +uint8 is_bigendian # is this data bigendian? +uint32 step # Full row length in bytes +uint8[] data # actual matrix data, size is (step * rows) +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2701,7 +7765,65 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Imu { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Imu"; const MD5SUM: &'static str = "6a62c6daae103f4ff57a132d6f95cec2"; - const DEFINITION : & 'static str = "# This is a message to hold data from an IMU (Inertial Measurement Unit)\n#\n# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n#\n# If the covariance of the measurement is known, it should be filled in (if all you know is the \n# variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n# A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the\n# data a covariance will have to be assumed or gotten from some other source\n#\n# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation \n# estimate), please set element 0 of the associated covariance matrix to -1\n# If you are interpreting this message, please check for a value of -1 in the first element of each \n# covariance matrix, and disregard the associated estimate.\n\nHeader header\n\ngeometry_msgs/Quaternion orientation\nfloat64[9] orientation_covariance # Row major about x, y, z axes\n\ngeometry_msgs/Vector3 angular_velocity\nfloat64[9] angular_velocity_covariance # Row major about x, y, z axes\n\ngeometry_msgs/Vector3 linear_acceleration\nfloat64[9] linear_acceleration_covariance # Row major x, y z" ; + const DEFINITION: &'static str = r#"# This is a message to hold data from an IMU (Inertial Measurement Unit) +# +# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec +# +# If the covariance of the measurement is known, it should be filled in (if all you know is the +# variance of each measurement, e.g. from the datasheet, just put those along the diagonal) +# A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the +# data a covariance will have to be assumed or gotten from some other source +# +# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation +# estimate), please set element 0 of the associated covariance matrix to -1 +# If you are interpreting this message, please check for a value of -1 in the first element of each +# covariance matrix, and disregard the associated estimate. + +Header header + +geometry_msgs/Quaternion orientation +float64[9] orientation_covariance # Row major about x, y, z axes + +geometry_msgs/Vector3 angular_velocity +float64[9] angular_velocity_covariance # Row major about x, y, z axes + +geometry_msgs/Vector3 linear_acceleration +float64[9] linear_acceleration_covariance # Row major x, y z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2723,7 +7845,47 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for JointState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JointState"; const MD5SUM: &'static str = "3066dcd76a6cfaef579bd0f34173e9fd"; - const DEFINITION : & 'static str = "# This is a message that holds data to describe the state of a set of torque controlled joints. \n#\n# The state of each joint (revolute or prismatic) is defined by:\n# * the position of the joint (rad or m),\n# * the velocity of the joint (rad/s or m/s) and \n# * the effort that is applied in the joint (Nm or N).\n#\n# Each joint is uniquely identified by its name\n# The header specifies the time at which the joint states were recorded. All the joint states\n# in one message have to be recorded at the same time.\n#\n# This message consists of a multiple arrays, one for each part of the joint state. \n# The goal is to make each of the fields optional. When e.g. your joints have no\n# effort associated with them, you can leave the effort array empty. \n#\n# All arrays in this message should have the same size, or be empty.\n# This is the only way to uniquely associate the joint name with the correct\n# states.\n\n\nHeader header\n\nstring[] name\nfloat64[] position\nfloat64[] velocity\nfloat64[] effort" ; + const DEFINITION: &'static str = r#"# This is a message that holds data to describe the state of a set of torque controlled joints. +# +# The state of each joint (revolute or prismatic) is defined by: +# * the position of the joint (rad or m), +# * the velocity of the joint (rad/s or m/s) and +# * the effort that is applied in the joint (Nm or N). +# +# Each joint is uniquely identified by its name +# The header specifies the time at which the joint states were recorded. All the joint states +# in one message have to be recorded at the same time. +# +# This message consists of a multiple arrays, one for each part of the joint state. +# The goal is to make each of the fields optional. When e.g. your joints have no +# effort associated with them, you can leave the effort array empty. +# +# All arrays in this message should have the same size, or be empty. +# This is the only way to uniquely associate the joint name with the correct +# states. + + +Header header + +string[] name +float64[] position +float64[] velocity +float64[] effort +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2743,7 +7905,25 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Joy { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Joy"; const MD5SUM: &'static str = "5a9ea5f83505693b71e785041e67a8bb"; - const DEFINITION : & 'static str = "# Reports the state of a joysticks axes and buttons.\nHeader header # timestamp in the header is the time the data is received from the joystick\nfloat32[] axes # the axes measurements from a joystick\nint32[] buttons # the buttons measurements from a joystick" ; + const DEFINITION: &'static str = r#"# Reports the state of a joysticks axes and buttons. +Header header # timestamp in the header is the time the data is received from the joystick +float32[] axes # the axes measurements from a joystick +int32[] buttons # the buttons measurements from a joystick +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2763,7 +7943,20 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for JoyFeedback { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JoyFeedback"; const MD5SUM: &'static str = "f4dcd73460360d98f36e55ee7f2e46f1"; - const DEFINITION : & 'static str = "# Declare of the type of feedback\nuint8 TYPE_LED = 0\nuint8 TYPE_RUMBLE = 1\nuint8 TYPE_BUZZER = 2\n\nuint8 type\n\n# This will hold an id number for each type of each feedback.\n# Example, the first led would be id=0, the second would be id=1\nuint8 id\n\n# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is\n# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on.\nfloat32 intensity" ; + const DEFINITION: &'static str = r#"# Declare of the type of feedback +uint8 TYPE_LED = 0 +uint8 TYPE_RUMBLE = 1 +uint8 TYPE_BUZZER = 2 + +uint8 type + +# This will hold an id number for each type of each feedback. +# Example, the first led would be id=0, the second would be id=1 +uint8 id + +# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is +# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. +float32 intensity"#; } impl JoyFeedback { pub const r#TYPE_LED: u8 = 0u8; @@ -2786,8 +7979,24 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for JoyFeedbackArray { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JoyFeedbackArray"; const MD5SUM: &'static str = "cde5730a895b1fc4dee6f91b754b213d"; - const DEFINITION: &'static str = - "# This message publishes values for multiple feedback at once. \nJoyFeedback[] array"; + const DEFINITION: &'static str = r#"# This message publishes values for multiple feedback at once. +JoyFeedback[] array +================================================================================ +MSG: sensor_msgs/JoyFeedback +# Declare of the type of feedback +uint8 TYPE_LED = 0 +uint8 TYPE_RUMBLE = 1 +uint8 TYPE_BUZZER = 2 + +uint8 type + +# This will hold an id number for each type of each feedback. +# Example, the first led would be id=0, the second would be id=1 +uint8 id + +# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is +# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. +float32 intensity"#; } #[allow(non_snake_case)] #[derive( @@ -2805,7 +8014,11 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for LaserEcho { const ROS_TYPE_NAME: &'static str = "sensor_msgs/LaserEcho"; const MD5SUM: &'static str = "8bc5ae449b200fba4d552b4225586696"; - const DEFINITION : & 'static str = "# This message is a submessage of MultiEchoLaserScan and is not intended\n# to be used separately.\n\nfloat32[] echoes # Multiple values of ranges or intensities.\n # Each array represents data from the same angle increment." ; + const DEFINITION: &'static str = r#"# This message is a submessage of MultiEchoLaserScan and is not intended +# to be used separately. + +float32[] echoes # Multiple values of ranges or intensities. + # Each array represents data from the same angle increment."#; } #[allow(non_snake_case)] #[derive( @@ -2832,7 +8045,50 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for LaserScan { const ROS_TYPE_NAME: &'static str = "sensor_msgs/LaserScan"; const MD5SUM: &'static str = "90c7ef2dc6895d81024acba2ac42f369"; - const DEFINITION : & 'static str = "# Single scan from a planar laser range-finder\n#\n# If you have another ranging device with different behavior (e.g. a sonar\n# array), please find or create a different message, since applications\n# will make fairly laser-specific assumptions about this data\n\nHeader header # timestamp in the header is the acquisition time of \n # the first ray in the scan.\n #\n # in frame frame_id, angles are measured around \n # the positive Z axis (counterclockwise, if Z is up)\n # with zero angle being forward along the x axis\n \nfloat32 angle_min # start angle of the scan [rad]\nfloat32 angle_max # end angle of the scan [rad]\nfloat32 angle_increment # angular distance between measurements [rad]\n\nfloat32 time_increment # time between measurements [seconds] - if your scanner\n # is moving, this will be used in interpolating position\n # of 3d points\nfloat32 scan_time # time between scans [seconds]\n\nfloat32 range_min # minimum range value [m]\nfloat32 range_max # maximum range value [m]\n\nfloat32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)\nfloat32[] intensities # intensity data [device-specific units]. If your\n # device does not provide intensities, please leave\n # the array empty." ; + const DEFINITION: &'static str = r#"# Single scan from a planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, angles are measured around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) +float32[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2852,7 +8108,55 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for MagneticField { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MagneticField"; const MD5SUM: &'static str = "2f3b0b43eed0c9501de0fa3ff89a45aa"; - const DEFINITION : & 'static str = "# Measurement of the Magnetic Field vector at a specific location.\n\n # If the covariance of the measurement is known, it should be filled in\n # (if all you know is the variance of each measurement, e.g. from the datasheet,\n #just put those along the diagonal)\n # A covariance matrix of all zeros will be interpreted as \"covariance unknown\",\n # and to use the data a covariance will have to be assumed or gotten from some\n # other source\n\n\n Header header # timestamp is the time the\n # field was measured\n # frame_id is the location and orientation\n # of the field measurement\n\n geometry_msgs/Vector3 magnetic_field # x, y, and z components of the\n # field vector in Tesla\n # If your sensor does not output 3 axes,\n # put NaNs in the components not reported.\n\n float64[9] magnetic_field_covariance # Row major about x, y, z axes\n # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Measurement of the Magnetic Field vector at a specific location. + + # If the covariance of the measurement is known, it should be filled in + # (if all you know is the variance of each measurement, e.g. from the datasheet, + #just put those along the diagonal) + # A covariance matrix of all zeros will be interpreted as "covariance unknown", + # and to use the data a covariance will have to be assumed or gotten from some + # other source + + + Header header # timestamp is the time the + # field was measured + # frame_id is the location and orientation + # of the field measurement + + geometry_msgs/Vector3 magnetic_field # x, y, and z components of the + # field vector in Tesla + # If your sensor does not output 3 axes, + # put NaNs in the components not reported. + + float64[9] magnetic_field_covariance # Row major about x, y, z axes + # 0 is interpreted as variance unknown +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2874,7 +8178,128 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for MultiDOFJointState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MultiDOFJointState"; const MD5SUM: &'static str = "690f272f0640d2631c305eeb8301e59d"; - const DEFINITION : & 'static str = "# Representation of state for joints with multiple degrees of freedom, \n# following the structure of JointState.\n#\n# It is assumed that a joint in a system corresponds to a transform that gets applied \n# along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw)\n# and those 3DOF can be expressed as a transformation matrix, and that transformation\n# matrix can be converted back to (x, y, yaw)\n#\n# Each joint is uniquely identified by its name\n# The header specifies the time at which the joint states were recorded. All the joint states\n# in one message have to be recorded at the same time.\n#\n# This message consists of a multiple arrays, one for each part of the joint state. \n# The goal is to make each of the fields optional. When e.g. your joints have no\n# wrench associated with them, you can leave the wrench array empty. \n#\n# All arrays in this message should have the same size, or be empty.\n# This is the only way to uniquely associate the joint name with the correct\n# states.\n\nHeader header\n\nstring[] joint_names\ngeometry_msgs/Transform[] transforms\ngeometry_msgs/Twist[] twist\ngeometry_msgs/Wrench[] wrench" ; + const DEFINITION: &'static str = r#"# Representation of state for joints with multiple degrees of freedom, +# following the structure of JointState. +# +# It is assumed that a joint in a system corresponds to a transform that gets applied +# along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) +# and those 3DOF can be expressed as a transformation matrix, and that transformation +# matrix can be converted back to (x, y, yaw) +# +# Each joint is uniquely identified by its name +# The header specifies the time at which the joint states were recorded. All the joint states +# in one message have to be recorded at the same time. +# +# This message consists of a multiple arrays, one for each part of the joint state. +# The goal is to make each of the fields optional. When e.g. your joints have no +# wrench associated with them, you can leave the wrench array empty. +# +# All arrays in this message should have the same size, or be empty. +# This is the only way to uniquely associate the joint name with the correct +# states. + +Header header + +string[] joint_names +geometry_msgs/Transform[] transforms +geometry_msgs/Twist[] twist +geometry_msgs/Wrench[] wrench +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Wrench +# This represents force in free space, separated into +# its linear and angular parts. +Vector3 force +Vector3 torque +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2901,7 +8326,59 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for MultiEchoLaserScan { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MultiEchoLaserScan"; const MD5SUM: &'static str = "6fefb0c6da89d7c8abe4b339f5c2f8fb"; - const DEFINITION : & 'static str = "# Single scan from a multi-echo planar laser range-finder\n#\n# If you have another ranging device with different behavior (e.g. a sonar\n# array), please find or create a different message, since applications\n# will make fairly laser-specific assumptions about this data\n\nHeader header # timestamp in the header is the acquisition time of \n # the first ray in the scan.\n #\n # in frame frame_id, angles are measured around \n # the positive Z axis (counterclockwise, if Z is up)\n # with zero angle being forward along the x axis\n \nfloat32 angle_min # start angle of the scan [rad]\nfloat32 angle_max # end angle of the scan [rad]\nfloat32 angle_increment # angular distance between measurements [rad]\n\nfloat32 time_increment # time between measurements [seconds] - if your scanner\n # is moving, this will be used in interpolating position\n # of 3d points\nfloat32 scan_time # time between scans [seconds]\n\nfloat32 range_min # minimum range value [m]\nfloat32 range_max # maximum range value [m]\n\nLaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded)\n # +Inf measurements are out of range\n # -Inf measurements are too close to determine exact distance.\nLaserEcho[] intensities # intensity data [device-specific units]. If your\n # device does not provide intensities, please leave\n # the array empty." ; + const DEFINITION: &'static str = r#"# Single scan from a multi-echo planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, angles are measured around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded) + # +Inf measurements are out of range + # -Inf measurements are too close to determine exact distance. +LaserEcho[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. +================================================================================ +MSG: sensor_msgs/LaserEcho +# This message is a submessage of MultiEchoLaserScan and is not intended +# to be used separately. + +float32[] echoes # Multiple values of ranges or intensities. + # Each array represents data from the same angle increment. +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2925,7 +8402,91 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for NavSatFix { const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatFix"; const MD5SUM: &'static str = "2d3a8cd499b9b4a0249fb98fd05cfa48"; - const DEFINITION : & 'static str = "# Navigation Satellite fix for any Global Navigation Satellite System\n#\n# Specified using the WGS 84 reference ellipsoid\n\n# header.stamp specifies the ROS time for this measurement (the\n# corresponding satellite time may be reported using the\n# sensor_msgs/TimeReference message).\n#\n# header.frame_id is the frame of reference reported by the satellite\n# receiver, usually the location of the antenna. This is a\n# Euclidean frame relative to the vehicle, not a reference\n# ellipsoid.\nHeader header\n\n# satellite fix status information\nNavSatStatus status\n\n# Latitude [degrees]. Positive is north of equator; negative is south.\nfloat64 latitude\n\n# Longitude [degrees]. Positive is east of prime meridian; negative is west.\nfloat64 longitude\n\n# Altitude [m]. Positive is above the WGS 84 ellipsoid\n# (quiet NaN if no altitude is available).\nfloat64 altitude\n\n# Position covariance [m^2] defined relative to a tangential plane\n# through the reported position. The components are East, North, and\n# Up (ENU), in row-major order.\n#\n# Beware: this coordinate system exhibits singularities at the poles.\n\nfloat64[9] position_covariance\n\n# If the covariance of the fix is known, fill it in completely. If the\n# GPS receiver provides the variance of each measurement, put them\n# along the diagonal. If only Dilution of Precision is available,\n# estimate an approximate covariance from that.\n\nuint8 COVARIANCE_TYPE_UNKNOWN = 0\nuint8 COVARIANCE_TYPE_APPROXIMATED = 1\nuint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\nuint8 COVARIANCE_TYPE_KNOWN = 3\n\nuint8 position_covariance_type" ; + const DEFINITION: &'static str = r#"# Navigation Satellite fix for any Global Navigation Satellite System +# +# Specified using the WGS 84 reference ellipsoid + +# header.stamp specifies the ROS time for this measurement (the +# corresponding satellite time may be reported using the +# sensor_msgs/TimeReference message). +# +# header.frame_id is the frame of reference reported by the satellite +# receiver, usually the location of the antenna. This is a +# Euclidean frame relative to the vehicle, not a reference +# ellipsoid. +Header header + +# satellite fix status information +NavSatStatus status + +# Latitude [degrees]. Positive is north of equator; negative is south. +float64 latitude + +# Longitude [degrees]. Positive is east of prime meridian; negative is west. +float64 longitude + +# Altitude [m]. Positive is above the WGS 84 ellipsoid +# (quiet NaN if no altitude is available). +float64 altitude + +# Position covariance [m^2] defined relative to a tangential plane +# through the reported position. The components are East, North, and +# Up (ENU), in row-major order. +# +# Beware: this coordinate system exhibits singularities at the poles. + +float64[9] position_covariance + +# If the covariance of the fix is known, fill it in completely. If the +# GPS receiver provides the variance of each measurement, put them +# along the diagonal. If only Dilution of Precision is available, +# estimate an approximate covariance from that. + +uint8 COVARIANCE_TYPE_UNKNOWN = 0 +uint8 COVARIANCE_TYPE_APPROXIMATED = 1 +uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 +uint8 COVARIANCE_TYPE_KNOWN = 3 + +uint8 position_covariance_type +================================================================================ +MSG: sensor_msgs/NavSatStatus +# Navigation Satellite fix status for any Global Navigation Satellite System + +# Whether to output an augmented fix is determined by both the fix +# type and the last time differential corrections were received. A +# fix is valid when status >= STATUS_FIX. + +int8 STATUS_NO_FIX = -1 # unable to fix position +int8 STATUS_FIX = 0 # unaugmented fix +int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation +int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation + +int8 status + +# Bits defining which Global Navigation Satellite System signals were +# used by the receiver. + +uint16 SERVICE_GPS = 1 +uint16 SERVICE_GLONASS = 2 +uint16 SERVICE_COMPASS = 4 # includes BeiDou. +uint16 SERVICE_GALILEO = 8 + +uint16 service +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl NavSatFix { pub const r#COVARIANCE_TYPE_UNKNOWN: u8 = 0u8; @@ -2950,7 +8511,28 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for NavSatStatus { const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatStatus"; const MD5SUM: &'static str = "331cdbddfa4bc96ffc3b9ad98900a54c"; - const DEFINITION : & 'static str = "# Navigation Satellite fix status for any Global Navigation Satellite System\n\n# Whether to output an augmented fix is determined by both the fix\n# type and the last time differential corrections were received. A\n# fix is valid when status >= STATUS_FIX.\n\nint8 STATUS_NO_FIX = -1 # unable to fix position\nint8 STATUS_FIX = 0 # unaugmented fix\nint8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\nint8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n\nint8 status\n\n# Bits defining which Global Navigation Satellite System signals were\n# used by the receiver.\n\nuint16 SERVICE_GPS = 1\nuint16 SERVICE_GLONASS = 2\nuint16 SERVICE_COMPASS = 4 # includes BeiDou.\nuint16 SERVICE_GALILEO = 8\n\nuint16 service" ; + const DEFINITION: &'static str = r#"# Navigation Satellite fix status for any Global Navigation Satellite System + +# Whether to output an augmented fix is determined by both the fix +# type and the last time differential corrections were received. A +# fix is valid when status >= STATUS_FIX. + +int8 STATUS_NO_FIX = -1 # unable to fix position +int8 STATUS_FIX = 0 # unaugmented fix +int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation +int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation + +int8 status + +# Bits defining which Global Navigation Satellite System signals were +# used by the receiver. + +uint16 SERVICE_GPS = 1 +uint16 SERVICE_GLONASS = 2 +uint16 SERVICE_COMPASS = 4 # includes BeiDou. +uint16 SERVICE_GALILEO = 8 + +uint16 service"#; } impl NavSatStatus { pub const r#STATUS_NO_FIX: i8 = -1i8; @@ -2980,7 +8562,74 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for PointCloud { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointCloud"; const MD5SUM: &'static str = "d8e9c3f5afbdd8a130fd1d2763945fca"; - const DEFINITION : & 'static str = "# This message holds a collection of 3d points, plus optional additional\n# information about each point.\n\n# Time of sensor data acquisition, coordinate frame ID.\nHeader header\n\n# Array of 3d points. Each Point32 should be interpreted as a 3d point\n# in the frame given in the header.\ngeometry_msgs/Point32[] points\n\n# Each channel should have the same number of elements as points array,\n# and the data in each channel should correspond 1:1 with each point.\n# Channel names in common practice are listed in ChannelFloat32.msg.\nChannelFloat32[] channels" ; + const DEFINITION: &'static str = r#"# This message holds a collection of 3d points, plus optional additional +# information about each point. + +# Time of sensor data acquisition, coordinate frame ID. +Header header + +# Array of 3d points. Each Point32 should be interpreted as a 3d point +# in the frame given in the header. +geometry_msgs/Point32[] points + +# Each channel should have the same number of elements as points array, +# and the data in each channel should correspond 1:1 with each point. +# Channel names in common practice are listed in ChannelFloat32.msg. +ChannelFloat32[] channels +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommeded to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z +================================================================================ +MSG: sensor_msgs/ChannelFloat32 +# This message is used by the PointCloud message to hold optional data +# associated with each point in the cloud. The length of the values +# array should be the same as the length of the points array in the +# PointCloud, and each value should be associated with the corresponding +# point. + +# Channel names in existing practice include: +# "u", "v" - row and column (respectively) in the left stereo image. +# This is opposite to usual conventions but remains for +# historical reasons. The newer PointCloud2 message has no +# such problem. +# "rgb" - For point clouds produced by color stereo cameras. uint8 +# (R,G,B) values packed into the least significant 24 bits, +# in order. +# "intensity" - laser or pixel intensity. +# "distance" + +# The channel name should give semantics of the channel (e.g. +# "intensity" instead of "value"). +string name + +# The values array should be 1-1 with the elements of the associated +# PointCloud. +float32[] values +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -3006,7 +8655,65 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for PointCloud2 { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointCloud2"; const MD5SUM: &'static str = "1158d486dd51d683ce2f1be655c3c181"; - const DEFINITION : & 'static str = "# This message holds a collection of N-dimensional points, which may\n# contain additional information such as normals, intensity, etc. The\n# point data is stored as a binary blob, its layout described by the\n# contents of the \"fields\" array.\n\n# The point cloud data may be organized 2d (image-like) or 1d\n# (unordered). Point clouds organized as 2d images may be produced by\n# camera depth sensors such as stereo or time-of-flight.\n\n# Time of sensor data acquisition, and the coordinate frame ID (for 3d\n# points).\nHeader header\n\n# 2D structure of the point cloud. If the cloud is unordered, height is\n# 1 and width is the length of the point cloud.\nuint32 height\nuint32 width\n\n# Describes the channels and their layout in the binary data blob.\nPointField[] fields\n\nbool is_bigendian # Is this data bigendian?\nuint32 point_step # Length of a point in bytes\nuint32 row_step # Length of a row in bytes\nuint8[] data # Actual point data, size is (row_step*height)\n\nbool is_dense # True if there are no invalid points" ; + const DEFINITION: &'static str = r#"# This message holds a collection of N-dimensional points, which may +# contain additional information such as normals, intensity, etc. The +# point data is stored as a binary blob, its layout described by the +# contents of the "fields" array. + +# The point cloud data may be organized 2d (image-like) or 1d +# (unordered). Point clouds organized as 2d images may be produced by +# camera depth sensors such as stereo or time-of-flight. + +# Time of sensor data acquisition, and the coordinate frame ID (for 3d +# points). +Header header + +# 2D structure of the point cloud. If the cloud is unordered, height is +# 1 and width is the length of the point cloud. +uint32 height +uint32 width + +# Describes the channels and their layout in the binary data blob. +PointField[] fields + +bool is_bigendian # Is this data bigendian? +uint32 point_step # Length of a point in bytes +uint32 row_step # Length of a row in bytes +uint8[] data # Actual point data, size is (row_step*height) + +bool is_dense # True if there are no invalid points +================================================================================ +MSG: sensor_msgs/PointField +# This message holds the description of one point entry in the +# PointCloud2 message format. +uint8 INT8 = 1 +uint8 UINT8 = 2 +uint8 INT16 = 3 +uint8 UINT16 = 4 +uint8 INT32 = 5 +uint8 UINT32 = 6 +uint8 FLOAT32 = 7 +uint8 FLOAT64 = 8 + +string name # Name of field +uint32 offset # Offset from start of point struct +uint8 datatype # Datatype enumeration, see above +uint32 count # How many elements in the field +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -3027,7 +8734,21 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for PointField { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointField"; const MD5SUM: &'static str = "268eacb2962780ceac86cbd17e328150"; - const DEFINITION : & 'static str = "# This message holds the description of one point entry in the\n# PointCloud2 message format.\nuint8 INT8 = 1\nuint8 UINT8 = 2\nuint8 INT16 = 3\nuint8 UINT16 = 4\nuint8 INT32 = 5\nuint8 UINT32 = 6\nuint8 FLOAT32 = 7\nuint8 FLOAT64 = 8\n\nstring name # Name of field\nuint32 offset # Offset from start of point struct\nuint8 datatype # Datatype enumeration, see above\nuint32 count # How many elements in the field" ; + const DEFINITION: &'static str = r#"# This message holds the description of one point entry in the +# PointCloud2 message format. +uint8 INT8 = 1 +uint8 UINT8 = 2 +uint8 INT16 = 3 +uint8 UINT16 = 4 +uint8 INT32 = 5 +uint8 UINT32 = 6 +uint8 FLOAT32 = 7 +uint8 FLOAT64 = 8 + +string name # Name of field +uint32 offset # Offset from start of point struct +uint8 datatype # Datatype enumeration, see above +uint32 count # How many elements in the field"#; } impl PointField { pub const r#INT8: u8 = 1u8; @@ -3060,7 +8781,61 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Range { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Range"; const MD5SUM: &'static str = "c005c34273dc426c67a020a87bc24148"; - const DEFINITION : & 'static str = "# Single range reading from an active ranger that emits energy and reports\n# one range reading that is valid along an arc at the distance measured. \n# This message is not appropriate for laser scanners. See the LaserScan\n# message if you are working with a laser scanner.\n\n# This message also can represent a fixed-distance (binary) ranger. This\n# sensor will have min_range===max_range===distance of detection.\n# These sensors follow REP 117 and will output -Inf if the object is detected\n# and +Inf if the object is outside of the detection range.\n\nHeader header # timestamp in the header is the time the ranger\n # returned the distance reading\n\n# Radiation type enums\n# If you want a value added to this list, send an email to the ros-users list\nuint8 ULTRASOUND=0\nuint8 INFRARED=1\n\nuint8 radiation_type # the type of radiation used by the sensor\n # (sound, IR, etc) [enum]\n\nfloat32 field_of_view # the size of the arc that the distance reading is\n # valid for [rad]\n # the object causing the range reading may have\n # been anywhere within -field_of_view/2 and\n # field_of_view/2 at the measured range. \n # 0 angle corresponds to the x-axis of the sensor.\n\nfloat32 min_range # minimum range value [m]\nfloat32 max_range # maximum range value [m]\n # Fixed distance rangers require min_range==max_range\n\nfloat32 range # range data [m]\n # (Note: values < range_min or > range_max\n # should be discarded)\n # Fixed distance rangers only output -Inf or +Inf.\n # -Inf represents a detection within fixed distance.\n # (Detection too close to the sensor to quantify)\n # +Inf represents no detection within the fixed distance.\n # (Object out of range)" ; + const DEFINITION: &'static str = r#"# Single range reading from an active ranger that emits energy and reports +# one range reading that is valid along an arc at the distance measured. +# This message is not appropriate for laser scanners. See the LaserScan +# message if you are working with a laser scanner. + +# This message also can represent a fixed-distance (binary) ranger. This +# sensor will have min_range===max_range===distance of detection. +# These sensors follow REP 117 and will output -Inf if the object is detected +# and +Inf if the object is outside of the detection range. + +Header header # timestamp in the header is the time the ranger + # returned the distance reading + +# Radiation type enums +# If you want a value added to this list, send an email to the ros-users list +uint8 ULTRASOUND=0 +uint8 INFRARED=1 + +uint8 radiation_type # the type of radiation used by the sensor + # (sound, IR, etc) [enum] + +float32 field_of_view # the size of the arc that the distance reading is + # valid for [rad] + # the object causing the range reading may have + # been anywhere within -field_of_view/2 and + # field_of_view/2 at the measured range. + # 0 angle corresponds to the x-axis of the sensor. + +float32 min_range # minimum range value [m] +float32 max_range # maximum range value [m] + # Fixed distance rangers require min_range==max_range + +float32 range # range data [m] + # (Note: values < range_min or > range_max + # should be discarded) + # Fixed distance rangers only output -Inf or +Inf. + # -Inf represents a detection within fixed distance. + # (Detection too close to the sensor to quantify) + # +Inf represents no detection within the fixed distance. + # (Object out of range) +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl Range { pub const r#ULTRASOUND: u8 = 0u8; @@ -3086,7 +8861,25 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for RegionOfInterest { const ROS_TYPE_NAME: &'static str = "sensor_msgs/RegionOfInterest"; const MD5SUM: &'static str = "bdb633039d588fcccb441a4d43ccfe09"; - const DEFINITION : & 'static str = "# This message is used to specify a region of interest within an image.\n#\n# When used to specify the ROI setting of the camera when the image was\n# taken, the height and width fields should either match the height and\n# width fields for the associated image; or height = width = 0\n# indicates that the full resolution image was captured.\n\nuint32 x_offset # Leftmost pixel of the ROI\n # (0 if the ROI includes the left edge of the image)\nuint32 y_offset # Topmost pixel of the ROI\n # (0 if the ROI includes the top edge of the image)\nuint32 height # Height of ROI\nuint32 width # Width of ROI\n\n# True if a distinct rectified ROI should be calculated from the \"raw\"\n# ROI in this message. Typically this should be False if the full image\n# is captured (ROI not used), and True if a subwindow is captured (ROI\n# used).\nbool do_rectify" ; + const DEFINITION: &'static str = r#"# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify"#; } #[allow(non_snake_case)] #[derive( @@ -3106,7 +8899,33 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for RelativeHumidity { const ROS_TYPE_NAME: &'static str = "sensor_msgs/RelativeHumidity"; const MD5SUM: &'static str = "8730015b05955b7e992ce29a2678d90f"; - const DEFINITION : & 'static str = "# Single reading from a relative humidity sensor. Defines the ratio of partial\n # pressure of water vapor to the saturated vapor pressure at a temperature.\n\n Header header # timestamp of the measurement\n # frame_id is the location of the humidity sensor\n\n float64 relative_humidity # Expression of the relative humidity\n # from 0.0 to 1.0.\n # 0.0 is no partial pressure of water vapor\n # 1.0 represents partial pressure of saturation\n\n float64 variance # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Single reading from a relative humidity sensor. Defines the ratio of partial + # pressure of water vapor to the saturated vapor pressure at a temperature. + + Header header # timestamp of the measurement + # frame_id is the location of the humidity sensor + + float64 relative_humidity # Expression of the relative humidity + # from 0.0 to 1.0. + # 0.0 is no partial pressure of water vapor + # 1.0 represents partial pressure of saturation + + float64 variance # 0 is interpreted as variance unknown +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -3126,7 +8945,29 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Temperature { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Temperature"; const MD5SUM: &'static str = "ff71b307acdbe7c871a5a6d7ed359100"; - const DEFINITION : & 'static str = "# Single temperature reading.\n\n Header header # timestamp is the time the temperature was measured\n # frame_id is the location of the temperature reading\n\n float64 temperature # Measurement of the Temperature in Degrees Celsius\n\n float64 variance # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Single temperature reading. + + Header header # timestamp is the time the temperature was measured + # frame_id is the location of the temperature reading + + float64 temperature # Measurement of the Temperature in Degrees Celsius + + float64 variance # 0 is interpreted as variance unknown +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -3146,7 +8987,28 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for TimeReference { const ROS_TYPE_NAME: &'static str = "sensor_msgs/TimeReference"; const MD5SUM: &'static str = "fded64a0265108ba86c3d38fb11c0c16"; - const DEFINITION : & 'static str = "# Measurement from an external time source not actively synchronized with the system clock.\n\nHeader header # stamp is system time for which measurement was valid\n # frame_id is not used \n\ntime time_ref # corresponding time from this external source\nstring source # (optional) name of time source" ; + const DEFINITION: &'static str = r#"# Measurement from an external time source not actively synchronized with the system clock. + +Header header # stamp is system time for which measurement was valid + # frame_id is not used + +time time_ref # corresponding time from this external source +string source # (optional) name of time source +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -3164,7 +9026,220 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for SetCameraInfoRequest { const ROS_TYPE_NAME: &'static str = "sensor_msgs/SetCameraInfoRequest"; const MD5SUM: &'static str = "ee34be01fdeee563d0d99cd594d5581d"; - const DEFINITION : & 'static str = "# This service requests that a camera stores the given CameraInfo \n# as that camera's calibration information.\n#\n# The width and height in the camera_info field should match what the\n# camera is currently outputting on its camera_info topic, and the camera\n# will assume that the region of the imager that is being referred to is\n# the region that the camera is currently capturing.\n\nsensor_msgs/CameraInfo camera_info # The camera_info to store" ; + const DEFINITION: &'static str = r#"# This service requests that a camera stores the given CameraInfo +# as that camera's calibration information. +# +# The width and height in the camera_info field should match what the +# camera is currently outputting on its camera_info topic, and the camera +# will assume that the region of the imager that is being referred to is +# the region that the camera is currently capturing. + +sensor_msgs/CameraInfo camera_info # The camera_info to store +================================================================================ +MSG: sensor_msgs/CameraInfo +# This message defines meta information for a camera. It should be in a +# camera namespace on topic "camera_info" and accompanied by up to five +# image topics named: +# +# image_raw - raw data from the camera driver, possibly Bayer encoded +# image - monochrome, distorted +# image_color - color, distorted +# image_rect - monochrome, rectified +# image_rect_color - color, rectified +# +# The image_pipeline contains packages (image_proc, stereo_image_proc) +# for producing the four processed image topics from image_raw and +# camera_info. The meaning of the camera parameters are described in +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. +# +# The image_geometry package provides a user-friendly interface to +# common operations using this meta information. If you want to, e.g., +# project a 3d point into image coordinates, we strongly recommend +# using image_geometry. +# +# If the camera is uncalibrated, the matrices D, K, R, P should be left +# zeroed out. In particular, clients may assume that K[0] == 0.0 +# indicates an uncalibrated camera. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, camera coordinate frame ID +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into the plane of the image + + +####################################################################### +# Calibration Parameters # +####################################################################### +# These are fixed during camera calibration. Their values will be the # +# same in all messages until the camera is recalibrated. Note that # +# self-calibrating systems may "recalibrate" frequently. # +# # +# The internal parameters can be used to warp a raw (distorted) image # +# to: # +# 1. An undistorted image (requires D and K) # +# 2. A rectified image (requires D, K, R) # +# The projection matrix P projects 3D points into the rectified image.# +####################################################################### + +# The image dimensions with which the camera was calibrated. Normally +# this will be the full camera resolution in pixels. +uint32 height +uint32 width + +# The distortion model used. Supported models are listed in +# sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a +# simple model of radial and tangential distortion - is sufficient. +string distortion_model + +# The distortion parameters, size depending on the distortion model. +# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). +float64[] D + +# Intrinsic camera matrix for the raw (distorted) images. +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy). +float64[9] K # 3x3 row-major matrix + +# Rectification matrix (stereo cameras only) +# A rotation matrix aligning the camera coordinate system to the ideal +# stereo image plane so that epipolar lines in both stereo images are +# parallel. +float64[9] R # 3x3 row-major matrix + +# Projection/camera matrix +# [fx' 0 cx' Tx] +# P = [ 0 fy' cy' Ty] +# [ 0 0 1 0] +# By convention, this matrix specifies the intrinsic (camera) matrix +# of the processed (rectified) image. That is, the left 3x3 portion +# is the normal camera intrinsic matrix for the rectified image. +# It projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx', fy') and principal point +# (cx', cy') - these may differ from the values in K. +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will +# also have R = the identity and P[1:3,1:3] = K. +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the +# position of the optical center of the second camera in the first +# camera's frame. We assume Tz = 0 so both cameras are in the same +# stereo image plane. The first camera always has Tx = Ty = 0. For +# the right (second) camera of a horizontal stereo pair, Ty = 0 and +# Tx = -fx' * B, where B is the baseline between the cameras. +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto +# the rectified image is given by: +# [u v w]' = P * [X Y Z 1]' +# x = u / w +# y = v / w +# This holds for both images of a stereo pair. +float64[12] P # 3x4 row-major matrix + + +####################################################################### +# Operational Parameters # +####################################################################### +# These define the image region actually captured by the camera # +# driver. Although they affect the geometry of the output image, they # +# may be changed freely without recalibrating the camera. # +####################################################################### + +# Binning refers here to any camera setting which combines rectangular +# neighborhoods of pixels into larger "super-pixels." It reduces the +# resolution of the output image to +# (width / binning_x) x (height / binning_y). +# The default values binning_x = binning_y = 0 is considered the same +# as binning_x = binning_y = 1 (no subsampling). +uint32 binning_x +uint32 binning_y + +# Region of interest (subwindow of full camera resolution), given in +# full resolution (unbinned) image coordinates. A particular ROI +# always denotes the same window of pixels on the camera sensor, +# regardless of binning settings. +# The default setting of roi (all values 0) is considered the same as +# full resolution (roi.width = width, roi.height = height). +RegionOfInterest roi +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -3183,7 +9258,8 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for SetCameraInfoResponse { const ROS_TYPE_NAME: &'static str = "sensor_msgs/SetCameraInfoResponse"; const MD5SUM: &'static str = "2ec6f3eff0161f4257b808b12bc830c2"; - const DEFINITION : & 'static str = "bool success # True if the call succeeded\nstring status_message # Used to give details about success" ; + const DEFINITION: &'static str = r#"bool success # True if the call succeeded +string status_message # Used to give details about success"#; } pub struct SetCameraInfo {} impl ::roslibrust_codegen::RosServiceType for SetCameraInfo { @@ -3225,7 +9301,23 @@ pub mod shape_msgs { impl ::roslibrust_codegen::RosMessageType for Mesh { const ROS_TYPE_NAME: &'static str = "shape_msgs/Mesh"; const MD5SUM: &'static str = "1ffdae9486cd3316a121c578b47a85cc"; - const DEFINITION : & 'static str = "# Definition of a mesh\n\n# list of triangles; the index values refer to positions in vertices[]\nMeshTriangle[] triangles\n\n# the actual vertices that make up the mesh\ngeometry_msgs/Point[] vertices" ; + const DEFINITION: &'static str = r#"# Definition of a mesh + +# list of triangles; the index values refer to positions in vertices[] +MeshTriangle[] triangles + +# the actual vertices that make up the mesh +geometry_msgs/Point[] vertices +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: shape_msgs/MeshTriangle +# Definition of a triangle's vertices +uint32[3] vertex_indices"#; } #[allow(non_snake_case)] #[derive( @@ -3243,8 +9335,8 @@ pub mod shape_msgs { impl ::roslibrust_codegen::RosMessageType for MeshTriangle { const ROS_TYPE_NAME: &'static str = "shape_msgs/MeshTriangle"; const MD5SUM: &'static str = "23688b2e6d2de3d32fe8af104a903253"; - const DEFINITION: &'static str = - "# Definition of a triangle's vertices\nuint32[3] vertex_indices"; + const DEFINITION: &'static str = r#"# Definition of a triangle's vertices +uint32[3] vertex_indices"#; } #[allow(non_snake_case)] #[derive( @@ -3262,7 +9354,14 @@ pub mod shape_msgs { impl ::roslibrust_codegen::RosMessageType for Plane { const ROS_TYPE_NAME: &'static str = "shape_msgs/Plane"; const MD5SUM: &'static str = "2c1b92ed8f31492f8e73f6a4a44ca796"; - const DEFINITION : & 'static str = "# Representation of a plane, using the plane equation ax + by + cz + d = 0\n\n# a := coef[0]\n# b := coef[1]\n# c := coef[2]\n# d := coef[3]\n\nfloat64[4] coef" ; + const DEFINITION: &'static str = r#"# Representation of a plane, using the plane equation ax + by + cz + d = 0 + +# a := coef[0] +# b := coef[1] +# c := coef[2] +# d := coef[3] + +float64[4] coef"#; } #[allow(non_snake_case)] #[derive( @@ -3281,7 +9380,48 @@ pub mod shape_msgs { impl ::roslibrust_codegen::RosMessageType for SolidPrimitive { const ROS_TYPE_NAME: &'static str = "shape_msgs/SolidPrimitive"; const MD5SUM: &'static str = "d8f8cbc74c5ff283fca29569ccefb45d"; - const DEFINITION : & 'static str = "# Define box, sphere, cylinder, cone \n# All shapes are defined to have their bounding boxes centered around 0,0,0.\n\nuint8 BOX=1\nuint8 SPHERE=2\nuint8 CYLINDER=3\nuint8 CONE=4\n\n# The type of the shape\nuint8 type\n\n\n# The dimensions of the shape\nfloat64[] dimensions\n\n# The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array\n\n# For the BOX type, the X, Y, and Z dimensions are the length of the corresponding\n# sides of the box.\nuint8 BOX_X=0\nuint8 BOX_Y=1\nuint8 BOX_Z=2\n\n\n# For the SPHERE type, only one component is used, and it gives the radius of\n# the sphere.\nuint8 SPHERE_RADIUS=0\n\n\n# For the CYLINDER and CONE types, the center line is oriented along\n# the Z axis. Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component\n# of dimensions gives the height of the cylinder (cone). The\n# CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the\n# radius of the base of the cylinder (cone). Cone and cylinder\n# primitives are defined to be circular. The tip of the cone is\n# pointing up, along +Z axis.\n\nuint8 CYLINDER_HEIGHT=0\nuint8 CYLINDER_RADIUS=1\n\nuint8 CONE_HEIGHT=0\nuint8 CONE_RADIUS=1" ; + const DEFINITION: &'static str = r#"# Define box, sphere, cylinder, cone +# All shapes are defined to have their bounding boxes centered around 0,0,0. + +uint8 BOX=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 CONE=4 + +# The type of the shape +uint8 type + + +# The dimensions of the shape +float64[] dimensions + +# The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array + +# For the BOX type, the X, Y, and Z dimensions are the length of the corresponding +# sides of the box. +uint8 BOX_X=0 +uint8 BOX_Y=1 +uint8 BOX_Z=2 + + +# For the SPHERE type, only one component is used, and it gives the radius of +# the sphere. +uint8 SPHERE_RADIUS=0 + + +# For the CYLINDER and CONE types, the center line is oriented along +# the Z axis. Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component +# of dimensions gives the height of the cylinder (cone). The +# CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the +# radius of the base of the cylinder (cone). Cone and cylinder +# primitives are defined to be circular. The tip of the cone is +# pointing up, along +Z axis. + +uint8 CYLINDER_HEIGHT=0 +uint8 CYLINDER_RADIUS=1 + +uint8 CONE_HEIGHT=0 +uint8 CONE_RADIUS=1"#; } impl SolidPrimitive { pub const r#BOX: u8 = 1u8; @@ -3329,7 +9469,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Bool { const ROS_TYPE_NAME: &'static str = "std_msgs/Bool"; const MD5SUM: &'static str = "8b94c1b53db61fb6aed406028ad6332a"; - const DEFINITION: &'static str = "bool data"; + const DEFINITION: &'static str = r#"bool data"#; } #[allow(non_snake_case)] #[derive( @@ -3347,7 +9487,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Byte { const ROS_TYPE_NAME: &'static str = "std_msgs/Byte"; const MD5SUM: &'static str = "ad736a2e8818154c487bb80fe42ce43b"; - const DEFINITION: &'static str = "byte data"; + const DEFINITION: &'static str = r#"byte data"#; } #[allow(non_snake_case)] #[derive( @@ -3366,7 +9506,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for ByteMultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/ByteMultiArray"; const MD5SUM: &'static str = "70ea476cbcfd65ac2f68f3cda1e891fe"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nbyte[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +byte[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3384,7 +9566,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Char { const ROS_TYPE_NAME: &'static str = "std_msgs/Char"; const MD5SUM: &'static str = "1bf77f25acecdedba0e224b162199717"; - const DEFINITION: &'static str = "char data"; + const DEFINITION: &'static str = r#"char data"#; } #[allow(non_snake_case)] #[derive( @@ -3405,7 +9587,10 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for ColorRGBA { const ROS_TYPE_NAME: &'static str = "std_msgs/ColorRGBA"; const MD5SUM: &'static str = "a29a96539573343b1310c73607334b00"; - const DEFINITION: &'static str = "float32 r\nfloat32 g\nfloat32 b\nfloat32 a"; + const DEFINITION: &'static str = r#"float32 r +float32 g +float32 b +float32 a"#; } #[allow(non_snake_case)] #[derive( @@ -3423,7 +9608,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Duration { const ROS_TYPE_NAME: &'static str = "std_msgs/Duration"; const MD5SUM: &'static str = "3e286caf4241d664e55f3ad380e2ae46"; - const DEFINITION: &'static str = "duration data"; + const DEFINITION: &'static str = r#"duration data"#; } #[allow(non_snake_case)] #[derive( @@ -3439,7 +9624,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Empty { const ROS_TYPE_NAME: &'static str = "std_msgs/Empty"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -3457,7 +9642,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Float32 { const ROS_TYPE_NAME: &'static str = "std_msgs/Float32"; const MD5SUM: &'static str = "73fcbf46b49191e672908e50842a83d4"; - const DEFINITION: &'static str = "float32 data"; + const DEFINITION: &'static str = r#"float32 data"#; } #[allow(non_snake_case)] #[derive( @@ -3476,7 +9661,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Float32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Float32MultiArray"; const MD5SUM: &'static str = "6a40e0ffa6a17a503ac3f8616991b1f6"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nfloat32[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float32[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3494,7 +9721,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Float64 { const ROS_TYPE_NAME: &'static str = "std_msgs/Float64"; const MD5SUM: &'static str = "fdb28210bfa9d7c91146260178d9a584"; - const DEFINITION: &'static str = "float64 data"; + const DEFINITION: &'static str = r#"float64 data"#; } #[allow(non_snake_case)] #[derive( @@ -3513,7 +9740,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Float64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Float64MultiArray"; const MD5SUM: &'static str = "4b7d974086d4060e7db4613a7e6c3ba4"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nfloat64[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float64[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3533,7 +9802,19 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Header { const ROS_TYPE_NAME: &'static str = "std_msgs/Header"; const MD5SUM: &'static str = "2176decaecbce78abc3b96ef049fabed"; - const DEFINITION : & 'static str = "# Standard metadata for higher-level stamped data types.\n# This is generally used to communicate timestamped data \n# in a particular coordinate frame.\n# \n# sequence ID: consecutively increasing ID \nuint32 seq\n#Two-integer timestamp that is expressed as:\n# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n# time-handling sugar is provided by the client library\ntime stamp\n#Frame this data is associated with\nstring frame_id" ; + const DEFINITION: &'static str = r#"# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -3551,7 +9832,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int16 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int16"; const MD5SUM: &'static str = "8524586e34fbd7cb1c08c5f5f1ca0e57"; - const DEFINITION: &'static str = "int16 data"; + const DEFINITION: &'static str = r#"int16 data"#; } #[allow(non_snake_case)] #[derive( @@ -3570,7 +9851,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int16MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int16MultiArray"; const MD5SUM: &'static str = "d9338d7f523fcb692fae9d0a0e9f067c"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nint16[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int16[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3588,7 +9911,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int32 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int32"; const MD5SUM: &'static str = "da5909fbe378aeaf85e547e830cc1bb7"; - const DEFINITION: &'static str = "int32 data"; + const DEFINITION: &'static str = r#"int32 data"#; } #[allow(non_snake_case)] #[derive( @@ -3607,7 +9930,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int32MultiArray"; const MD5SUM: &'static str = "1d99f79f8b325b44fee908053e9c945b"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nint32[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int32[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3625,7 +9990,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int64 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int64"; const MD5SUM: &'static str = "34add168574510e6e17f5d23ecc077ef"; - const DEFINITION: &'static str = "int64 data"; + const DEFINITION: &'static str = r#"int64 data"#; } #[allow(non_snake_case)] #[derive( @@ -3644,7 +10009,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int64MultiArray"; const MD5SUM: &'static str = "54865aa6c65be0448113a2afc6a49270"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nint64[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int64[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3662,7 +10069,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int8 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int8"; const MD5SUM: &'static str = "27ffa0c9c4b8fb8492252bcad9e5c57b"; - const DEFINITION: &'static str = "int8 data"; + const DEFINITION: &'static str = r#"int8 data"#; } #[allow(non_snake_case)] #[derive( @@ -3681,7 +10088,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int8MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int8MultiArray"; const MD5SUM: &'static str = "d7c1af35a1b4781bbe79e03dd94b7c13"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nint8[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int8[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3701,7 +10150,9 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for MultiArrayDimension { const ROS_TYPE_NAME: &'static str = "std_msgs/MultiArrayDimension"; const MD5SUM: &'static str = "4cd0c83a8683deae40ecdac60e53bfa8"; - const DEFINITION : & 'static str = "string label # label of given dimension\nuint32 size # size of given dimension (in type units)\nuint32 stride # stride of given dimension" ; + const DEFINITION: &'static str = r#"string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3720,7 +10171,37 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for MultiArrayLayout { const ROS_TYPE_NAME: &'static str = "std_msgs/MultiArrayLayout"; const MD5SUM: &'static str = "0fed2a11c13e11c5571b4e2a995a91a3"; - const DEFINITION : & 'static str = "# The multiarray declares a generic multi-dimensional array of a\n# particular data type. Dimensions are ordered from outer most\n# to inner most.\n\nMultiArrayDimension[] dim # Array of dimension properties\nuint32 data_offset # padding elements at front of data\n\n# Accessors should ALWAYS be written in terms of dimension stride\n# and specified outer-most dimension first.\n# \n# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n#\n# A standard, 3-channel 640x480 image with interleaved color channels\n# would be specified as:\n#\n# dim[0].label = \"height\"\n# dim[0].size = 480\n# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n# dim[1].label = \"width\"\n# dim[1].size = 640\n# dim[1].stride = 3*640 = 1920\n# dim[2].label = \"channel\"\n# dim[2].size = 3\n# dim[2].stride = 3\n#\n# multiarray(i,j,k) refers to the ith row, jth column, and kth channel." ; + const DEFINITION: &'static str = r#"# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3738,7 +10219,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for String { const ROS_TYPE_NAME: &'static str = "std_msgs/String"; const MD5SUM: &'static str = "992ce8a1687cec8c8bd883ec73ca41d1"; - const DEFINITION: &'static str = "string data"; + const DEFINITION: &'static str = r#"string data"#; } #[allow(non_snake_case)] #[derive( @@ -3756,7 +10237,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Time { const ROS_TYPE_NAME: &'static str = "std_msgs/Time"; const MD5SUM: &'static str = "cd7166c74c552c311fbcc2fe5a7bc289"; - const DEFINITION: &'static str = "time data"; + const DEFINITION: &'static str = r#"time data"#; } #[allow(non_snake_case)] #[derive( @@ -3774,7 +10255,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt16 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt16"; const MD5SUM: &'static str = "1df79edf208b629fe6b81923a544552d"; - const DEFINITION: &'static str = "uint16 data"; + const DEFINITION: &'static str = r#"uint16 data"#; } #[allow(non_snake_case)] #[derive( @@ -3793,7 +10274,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt16MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt16MultiArray"; const MD5SUM: &'static str = "52f264f1c973c4b73790d384c6cb4484"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nuint16[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint16[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3811,7 +10334,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt32 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt32"; const MD5SUM: &'static str = "304a39449588c7f8ce2df6e8001c5fce"; - const DEFINITION: &'static str = "uint32 data"; + const DEFINITION: &'static str = r#"uint32 data"#; } #[allow(non_snake_case)] #[derive( @@ -3830,7 +10353,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt32MultiArray"; const MD5SUM: &'static str = "4d6a180abc9be191b96a7eda6c8a233d"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nuint32[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint32[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3848,7 +10413,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt64 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt64"; const MD5SUM: &'static str = "1b2a79973e8bf53d7b53acb71299cb57"; - const DEFINITION: &'static str = "uint64 data"; + const DEFINITION: &'static str = r#"uint64 data"#; } #[allow(non_snake_case)] #[derive( @@ -3867,7 +10432,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt64MultiArray"; const MD5SUM: &'static str = "6088f127afb1d6c72927aa1247e945af"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nuint64[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint64[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -3885,7 +10492,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt8 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt8"; const MD5SUM: &'static str = "7c8164229e7d2c17eb95e9231617fdee"; - const DEFINITION: &'static str = "uint8 data"; + const DEFINITION: &'static str = r#"uint8 data"#; } #[allow(non_snake_case)] #[derive( @@ -3904,7 +10511,49 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt8MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt8MultiArray"; const MD5SUM: &'static str = "82373f1612381bb6ee473b5cd6f5d89c"; - const DEFINITION : & 'static str = "# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nuint8[] data # array of data" ; + const DEFINITION: &'static str = r#"# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint8[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding elements at front of data + +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. +================================================================================ +MSG: std_msgs/MultiArrayDimension +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } } #[allow(unused_imports)] @@ -3936,7 +10585,7 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for EmptyRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/EmptyRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -3952,7 +10601,7 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for EmptyResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/EmptyResponse"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } pub struct Empty {} impl ::roslibrust_codegen::RosServiceType for Empty { @@ -3977,7 +10626,7 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for SetBoolRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/SetBoolRequest"; const MD5SUM: &'static str = "8b94c1b53db61fb6aed406028ad6332a"; - const DEFINITION: &'static str = "bool data # e.g. for hardware enabling / disabling"; + const DEFINITION: &'static str = r#"bool data # e.g. for hardware enabling / disabling"#; } #[allow(non_snake_case)] #[derive( @@ -3996,7 +10645,8 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for SetBoolResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/SetBoolResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; - const DEFINITION : & 'static str = "bool success # indicate successful run of triggered service\nstring message # informational, e.g. for error messages" ; + const DEFINITION: &'static str = r#"bool success # indicate successful run of triggered service +string message # informational, e.g. for error messages"#; } pub struct SetBool {} impl ::roslibrust_codegen::RosServiceType for SetBool { @@ -4019,7 +10669,7 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for TriggerRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/TriggerRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -4038,7 +10688,8 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for TriggerResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/TriggerResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; - const DEFINITION : & 'static str = "bool success # indicate successful run of triggered service\nstring message # informational, e.g. for error messages" ; + const DEFINITION: &'static str = r#"bool success # indicate successful run of triggered service +string message # informational, e.g. for error messages"#; } pub struct Trigger {} impl ::roslibrust_codegen::RosServiceType for Trigger { @@ -4086,7 +10737,115 @@ pub mod stereo_msgs { impl ::roslibrust_codegen::RosMessageType for DisparityImage { const ROS_TYPE_NAME: &'static str = "stereo_msgs/DisparityImage"; const MD5SUM: &'static str = "04a177815f75271039fa21f16acad8c9"; - const DEFINITION : & 'static str = "# Separate header for compatibility with current TimeSynchronizer.\n# Likely to be removed in a later release, use image.header instead.\nHeader header\n\n# Floating point disparity image. The disparities are pre-adjusted for any\n# x-offset between the principal points of the two cameras (in the case\n# that they are verged). That is: d = x_l - x_r - (cx_l - cx_r)\nsensor_msgs/Image image\n\n# Stereo geometry. For disparity d, the depth from the camera is Z = fT/d.\nfloat32 f # Focal length, pixels\nfloat32 T # Baseline, world units\n\n# Subwindow of (potentially) valid disparity values.\nsensor_msgs/RegionOfInterest valid_window\n\n# The range of disparities searched.\n# In the disparity image, any disparity less than min_disparity is invalid.\n# The disparity search range defines the horopter, or 3D volume that the\n# stereo algorithm can \"see\". Points with Z outside of:\n# Z_min = fT / max_disparity\n# Z_max = fT / min_disparity\n# could not be found.\nfloat32 min_disparity\nfloat32 max_disparity\n\n# Smallest allowed disparity increment. The smallest achievable depth range\n# resolution is delta_Z = (Z^2/fT)*delta_d.\nfloat32 delta_d" ; + const DEFINITION: &'static str = r#"# Separate header for compatibility with current TimeSynchronizer. +# Likely to be removed in a later release, use image.header instead. +Header header + +# Floating point disparity image. The disparities are pre-adjusted for any +# x-offset between the principal points of the two cameras (in the case +# that they are verged). That is: d = x_l - x_r - (cx_l - cx_r) +sensor_msgs/Image image + +# Stereo geometry. For disparity d, the depth from the camera is Z = fT/d. +float32 f # Focal length, pixels +float32 T # Baseline, world units + +# Subwindow of (potentially) valid disparity values. +sensor_msgs/RegionOfInterest valid_window + +# The range of disparities searched. +# In the disparity image, any disparity less than min_disparity is invalid. +# The disparity search range defines the horopter, or 3D volume that the +# stereo algorithm can "see". Points with Z outside of: +# Z_min = fT / max_disparity +# Z_max = fT / min_disparity +# could not be found. +float32 min_disparity +float32 max_disparity + +# Smallest allowed disparity increment. The smallest achievable depth range +# resolution is delta_Z = (Z^2/fT)*delta_d. +float32 delta_d +================================================================================ +MSG: sensor_msgs/Image +# This message contains an uncompressed image +# (0, 0) is at top-left corner of image +# + +Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + # If the frame_id here and the frame_id of the CameraInfo + # message associated with the image conflict + # the behavior is undefined + +uint32 height # image height, that is, number of rows +uint32 width # image width, that is, number of columns + +# The legal values for encoding are in file src/image_encodings.cpp +# If you want to standardize a new string format, join +# ros-users@lists.sourceforge.net and send an email proposing a new encoding. + +string encoding # Encoding of pixels -- channel meaning, ordering, size + # taken from the list of strings in include/sensor_msgs/image_encodings.h + +uint8 is_bigendian # is this data bigendian? +uint32 step # Full row length in bytes +uint8[] data # actual matrix data, size is (step * rows) +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } } #[allow(unused_imports)] @@ -4118,7 +10877,12 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for Constants { const ROS_TYPE_NAME: &'static str = "test_msgs/Constants"; const MD5SUM: &'static str = "027df5f26b72c57b1e40902038ca3eec"; - const DEFINITION : & 'static str = "string TEST_STR=\"/topic\"\nstring TEST_STR_2 = '/topic_2'\n# Apparently unquoted strings are also valid?\n# Pulled from https://github.com/ros/bond_core/blob/kinetic-devel/bond/msg/Constants.msg\nstring DISABLE_HEARTBEAT_TIMEOUT_PARAM=/bond_disable_heartbeat_timeout\nfloat32 TEST_FLOAT=0 # testing" ; + const DEFINITION: &'static str = r#"string TEST_STR="/topic" +string TEST_STR_2 = '/topic_2' +# Apparently unquoted strings are also valid? +# Pulled from https://github.com/ros/bond_core/blob/kinetic-devel/bond/msg/Constants.msg +string DISABLE_HEARTBEAT_TIMEOUT_PARAM=/bond_disable_heartbeat_timeout +float32 TEST_FLOAT=0 # testing"#; } impl Constants { pub const r#TEST_STR: &'static str = "\"/topic\""; @@ -4144,7 +10908,23 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for Float64Stamped { const ROS_TYPE_NAME: &'static str = "test_msgs/Float64Stamped"; const MD5SUM: &'static str = "d053817de0764f9ee90dbc89c4cdd751"; - const DEFINITION: &'static str = "Header header\nfloat64 value"; + const DEFINITION: &'static str = r#"Header header +float64 value +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -4162,7 +10942,7 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for LoggerLevel { const ROS_TYPE_NAME: &'static str = "test_msgs/LoggerLevel"; const MD5SUM: &'static str = "097b0e938d0dd7788057f4cdc9013238"; - const DEFINITION: &'static str = "string level"; + const DEFINITION: &'static str = r#"string level"#; } #[allow(non_snake_case)] #[derive( @@ -4182,7 +10962,18 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for Metric { const ROS_TYPE_NAME: &'static str = "test_msgs/Metric"; const MD5SUM: &'static str = "474be567370f515a7d5d3f3243aad369"; - const DEFINITION : & 'static str = "#Metric data type\n#For logging a set of points, e.g. for a pie chart\n\nstring name\nfloat64 time\nMetricPair[] data" ; + const DEFINITION: &'static str = r#"#Metric data type +#For logging a set of points, e.g. for a pie chart + +string name +float64 time +MetricPair[] data +================================================================================ +MSG: test_msgs/MetricPair +#Data type for storing the key/value pairs from the Metric.data map + +string key +float64 value"#; } #[allow(non_snake_case)] #[derive( @@ -4201,7 +10992,10 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for MetricPair { const ROS_TYPE_NAME: &'static str = "test_msgs/MetricPair"; const MD5SUM: &'static str = "a681f679e1c39fbe570b7737e7cf183d"; - const DEFINITION : & 'static str = "#Data type for storing the key/value pairs from the Metric.data map\n\nstring key\nfloat64 value" ; + const DEFINITION: &'static str = r#"#Data type for storing the key/value pairs from the Metric.data map + +string key +float64 value"#; } #[allow(non_snake_case)] #[derive( @@ -4221,7 +11015,22 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for NodeInfo { const ROS_TYPE_NAME: &'static str = "test_msgs/NodeInfo"; const MD5SUM: &'static str = "7fab1acc377fd48898b00b7f3a897f47"; - const DEFINITION : & 'static str = "string node_name\nint64 pid\n\n# Node is created, but is not yet initialized.\nuint8 STATUS_UNINITIALIZED=0\n# Node is initialized, but not connected.\nuint8 STATUS_DISCONNECTED=1\n# Node is initialized, connected, and running successfully.\nuint8 STATUS_RUNNING=2\n# Node is initialized and connected, but has a run error.\nuint8 STATUS_RUN_ERROR=3\n# Node was running, and is now shutting down.\nuint8 STATUS_SHUTTING_DOWN=4\n# Node is stopped.\nuint8 STATUS_SHUTDOWN=5\nuint8 status" ; + const DEFINITION: &'static str = r#"string node_name +int64 pid + +# Node is created, but is not yet initialized. +uint8 STATUS_UNINITIALIZED=0 +# Node is initialized, but not connected. +uint8 STATUS_DISCONNECTED=1 +# Node is initialized, connected, and running successfully. +uint8 STATUS_RUNNING=2 +# Node is initialized and connected, but has a run error. +uint8 STATUS_RUN_ERROR=3 +# Node was running, and is now shutting down. +uint8 STATUS_SHUTTING_DOWN=4 +# Node is stopped. +uint8 STATUS_SHUTDOWN=5 +uint8 status"#; } impl NodeInfo { pub const r#STATUS_UNINITIALIZED: u8 = 0u8; @@ -4248,7 +11057,11 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for AddTwoIntsRequest { const ROS_TYPE_NAME: &'static str = "test_msgs/AddTwoIntsRequest"; const MD5SUM: &'static str = "36d09b846be0b371c5f190354dd3153e"; - const DEFINITION : & 'static str = "# AddTwoInts.srv\n# --- for funsies\n# From this ROS tutorial: http://wiki.ros.org/ROS/Tutorials/CreatingMsgAndSrv#Creating_a_srv\nint64 a\nint64 b" ; + const DEFINITION: &'static str = r#"# AddTwoInts.srv +# --- for funsies +# From this ROS tutorial: http://wiki.ros.org/ROS/Tutorials/CreatingMsgAndSrv#Creating_a_srv +int64 a +int64 b"#; } #[allow(non_snake_case)] #[derive( @@ -4266,7 +11079,8 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for AddTwoIntsResponse { const ROS_TYPE_NAME: &'static str = "test_msgs/AddTwoIntsResponse"; const MD5SUM: &'static str = "b88405221c77b1878a3cbbfff53428d7"; - const DEFINITION: &'static str = "# Overflow? What overflow?\nint64 sum"; + const DEFINITION: &'static str = r#"# Overflow? What overflow? +int64 sum"#; } pub struct AddTwoInts {} impl ::roslibrust_codegen::RosServiceType for AddTwoInts { @@ -4291,8 +11105,8 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for RoundTripArrayRequest { const ROS_TYPE_NAME: &'static str = "test_msgs/RoundTripArrayRequest"; const MD5SUM: &'static str = "d159f2bd8169d3b3339e6f1fce045c6d"; - const DEFINITION: &'static str = - "# Purpose of this array is send and receive a large payload \nuint8[] bytes"; + const DEFINITION: &'static str = r#"# Purpose of this array is send and receive a large payload +uint8[] bytes"#; } #[allow(non_snake_case)] #[derive( @@ -4310,7 +11124,7 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for RoundTripArrayResponse { const ROS_TYPE_NAME: &'static str = "test_msgs/RoundTripArrayResponse"; const MD5SUM: &'static str = "d159f2bd8169d3b3339e6f1fce045c6d"; - const DEFINITION: &'static str = "uint8[] bytes"; + const DEFINITION: &'static str = r#"uint8[] bytes"#; } pub struct RoundTripArray {} impl ::roslibrust_codegen::RosServiceType for RoundTripArray { @@ -4353,8 +11167,35 @@ pub mod trajectory_msgs { impl ::roslibrust_codegen::RosMessageType for JointTrajectory { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/JointTrajectory"; const MD5SUM: &'static str = "65b4f94a94d1ed67169da35a02f33d3f"; - const DEFINITION: &'static str = - "Header header\nstring[] joint_names\nJointTrajectoryPoint[] points"; + const DEFINITION: &'static str = r#"Header header +string[] joint_names +JointTrajectoryPoint[] points +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: trajectory_msgs/JointTrajectoryPoint +# Each trajectory point specifies either positions[, velocities[, accelerations]] +# or positions[, effort] for the trajectory to be executed. +# All specified values are in the same order as the joint names in JointTrajectory.msg + +float64[] positions +float64[] velocities +float64[] accelerations +float64[] effort +duration time_from_start"#; } #[allow(non_snake_case)] #[derive( @@ -4376,7 +11217,15 @@ pub mod trajectory_msgs { impl ::roslibrust_codegen::RosMessageType for JointTrajectoryPoint { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/JointTrajectoryPoint"; const MD5SUM: &'static str = "f3cd1e1c4d320c79d6985c904ae5dcd3"; - const DEFINITION : & 'static str = "# Each trajectory point specifies either positions[, velocities[, accelerations]]\n# or positions[, effort] for the trajectory to be executed.\n# All specified values are in the same order as the joint names in JointTrajectory.msg\n\nfloat64[] positions\nfloat64[] velocities\nfloat64[] accelerations\nfloat64[] effort\nduration time_from_start" ; + const DEFINITION: &'static str = r#"# Each trajectory point specifies either positions[, velocities[, accelerations]] +# or positions[, effort] for the trajectory to be executed. +# All specified values are in the same order as the joint names in JointTrajectory.msg + +float64[] positions +float64[] velocities +float64[] accelerations +float64[] effort +duration time_from_start"#; } #[allow(non_snake_case)] #[derive( @@ -4396,7 +11245,169 @@ pub mod trajectory_msgs { impl ::roslibrust_codegen::RosMessageType for MultiDOFJointTrajectory { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/MultiDOFJointTrajectory"; const MD5SUM: &'static str = "ef145a45a5f47b77b7f5cdde4b16c942"; - const DEFINITION : & 'static str = "# The header is used to specify the coordinate frame and the reference time for the trajectory durations\nHeader header\n\n# A representation of a multi-dof joint trajectory (each point is a transformation)\n# Each point along the trajectory will include an array of positions/velocities/accelerations\n# that has the same length as the array of joint names, and has the same order of joints as \n# the joint names array.\n\nstring[] joint_names\nMultiDOFJointTrajectoryPoint[] points" ; + const DEFINITION: &'static str = r#"# The header is used to specify the coordinate frame and the reference time for the trajectory durations +Header header + +# A representation of a multi-dof joint trajectory (each point is a transformation) +# Each point along the trajectory will include an array of positions/velocities/accelerations +# that has the same length as the array of joint names, and has the same order of joints as +# the joint names array. + +string[] joint_names +MultiDOFJointTrajectoryPoint[] points +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: trajectory_msgs/MultiDOFJointTrajectoryPoint +# Each multi-dof joint can specify a transform (up to 6 DOF) +geometry_msgs/Transform[] transforms + +# There can be a velocity specified for the origin of the joint +geometry_msgs/Twist[] velocities + +# There can be an acceleration specified for the origin of the joint +geometry_msgs/Twist[] accelerations + +duration time_from_start +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -4417,7 +11428,79 @@ pub mod trajectory_msgs { impl ::roslibrust_codegen::RosMessageType for MultiDOFJointTrajectoryPoint { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/MultiDOFJointTrajectoryPoint"; const MD5SUM: &'static str = "3ebe08d1abd5b65862d50e09430db776"; - const DEFINITION : & 'static str = "# Each multi-dof joint can specify a transform (up to 6 DOF)\ngeometry_msgs/Transform[] transforms\n\n# There can be a velocity specified for the origin of the joint \ngeometry_msgs/Twist[] velocities\n\n# There can be an acceleration specified for the origin of the joint \ngeometry_msgs/Twist[] accelerations\n\nduration time_from_start" ; + const DEFINITION: &'static str = r#"# Each multi-dof joint can specify a transform (up to 6 DOF) +geometry_msgs/Transform[] transforms + +# There can be a velocity specified for the origin of the joint +geometry_msgs/Twist[] velocities + +# There can be an acceleration specified for the origin of the joint +geometry_msgs/Twist[] accelerations + +duration time_from_start +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z"#; } } #[allow(unused_imports)] @@ -4463,7 +11546,57 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for ImageMarker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/ImageMarker"; const MD5SUM: &'static str = "1de93c67ec8858b831025a08fbf1b35c"; - const DEFINITION : & 'static str = "uint8 CIRCLE=0\nuint8 LINE_STRIP=1\nuint8 LINE_LIST=2\nuint8 POLYGON=3\nuint8 POINTS=4\n\nuint8 ADD=0\nuint8 REMOVE=1\n\nHeader header\nstring ns\t\t# namespace, used with id to form a unique id\nint32 id \t# unique id within the namespace\nint32 type \t# CIRCLE/LINE_STRIP/etc.\nint32 action \t# ADD/REMOVE\ngeometry_msgs/Point position # 2D, in pixel-coords\nfloat32 scale\t \t# the diameter for a circle, etc.\nstd_msgs/ColorRGBA outline_color\nuint8 filled\t\t# whether to fill in the shape with color\nstd_msgs/ColorRGBA fill_color # color [0.0-1.0]\nduration lifetime # How long the object should last before being automatically deleted. 0 means forever\n\n\ngeometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords\nstd_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc." ; + const DEFINITION: &'static str = r#"uint8 CIRCLE=0 +uint8 LINE_STRIP=1 +uint8 LINE_LIST=2 +uint8 POLYGON=3 +uint8 POINTS=4 + +uint8 ADD=0 +uint8 REMOVE=1 + +Header header +string ns # namespace, used with id to form a unique id +int32 id # unique id within the namespace +int32 type # CIRCLE/LINE_STRIP/etc. +int32 action # ADD/REMOVE +geometry_msgs/Point position # 2D, in pixel-coords +float32 scale # the diameter for a circle, etc. +std_msgs/ColorRGBA outline_color +uint8 filled # whether to fill in the shape with color +std_msgs/ColorRGBA fill_color # color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever + + +geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords +std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc. +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl ImageMarker { pub const r#CIRCLE: u8 = 0u8; @@ -4496,7 +11629,523 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarker"; const MD5SUM: &'static str = "dd86d22909d5a3364b384492e35c10af"; - const DEFINITION : & 'static str = "# Time/frame info.\n# If header.time is set to 0, the marker will be retransformed into\n# its frame on each timestep. You will receive the pose feedback\n# in the same frame.\n# Otherwise, you might receive feedback in a different frame.\n# For rviz, this will be the current 'fixed frame' set by the user.\nHeader header\n\n# Initial pose. Also, defines the pivot point for rotations.\ngeometry_msgs/Pose pose\n\n# Identifying string. Must be globally unique in\n# the topic that this message is sent through.\nstring name\n\n# Short description (< 40 characters).\nstring description\n\n# Scale to be used for default controls (default=1).\nfloat32 scale\n\n# All menu and submenu entries associated with this marker.\nMenuEntry[] menu_entries\n\n# List of controls displayed for this marker.\nInteractiveMarkerControl[] controls" ; + const DEFINITION: &'static str = r#"# Time/frame info. +# If header.time is set to 0, the marker will be retransformed into +# its frame on each timestep. You will receive the pose feedback +# in the same frame. +# Otherwise, you might receive feedback in a different frame. +# For rviz, this will be the current 'fixed frame' set by the user. +Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name + +# Short description (< 40 characters). +string description + +# Scale to be used for default controls (default=1). +float32 scale + +# All menu and submenu entries associated with this marker. +MenuEntry[] menu_entries + +# List of controls displayed for this marker. +InteractiveMarkerControl[] controls +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. + +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. + +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type"#; } #[allow(non_snake_case)] #[derive( @@ -4521,7 +12170,261 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerControl { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerControl"; const MD5SUM: &'static str = "b3c81e785788195d1840b86c28da1aac"; - const DEFINITION : & 'static str = "# Represents a control that is to be displayed together with an interactive marker\n\n# Identifying string for this control.\n# You need to assign a unique value to this to receive feedback from the GUI\n# on what actions the user performs on this control (e.g. a button click).\nstring name\n\n\n# Defines the local coordinate frame (relative to the pose of the parent\n# interactive marker) in which is being rotated and translated.\n# Default: Identity\ngeometry_msgs/Quaternion orientation\n\n\n# Orientation mode: controls how orientation changes.\n# INHERIT: Follow orientation of interactive marker\n# FIXED: Keep orientation fixed at initial state\n# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up).\nuint8 INHERIT = 0 \nuint8 FIXED = 1\nuint8 VIEW_FACING = 2\n\nuint8 orientation_mode\n\n# Interaction mode for this control\n# \n# NONE: This control is only meant for visualization; no context menu.\n# MENU: Like NONE, but right-click menu is active.\n# BUTTON: Element can be left-clicked.\n# MOVE_AXIS: Translate along local x-axis.\n# MOVE_PLANE: Translate in local y-z plane.\n# ROTATE_AXIS: Rotate around local x-axis.\n# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS.\nuint8 NONE = 0 \nuint8 MENU = 1\nuint8 BUTTON = 2\nuint8 MOVE_AXIS = 3 \nuint8 MOVE_PLANE = 4\nuint8 ROTATE_AXIS = 5\nuint8 MOVE_ROTATE = 6\n# \"3D\" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors.\n# MOVE_3D: Translate freely in 3D space.\n# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame.\n# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin.\nuint8 MOVE_3D = 7\nuint8 ROTATE_3D = 8\nuint8 MOVE_ROTATE_3D = 9\n\nuint8 interaction_mode\n\n\n# If true, the contained markers will also be visible\n# when the gui is not in interactive mode.\nbool always_visible\n\n\n# Markers to be displayed as custom visual representation.\n# Leave this empty to use the default control handles.\n#\n# Note: \n# - The markers can be defined in an arbitrary coordinate frame,\n# but will be transformed into the local frame of the interactive marker.\n# - If the header of a marker is empty, its pose will be interpreted as \n# relative to the pose of the parent interactive marker.\nMarker[] markers\n\n\n# In VIEW_FACING mode, set this to true if you don't want the markers\n# to be aligned with the camera view point. The markers will show up\n# as in INHERIT mode.\nbool independent_marker_orientation\n\n\n# Short description (< 40 characters) of what this control does,\n# e.g. \"Move the robot\". \n# Default: A generic description based on the interaction mode\nstring description" ; + const DEFINITION: &'static str = r#"# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl InteractiveMarkerControl { pub const r#INHERIT: u8 = 0u8; @@ -4562,7 +12465,96 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerFeedback { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerFeedback"; const MD5SUM: &'static str = "ab0f1eee058667e28c19ff3ffc3f4b78"; - const DEFINITION : & 'static str = "# Time/frame info.\nHeader header\n\n# Identifying string. Must be unique in the topic namespace.\nstring client_id\n\n# Feedback message sent back from the GUI, e.g.\n# when the status of an interactive marker was modified by the user.\n\n# Specifies which interactive marker and control this message refers to\nstring marker_name\nstring control_name\n\n# Type of the event\n# KEEP_ALIVE: sent while dragging to keep up control of the marker\n# MENU_SELECT: a menu entry has been selected\n# BUTTON_CLICK: a button control has been clicked\n# POSE_UPDATE: the pose has been changed using one of the controls\nuint8 KEEP_ALIVE = 0\nuint8 POSE_UPDATE = 1\nuint8 MENU_SELECT = 2\nuint8 BUTTON_CLICK = 3\n\nuint8 MOUSE_DOWN = 4\nuint8 MOUSE_UP = 5\n\nuint8 event_type\n\n# Current pose of the marker\n# Note: Has to be valid for all feedback types.\ngeometry_msgs/Pose pose\n\n# Contains the ID of the selected menu entry\n# Only valid for MENU_SELECT events.\nuint32 menu_entry_id\n\n# If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point\n# may contain the 3 dimensional position of the event on the\n# control. If it does, mouse_point_valid will be true. mouse_point\n# will be relative to the frame listed in the header.\ngeometry_msgs/Point mouse_point\nbool mouse_point_valid" ; + const DEFINITION: &'static str = r#"# Time/frame info. +Header header + +# Identifying string. Must be unique in the topic namespace. +string client_id + +# Feedback message sent back from the GUI, e.g. +# when the status of an interactive marker was modified by the user. + +# Specifies which interactive marker and control this message refers to +string marker_name +string control_name + +# Type of the event +# KEEP_ALIVE: sent while dragging to keep up control of the marker +# MENU_SELECT: a menu entry has been selected +# BUTTON_CLICK: a button control has been clicked +# POSE_UPDATE: the pose has been changed using one of the controls +uint8 KEEP_ALIVE = 0 +uint8 POSE_UPDATE = 1 +uint8 MENU_SELECT = 2 +uint8 BUTTON_CLICK = 3 + +uint8 MOUSE_DOWN = 4 +uint8 MOUSE_UP = 5 + +uint8 event_type + +# Current pose of the marker +# Note: Has to be valid for all feedback types. +geometry_msgs/Pose pose + +# Contains the ID of the selected menu entry +# Only valid for MENU_SELECT events. +uint32 menu_entry_id + +# If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point +# may contain the 3 dimensional position of the event on the +# control. If it does, mouse_point_valid will be true. mouse_point +# will be relative to the frame listed in the header. +geometry_msgs/Point mouse_point +bool mouse_point_valid +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl InteractiveMarkerFeedback { pub const r#KEEP_ALIVE: u8 = 0u8; @@ -4590,7 +12582,1030 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerInit { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerInit"; const MD5SUM: &'static str = "d5f2c5045a72456d228676ab91048734"; - const DEFINITION : & 'static str = "# Identifying string. Must be unique in the topic namespace\n# that this server works on.\nstring server_id\n\n# Sequence number.\n# The client will use this to detect if it has missed a subsequent\n# update. Every update message will have the same sequence number as\n# an init message. Clients will likely want to unsubscribe from the\n# init topic after a successful initialization to avoid receiving\n# duplicate data.\nuint64 seq_num\n\n# All markers.\nInteractiveMarker[] markers" ; + const DEFINITION: &'static str = r#"# Identifying string. Must be unique in the topic namespace +# that this server works on. +string server_id + +# Sequence number. +# The client will use this to detect if it has missed a subsequent +# update. Every update message will have the same sequence number as +# an init message. Clients will likely want to unsubscribe from the +# init topic after a successful initialization to avoid receiving +# duplicate data. +uint64 seq_num + +# All markers. +InteractiveMarker[] markers +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarker +# Time/frame info. +# If header.time is set to 0, the marker will be retransformed into +# its frame on each timestep. You will receive the pose feedback +# in the same frame. +# Otherwise, you might receive feedback in a different frame. +# For rviz, this will be the current 'fixed frame' set by the user. +Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name + +# Short description (< 40 characters). +string description + +# Scale to be used for default controls (default=1). +float32 scale + +# All menu and submenu entries associated with this marker. +MenuEntry[] menu_entries + +# List of controls displayed for this marker. +InteractiveMarkerControl[] controls +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. + +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. + +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. + +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. + +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type"#; } #[allow(non_snake_case)] #[derive( @@ -4610,7 +13625,63 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerPose { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerPose"; const MD5SUM: &'static str = "a6e6833209a196a38d798dadb02c81f8"; - const DEFINITION : & 'static str = "# Time/frame info.\nHeader header\n\n# Initial pose. Also, defines the pivot point for rotations.\ngeometry_msgs/Pose pose\n\n# Identifying string. Must be globally unique in\n# the topic that this message is sent through.\nstring name" ; + const DEFINITION: &'static str = r#"# Time/frame info. +Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -4633,7 +13704,1106 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerUpdate { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerUpdate"; const MD5SUM: &'static str = "710d308d0a9276d65945e92dd30b3946"; - const DEFINITION : & 'static str = "# Identifying string. Must be unique in the topic namespace\n# that this server works on.\nstring server_id\n\n# Sequence number.\n# The client will use this to detect if it has missed an update.\nuint64 seq_num\n\n# Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE.\n# UPDATE: Incremental update to previous state. \n# The sequence number must be 1 higher than for\n# the previous update.\n# KEEP_ALIVE: Indicates the that the server is still living.\n# The sequence number does not increase.\n# No payload data should be filled out (markers, poses, or erases).\nuint8 KEEP_ALIVE = 0\nuint8 UPDATE = 1\n\nuint8 type\n\n#Note: No guarantees on the order of processing.\n# Contents must be kept consistent by sender.\n\n#Markers to be added or updated\nInteractiveMarker[] markers\n\n#Poses of markers that should be moved\nInteractiveMarkerPose[] poses\n\n#Names of markers to be erased\nstring[] erases" ; + const DEFINITION: &'static str = r#"# Identifying string. Must be unique in the topic namespace +# that this server works on. +string server_id + +# Sequence number. +# The client will use this to detect if it has missed an update. +uint64 seq_num + +# Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE. +# UPDATE: Incremental update to previous state. +# The sequence number must be 1 higher than for +# the previous update. +# KEEP_ALIVE: Indicates the that the server is still living. +# The sequence number does not increase. +# No payload data should be filled out (markers, poses, or erases). +uint8 KEEP_ALIVE = 0 +uint8 UPDATE = 1 + +uint8 type + +#Note: No guarantees on the order of processing. +# Contents must be kept consistent by sender. + +#Markers to be added or updated +InteractiveMarker[] markers + +#Poses of markers that should be moved +InteractiveMarkerPose[] poses + +#Names of markers to be erased +string[] erases +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarker +# Time/frame info. +# If header.time is set to 0, the marker will be retransformed into +# its frame on each timestep. You will receive the pose feedback +# in the same frame. +# Otherwise, you might receive feedback in a different frame. +# For rviz, this will be the current 'fixed frame' set by the user. +Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name + +# Short description (< 40 characters). +string description + +# Scale to be used for default controls (default=1). +float32 scale + +# All menu and submenu entries associated with this marker. +MenuEntry[] menu_entries + +# List of controls displayed for this marker. +InteractiveMarkerControl[] controls +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. + +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. + +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarkerPose +# Time/frame info. +Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. + +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. + +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type"#; } impl InteractiveMarkerUpdate { pub const r#KEEP_ALIVE: u8 = 0u8; @@ -4669,7 +14839,116 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for Marker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/Marker"; const MD5SUM: &'static str = "4048c9de2a16f4ae8e0538085ebf1b97"; - const DEFINITION : & 'static str = "# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz\n\nuint8 ARROW=0\nuint8 CUBE=1\nuint8 SPHERE=2\nuint8 CYLINDER=3\nuint8 LINE_STRIP=4\nuint8 LINE_LIST=5\nuint8 CUBE_LIST=6\nuint8 SPHERE_LIST=7\nuint8 POINTS=8\nuint8 TEXT_VIEW_FACING=9\nuint8 MESH_RESOURCE=10\nuint8 TRIANGLE_LIST=11\n\nuint8 ADD=0\nuint8 MODIFY=0\nuint8 DELETE=2\nuint8 DELETEALL=3\n\nHeader header # header for time/frame information\nstring ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object\nint32 id \t\t # object ID useful in conjunction with the namespace for manipulating and deleting the object later\nint32 type \t\t # Type of object\nint32 action \t # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects\ngeometry_msgs/Pose pose # Pose of the object\ngeometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)\nstd_msgs/ColorRGBA color # Color [0.0-1.0]\nduration lifetime # How long the object should last before being automatically deleted. 0 means forever\nbool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep\n\n#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\ngeometry_msgs/Point[] points\n#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)\n#number of colors must either be 0 or equal to the number of points\n#NOTE: alpha is not yet used\nstd_msgs/ColorRGBA[] colors\n\n# NOTE: only used for text markers\nstring text\n\n# NOTE: only used for MESH_RESOURCE markers\nstring mesh_resource\nbool mesh_use_embedded_materials" ; + const DEFINITION: &'static str = r#"# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } impl Marker { pub const r#ARROW: u8 = 0u8; @@ -4705,7 +14984,185 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for MarkerArray { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MarkerArray"; const MD5SUM: &'static str = "d155b9ce5188fbaf89745847fd5882d7"; - const DEFINITION: &'static str = "Marker[] markers"; + const DEFINITION: &'static str = r#"Marker[] markers +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz + +uint8 ARROW=0 +uint8 CUBE=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 LINE_STRIP=4 +uint8 LINE_LIST=5 +uint8 CUBE_LIST=6 +uint8 SPHERE_LIST=7 +uint8 POINTS=8 +uint8 TEXT_VIEW_FACING=9 +uint8 MESH_RESOURCE=10 +uint8 TRIANGLE_LIST=11 + +uint8 ADD=0 +uint8 MODIFY=0 +uint8 DELETE=2 +uint8 DELETEALL=3 + +Header header # header for time/frame information +string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object +int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later +int32 type # Type of object +int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects +geometry_msgs/Pose pose # Pose of the object +geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) +std_msgs/ColorRGBA color # Color [0.0-1.0] +duration lifetime # How long the object should last before being automatically deleted. 0 means forever +bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep + +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +geometry_msgs/Point[] points +#Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) +#number of colors must either be 0 or equal to the number of points +#NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# NOTE: only used for text markers +string text + +# NOTE: only used for MESH_RESOURCE markers +string mesh_resource +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x +float64 y +float64 z +float64 w +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. +# It is only meant to represent a direction. Therefore, it does not +# make sense to apply a translation to it (e.g., when applying a +# generic rigid transformation to a Vector3, tf2 will only apply the +# rotation). If you want your data to be translatable too, use the +# geometry_msgs/Point message instead. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. +# +# sequence ID: consecutively increasing ID +uint32 seq +#Two-integer timestamp that is expressed as: +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') +# time-handling sugar is provided by the client library +time stamp +#Frame this data is associated with +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -4727,7 +15184,60 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for MenuEntry { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MenuEntry"; const MD5SUM: &'static str = "b90ec63024573de83b57aa93eb39be2d"; - const DEFINITION : & 'static str = "# MenuEntry message.\n\n# Each InteractiveMarker message has an array of MenuEntry messages.\n# A collection of MenuEntries together describe a\n# menu/submenu/subsubmenu/etc tree, though they are stored in a flat\n# array. The tree structure is represented by giving each menu entry\n# an ID number and a \"parent_id\" field. Top-level entries are the\n# ones with parent_id = 0. Menu entries are ordered within their\n# level the same way they are ordered in the containing array. Parent\n# entries must appear before their children.\n\n# Example:\n# - id = 3\n# parent_id = 0\n# title = \"fun\"\n# - id = 2\n# parent_id = 0\n# title = \"robot\"\n# - id = 4\n# parent_id = 2\n# title = \"pr2\"\n# - id = 5\n# parent_id = 2\n# title = \"turtle\"\n#\n# Gives a menu tree like this:\n# - fun\n# - robot\n# - pr2\n# - turtle\n\n# ID is a number for each menu entry. Must be unique within the\n# control, and should never be 0.\nuint32 id\n\n# ID of the parent of this menu entry, if it is a submenu. If this\n# menu entry is a top-level entry, set parent_id to 0.\nuint32 parent_id\n\n# menu / entry title\nstring title\n\n# Arguments to command indicated by command_type (below)\nstring command\n\n# Command_type stores the type of response desired when this menu\n# entry is clicked.\n# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id.\n# ROSRUN: execute \"rosrun\" with arguments given in the command field (above).\n# ROSLAUNCH: execute \"roslaunch\" with arguments given in the command field (above).\nuint8 FEEDBACK=0\nuint8 ROSRUN=1\nuint8 ROSLAUNCH=2\nuint8 command_type" ; + const DEFINITION: &'static str = r#"# MenuEntry message. + +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. + +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type"#; } impl MenuEntry { pub const r#FEEDBACK: u8 = 0u8; diff --git a/roslibrust_test/src/ros2.rs b/roslibrust_test/src/ros2.rs index 0364f4ef..66869903 100644 --- a/roslibrust_test/src/ros2.rs +++ b/roslibrust_test/src/ros2.rs @@ -28,7 +28,15 @@ pub mod actionlib_msgs { impl ::roslibrust_codegen::RosMessageType for GoalID { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalID"; const MD5SUM: &'static str = "29380925936d499346662d2ed1573d06"; - const DEFINITION : & 'static str = "# The stamp should store the time at which this goal was requested.\n# It is used by an action server when it tries to preempt all\n# goals that were requested before a certain time\nbuiltin_interfaces/Time stamp\n\n# The id provides a way to associate feedback and\n# result message with specific goal requests. The id\n# specified must be unique.\nstring id" ; + const DEFINITION: &'static str = r#"# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +builtin_interfaces/Time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id"#; } #[allow(non_snake_case)] #[derive( @@ -48,7 +56,40 @@ pub mod actionlib_msgs { impl ::roslibrust_codegen::RosMessageType for GoalStatus { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalStatus"; const MD5SUM: &'static str = "c24a9e244d837a856267339807550287"; - const DEFINITION : & 'static str = "GoalID goal_id\nuint8 status\nuint8 PENDING = 0 # The goal has yet to be processed by the action server.\nuint8 ACTIVE = 1 # The goal is currently being processed by the action server.\nuint8 PREEMPTED = 2 # The goal received a cancel request after it started executing\n # and has since completed its execution (Terminal State).\nuint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server\n # (Terminal State).\nuint8 ABORTED = 4 # The goal was aborted during execution by the action server due\n # to some failure (Terminal State).\nuint8 REJECTED = 5 # The goal was rejected by the action server without being processed,\n # because the goal was unattainable or invalid (Terminal State).\nuint8 PREEMPTING = 6 # The goal received a cancel request after it started executing\n # and has not yet completed execution.\nuint8 RECALLING = 7 # The goal received a cancel request before it started executing, but\n # the action server has not yet confirmed that the goal is canceled.\nuint8 RECALLED = 8 # The goal received a cancel request before it started executing\n # and was successfully cancelled (Terminal State).\nuint8 LOST = 9 # An action client can determine that a goal is LOST. This should not\n # be sent over the wire by an action server.\n\n# Allow for the user to associate a string with GoalStatus for debugging.\nstring text" ; + const DEFINITION: &'static str = r#"GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server. +uint8 ACTIVE = 1 # The goal is currently being processed by the action server. +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State). +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server + # (Terminal State). +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State). +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State). +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution. +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, but + # the action server has not yet confirmed that the goal is canceled. +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State). +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not + # be sent over the wire by an action server. + +# Allow for the user to associate a string with GoalStatus for debugging. +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +builtin_interfaces/Time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id"#; } impl GoalStatus { pub const r#PENDING: u8 = 0u8; @@ -79,7 +120,68 @@ pub mod actionlib_msgs { impl ::roslibrust_codegen::RosMessageType for GoalStatusArray { const ROS_TYPE_NAME: &'static str = "actionlib_msgs/GoalStatusArray"; const MD5SUM: &'static str = "ad4c7a55992b9ff34d89596ca74a28e0"; - const DEFINITION : & 'static str = "# Stores the statuses for goals that are currently being tracked\n# by an action server\nstd_msgs/Header header\nGoalStatus[] status_list" ; + const DEFINITION: &'static str = r#"# Stores the statuses for goals that are currently being tracked +# by an action server +std_msgs/Header header +GoalStatus[] status_list +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +builtin_interfaces/Time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: actionlib_msgs/GoalStatus +GoalID goal_id +uint8 status +uint8 PENDING = 0 # The goal has yet to be processed by the action server. +uint8 ACTIVE = 1 # The goal is currently being processed by the action server. +uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing + # and has since completed its execution (Terminal State). +uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server + # (Terminal State). +uint8 ABORTED = 4 # The goal was aborted during execution by the action server due + # to some failure (Terminal State). +uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, + # because the goal was unattainable or invalid (Terminal State). +uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing + # and has not yet completed execution. +uint8 RECALLING = 7 # The goal received a cancel request before it started executing, but + # the action server has not yet confirmed that the goal is canceled. +uint8 RECALLED = 8 # The goal received a cancel request before it started executing + # and was successfully cancelled (Terminal State). +uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not + # be sent over the wire by an action server. + +# Allow for the user to associate a string with GoalStatus for debugging. +string text +================================================================================ +MSG: actionlib_msgs/GoalID +# The stamp should store the time at which this goal was requested. +# It is used by an action server when it tries to preempt all +# goals that were requested before a certain time +builtin_interfaces/Time stamp + +# The id provides a way to associate feedback and +# result message with specific goal requests. The id +# specified must be unique. +string id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } } #[allow(unused_imports)] @@ -112,7 +214,52 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for DiagnosticArray { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/DiagnosticArray"; const MD5SUM: &'static str = "7f04f8332be7e46b680724aa4e9a9d71"; - const DEFINITION : & 'static str = "# This message is used to send diagnostic information about the state of the robot.\nstd_msgs/Header header # for timestamp\nDiagnosticStatus[] status # an array of components being reported on" ; + const DEFINITION: &'static str = r#"# This message is used to send diagnostic information about the state of the robot. +std_msgs/Header header # for timestamp +DiagnosticStatus[] status # an array of components being reported on +================================================================================ +MSG: diagnostic_msgs/DiagnosticStatus +# This message holds the status of an individual component of the robot. + +# Possible levels of operations. +byte OK=0 +byte WARN=1 +byte ERROR=2 +byte STALE=3 + +# Level of operation enumerated above. +byte level +# A description of the test/component reporting. +string name +# A description of the status. +string message +# A hardware unique string. +string hardware_id +# An array of values associated with the status. +KeyValue[] values +================================================================================ +MSG: diagnostic_msgs/KeyValue +# What to label this value when viewing. +string key +# A value to track over time. +string value +================================================================================ +MSG: diagnostic_msgs/KeyValue +# What to label this value when viewing. +string key +# A value to track over time. +string value +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -134,7 +281,30 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for DiagnosticStatus { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/DiagnosticStatus"; const MD5SUM: &'static str = "d0ce08bc6e5ba34c7754f563a9cabaf1"; - const DEFINITION : & 'static str = "# This message holds the status of an individual component of the robot.\n\n# Possible levels of operations.\nbyte OK=0\nbyte WARN=1\nbyte ERROR=2\nbyte STALE=3\n\n# Level of operation enumerated above.\nbyte level\n# A description of the test/component reporting.\nstring name\n# A description of the status.\nstring message\n# A hardware unique string.\nstring hardware_id\n# An array of values associated with the status.\nKeyValue[] values" ; + const DEFINITION: &'static str = r#"# This message holds the status of an individual component of the robot. + +# Possible levels of operations. +byte OK=0 +byte WARN=1 +byte ERROR=2 +byte STALE=3 + +# Level of operation enumerated above. +byte level +# A description of the test/component reporting. +string name +# A description of the status. +string message +# A hardware unique string. +string hardware_id +# An array of values associated with the status. +KeyValue[] values +================================================================================ +MSG: diagnostic_msgs/KeyValue +# What to label this value when viewing. +string key +# A value to track over time. +string value"#; } impl DiagnosticStatus { pub const r#OK: u8 = 0u8; @@ -159,7 +329,10 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for KeyValue { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/KeyValue"; const MD5SUM: &'static str = "cf57fdc6617a881a88c16e768132149c"; - const DEFINITION : & 'static str = "# What to label this value when viewing.\nstring key\n# A value to track over time.\nstring value" ; + const DEFINITION: &'static str = r#"# What to label this value when viewing. +string key +# A value to track over time. +string value"#; } #[allow(non_snake_case)] #[derive( @@ -177,7 +350,23 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for AddDiagnosticsRequest { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/AddDiagnosticsRequest"; const MD5SUM: &'static str = "c26cf6e164288fbc6050d74f838bcdf0"; - const DEFINITION : & 'static str = "# This service is used as part of the process for loading analyzers at runtime,\n# and should be used by a loader script or program, not as a standalone service.\n# Information about dynamic addition of analyzers can be found at\n# http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime\n\n# The load_namespace parameter defines the namespace where parameters for the\n# initialization of analyzers in the diagnostic aggregator have been loaded. The\n# value should be a global name (i.e. /my/name/space), not a relative\n# (my/name/space) or private (~my/name/space) name. Analyzers will not be added\n# if a non-global name is used. The call will also fail if the namespace\n# contains parameters that follow a namespace structure that does not conform to\n# that expected by the analyzer definitions. See\n# http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators\n# and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer\n# for examples of the structure of yaml files which are expected to have been\n# loaded into the namespace.\nstring load_namespace" ; + const DEFINITION: &'static str = r#"# This service is used as part of the process for loading analyzers at runtime, +# and should be used by a loader script or program, not as a standalone service. +# Information about dynamic addition of analyzers can be found at +# http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime + +# The load_namespace parameter defines the namespace where parameters for the +# initialization of analyzers in the diagnostic aggregator have been loaded. The +# value should be a global name (i.e. /my/name/space), not a relative +# (my/name/space) or private (~my/name/space) name. Analyzers will not be added +# if a non-global name is used. The call will also fail if the namespace +# contains parameters that follow a namespace structure that does not conform to +# that expected by the analyzer definitions. See +# http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators +# and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer +# for examples of the structure of yaml files which are expected to have been +# loaded into the namespace. +string load_namespace"#; } #[allow(non_snake_case)] #[derive( @@ -196,7 +385,14 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for AddDiagnosticsResponse { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/AddDiagnosticsResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; - const DEFINITION : & 'static str = "# True if diagnostic aggregator was updated with new diagnostics, False\n# otherwise. A false return value means that either there is a bond in the\n# aggregator which already used the requested namespace, or the initialization\n# of analyzers failed.\nbool success\n\n# Message with additional information about the success or failure\nstring message" ; + const DEFINITION: &'static str = r#"# True if diagnostic aggregator was updated with new diagnostics, False +# otherwise. A false return value means that either there is a bond in the +# aggregator which already used the requested namespace, or the initialization +# of analyzers failed. +bool success + +# Message with additional information about the success or failure +string message"#; } pub struct AddDiagnostics {} impl ::roslibrust_codegen::RosServiceType for AddDiagnostics { @@ -219,7 +415,7 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for SelfTestRequest { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/SelfTestRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -239,7 +435,41 @@ pub mod diagnostic_msgs { impl ::roslibrust_codegen::RosMessageType for SelfTestResponse { const ROS_TYPE_NAME: &'static str = "diagnostic_msgs/SelfTestResponse"; const MD5SUM: &'static str = "ac21b1bab7ab17546986536c22eb34e9"; - const DEFINITION: &'static str = "string id\nbyte passed\nDiagnosticStatus[] status"; + const DEFINITION: &'static str = r#"string id +byte passed +DiagnosticStatus[] status +================================================================================ +MSG: diagnostic_msgs/DiagnosticStatus +# This message holds the status of an individual component of the robot. + +# Possible levels of operations. +byte OK=0 +byte WARN=1 +byte ERROR=2 +byte STALE=3 + +# Level of operation enumerated above. +byte level +# A description of the test/component reporting. +string name +# A description of the status. +string message +# A hardware unique string. +string hardware_id +# An array of values associated with the status. +KeyValue[] values +================================================================================ +MSG: diagnostic_msgs/KeyValue +# What to label this value when viewing. +string key +# A value to track over time. +string value +================================================================================ +MSG: diagnostic_msgs/KeyValue +# What to label this value when viewing. +string key +# A value to track over time. +string value"#; } pub struct SelfTest {} impl ::roslibrust_codegen::RosServiceType for SelfTest { @@ -279,7 +509,20 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Accel { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Accel"; const MD5SUM: &'static str = "9f195f881246fdfa2798d1d3eebca84a"; - const DEFINITION : & 'static str = "# This expresses acceleration in free space broken into its linear and angular parts.\nVector3 linear\nVector3 angular" ; + const DEFINITION: &'static str = r#"# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -298,7 +541,47 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for AccelStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelStamped"; const MD5SUM: &'static str = "19a31cf6d39a90e769a5539f9a293621"; - const DEFINITION : & 'static str = "# An accel with reference coordinate frame and timestamp\nstd_msgs/Header header\nAccel accel" ; + const DEFINITION: &'static str = r#"# An accel with reference coordinate frame and timestamp +std_msgs/Header header +Accel accel +================================================================================ +MSG: geometry_msgs/Accel +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -319,7 +602,42 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for AccelWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovariance"; const MD5SUM: &'static str = "ad5a718d699c6be72a02b8d6a139f334"; - const DEFINITION : & 'static str = "# This expresses acceleration in free space with uncertainty.\n\nAccel accel\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance" ; + const DEFINITION: &'static str = r#"# This expresses acceleration in free space with uncertainty. + +Accel accel + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Accel +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -338,7 +656,85 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for AccelWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/AccelWithCovarianceStamped"; const MD5SUM: &'static str = "36b6f1177d3c3f476d4c306279c6f18a"; - const DEFINITION : & 'static str = "# This represents an estimated accel with reference coordinate frame and timestamp.\nstd_msgs/Header header\nAccelWithCovariance accel" ; + const DEFINITION: &'static str = r#"# This represents an estimated accel with reference coordinate frame and timestamp. +std_msgs/Header header +AccelWithCovariance accel +================================================================================ +MSG: geometry_msgs/Accel +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/AccelWithCovariance +# This expresses acceleration in free space with uncertainty. + +Accel accel + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Accel +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -363,7 +759,33 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Inertia { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Inertia"; const MD5SUM: &'static str = "1d26e4bb6c83ff141c5cf0d883c2b0fe"; - const DEFINITION : & 'static str = "# Mass [kg]\nfloat64 m\n\n# Center of mass [m]\ngeometry_msgs/Vector3 com\n\n# Inertia Tensor [kg-m^2]\n# | ixx ixy ixz |\n# I = | ixy iyy iyz |\n# | ixz iyz izz |\nfloat64 ixx\nfloat64 ixy\nfloat64 ixz\nfloat64 iyy\nfloat64 iyz\nfloat64 izz" ; + const DEFINITION: &'static str = r#"# Mass [kg] +float64 m + +# Center of mass [m] +geometry_msgs/Vector3 com + +# Inertia Tensor [kg-m^2] +# | ixx ixy ixz | +# I = | ixy iyy iyz | +# | ixz iyz izz | +float64 ixx +float64 ixy +float64 ixz +float64 iyy +float64 iyz +float64 izz +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -382,7 +804,61 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for InertiaStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/InertiaStamped"; const MD5SUM: &'static str = "d4fb75ac056292d6c4bbec5e51d25080"; - const DEFINITION : & 'static str = "# An Inertia with a time stamp and reference frame.\n\nstd_msgs/Header header\nInertia inertia" ; + const DEFINITION: &'static str = r#"# An Inertia with a time stamp and reference frame. + +std_msgs/Header header +Inertia inertia +================================================================================ +MSG: geometry_msgs/Inertia +# Mass [kg] +float64 m + +# Center of mass [m] +geometry_msgs/Vector3 com + +# Inertia Tensor [kg-m^2] +# | ixx ixy ixz | +# I = | ixy iyy iyz | +# | ixz iyz izz | +float64 ixx +float64 ixy +float64 ixz +float64 iyy +float64 iyz +float64 izz +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -402,7 +878,10 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Point { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Point"; const MD5SUM: &'static str = "4a842b65f413084dc2b10fb484ea7f17"; - const DEFINITION : & 'static str = "# This contains the position of a point in free space\nfloat64 x\nfloat64 y\nfloat64 z" ; + const DEFINITION: &'static str = r#"# This contains the position of a point in free space +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -422,7 +901,17 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Point32 { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Point32"; const MD5SUM: &'static str = "cc153912f1453b708d221682bc23d9ac"; - const DEFINITION : & 'static str = "# This contains the position of a point in free space(with 32 bits of precision).\n# It is recommended to use Point wherever possible instead of Point32.\n#\n# This recommendation is to promote interoperability.\n#\n# This message is designed to take up less space when sending\n# lots of points at once, as in the case of a PointCloud.\n\nfloat32 x\nfloat32 y\nfloat32 z" ; + const DEFINITION: &'static str = r#"# This contains the position of a point in free space(with 32 bits of precision). +# It is recommended to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z"#; } #[allow(non_snake_case)] #[derive( @@ -441,7 +930,27 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PointStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PointStamped"; const MD5SUM: &'static str = "938cb86faf4572821e49e2490701e6df"; - const DEFINITION : & 'static str = "# This represents a Point with reference coordinate frame and timestamp\n\nstd_msgs/Header header\nPoint point" ; + const DEFINITION: &'static str = r#"# This represents a Point with reference coordinate frame and timestamp + +std_msgs/Header header +Point point +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -459,7 +968,22 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Polygon { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Polygon"; const MD5SUM: &'static str = "cd60a26494a087f577976f0329fa120e"; - const DEFINITION : & 'static str = "# A specification of a polygon where the first and last points are assumed to be connected\n\nPoint32[] points" ; + const DEFINITION: &'static str = r#"# A specification of a polygon where the first and last points are assumed to be connected + +Point32[] points +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommended to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z"#; } #[allow(non_snake_case)] #[derive( @@ -478,7 +1002,52 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PolygonStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PolygonStamped"; const MD5SUM: &'static str = "56a3a2a80165092f696df3db62e18fbf"; - const DEFINITION : & 'static str = "# This represents a Polygon with reference coordinate frame and timestamp\n\nstd_msgs/Header header\nPolygon polygon" ; + const DEFINITION: &'static str = r#"# This represents a Polygon with reference coordinate frame and timestamp + +std_msgs/Header header +Polygon polygon +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommended to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z +================================================================================ +MSG: geometry_msgs/Polygon +# A specification of a polygon where the first and last points are assumed to be connected + +Point32[] points +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommended to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -497,7 +1066,24 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Pose { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Pose"; const MD5SUM: &'static str = "e45d45a5a1ce597b249e23fb30fc871f"; - const DEFINITION : & 'static str = "# A representation of pose in free space, composed of position and orientation.\n\nPoint position\nQuaternion orientation" ; + const DEFINITION: &'static str = r#"# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1"#; } #[allow(non_snake_case)] #[derive( @@ -517,7 +1103,16 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Pose2D { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Pose2D"; const MD5SUM: &'static str = "938fa65709584ad8e77d238529be13b8"; - const DEFINITION : & 'static str = "# Deprecated as of Foxy and will potentially be removed in any following release.\n# Please use the full 3D pose.\n\n# In general our recommendation is to use a full 3D representation of everything and for 2D specific applications make the appropriate projections into the plane for their calculations but optimally will preserve the 3D information during processing.\n\n# If we have parallel copies of 2D datatypes every UI and other pipeline will end up needing to have dual interfaces to plot everything. And you will end up with not being able to use 3D tools for 2D use cases even if they're completely valid, as you'd have to reimplement it with different inputs and outputs. It's not particularly hard to plot the 2D pose or compute the yaw error for the Pose message and there are already tools and libraries that can do this for you.# This expresses a position and orientation on a 2D manifold.\n\nfloat64 x\nfloat64 y\nfloat64 theta" ; + const DEFINITION: &'static str = r#"# Deprecated as of Foxy and will potentially be removed in any following release. +# Please use the full 3D pose. + +# In general our recommendation is to use a full 3D representation of everything and for 2D specific applications make the appropriate projections into the plane for their calculations but optimally will preserve the 3D information during processing. + +# If we have parallel copies of 2D datatypes every UI and other pipeline will end up needing to have dual interfaces to plot everything. And you will end up with not being able to use 3D tools for 2D use cases even if they're completely valid, as you'd have to reimplement it with different inputs and outputs. It's not particularly hard to plot the 2D pose or compute the yaw error for the Pose message and there are already tools and libraries that can do this for you.# This expresses a position and orientation on a 2D manifold. + +float64 x +float64 y +float64 theta"#; } #[allow(non_snake_case)] #[derive( @@ -536,7 +1131,56 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PoseArray { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseArray"; const MD5SUM: &'static str = "ea7300c78ec47498d5f226be74a155e8"; - const DEFINITION : & 'static str = "# An array of poses with a header for global reference.\n\nstd_msgs/Header header\n\nPose[] poses" ; + const DEFINITION: &'static str = r#"# An array of poses with a header for global reference. + +std_msgs/Header header + +Pose[] poses +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -555,7 +1199,55 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PoseStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseStamped"; const MD5SUM: &'static str = "c088ec4a70a5930b0ca46520d5745e2d"; - const DEFINITION : & 'static str = "# A Pose with reference coordinate frame and timestamp\n\nstd_msgs/Header header\nPose pose" ; + const DEFINITION: &'static str = r#"# A Pose with reference coordinate frame and timestamp + +std_msgs/Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -576,7 +1268,49 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PoseWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovariance"; const MD5SUM: &'static str = "c23e848cf1b7533a8d7c259073a97e6f"; - const DEFINITION : & 'static str = "# This represents a pose in free space with uncertainty.\n\nPose pose\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance" ; + const DEFINITION: &'static str = r#"# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1"#; } #[allow(non_snake_case)] #[derive( @@ -595,7 +1329,100 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for PoseWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/PoseWithCovarianceStamped"; const MD5SUM: &'static str = "2178452bf195c1abe1e99b07b4e6c8f0"; - const DEFINITION : & 'static str = "# This expresses an estimated pose with a reference coordinate frame and timestamp\n\nstd_msgs/Header header\nPoseWithCovariance pose" ; + const DEFINITION: &'static str = r#"# This expresses an estimated pose with a reference coordinate frame and timestamp + +std_msgs/Header header +PoseWithCovariance pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -620,7 +1447,12 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Quaternion { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Quaternion"; const MD5SUM: &'static str = "a779879fadf0160734f906b8c19c7004"; - const DEFINITION : & 'static str = "# This represents an orientation in free space in quaternion form.\n\nfloat64 x 0\nfloat64 y 0\nfloat64 z 0\nfloat64 w 1" ; + const DEFINITION: &'static str = r#"# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1"#; } #[allow(non_snake_case)] #[derive( @@ -639,7 +1471,29 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for QuaternionStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/QuaternionStamped"; const MD5SUM: &'static str = "8f93ed7c8430d06bd82fefcc6f7a349e"; - const DEFINITION : & 'static str = "# This represents an orientation with reference coordinate frame and timestamp.\n\nstd_msgs/Header header\nQuaternion quaternion" ; + const DEFINITION: &'static str = r#"# This represents an orientation with reference coordinate frame and timestamp. + +std_msgs/Header header +Quaternion quaternion +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -658,7 +1512,29 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Transform { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Transform"; const MD5SUM: &'static str = "ac9eff44abf714214112b05d54a3cf9b"; - const DEFINITION : & 'static str = "# This represents the transform between two coordinate frames in free space.\n\nVector3 translation\nQuaternion rotation" ; + const DEFINITION: &'static str = r#"# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -678,7 +1554,80 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for TransformStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TransformStamped"; const MD5SUM: &'static str = "09bf247c06cf7c69e8c55300b05a7a04"; - const DEFINITION : & 'static str = "# This expresses a transform from coordinate frame header.frame_id\n# to the coordinate frame child_frame_id at the time of header.stamp\n#\n# This message is mostly used by the\n# tf2 package.\n# See its documentation for more information.\n#\n# The child_frame_id is necessary in addition to the frame_id\n# in the Header to communicate the full reference for the transform\n# in a self contained message.\n\n# The frame id in the header is used as the reference frame of this transform.\nstd_msgs/Header header\n\n# The frame id of the child frame to which this transform points.\nstring child_frame_id\n\n# Translation and rotation in 3-dimensions of child_frame_id from header.frame_id.\nTransform transform" ; + const DEFINITION: &'static str = r#"# This expresses a transform from coordinate frame header.frame_id +# to the coordinate frame child_frame_id at the time of header.stamp +# +# This message is mostly used by the +# tf2 package. +# See its documentation for more information. +# +# The child_frame_id is necessary in addition to the frame_id +# in the Header to communicate the full reference for the transform +# in a self contained message. + +# The frame id in the header is used as the reference frame of this transform. +std_msgs/Header header + +# The frame id of the child frame to which this transform points. +string child_frame_id + +# Translation and rotation in 3-dimensions of child_frame_id from header.frame_id. +Transform transform +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -697,7 +1646,21 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Twist { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Twist"; const MD5SUM: &'static str = "9f195f881246fdfa2798d1d3eebca84a"; - const DEFINITION : & 'static str = "# This expresses velocity in free space broken into its linear and angular parts.\n\nVector3 linear\nVector3 angular" ; + const DEFINITION: &'static str = r#"# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -716,7 +1679,49 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for TwistStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistStamped"; const MD5SUM: &'static str = "09f84400c1ca2e7e26a9da1232813bd0"; - const DEFINITION : & 'static str = "# A twist with reference coordinate frame and timestamp\n\nstd_msgs/Header header\nTwist twist" ; + const DEFINITION: &'static str = r#"# A twist with reference coordinate frame and timestamp + +std_msgs/Header header +Twist twist +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -737,7 +1742,43 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for TwistWithCovariance { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovariance"; const MD5SUM: &'static str = "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; - const DEFINITION : & 'static str = "# This expresses velocity in free space with uncertainty.\n\nTwist twist\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance" ; + const DEFINITION: &'static str = r#"# This expresses velocity in free space with uncertainty. + +Twist twist + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -756,7 +1797,88 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for TwistWithCovarianceStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/TwistWithCovarianceStamped"; const MD5SUM: &'static str = "7019807c85ce8602fb83180366470670"; - const DEFINITION : & 'static str = "# This represents an estimated twist with reference coordinate frame and timestamp.\n\nstd_msgs/Header header\nTwistWithCovariance twist" ; + const DEFINITION: &'static str = r#"# This represents an estimated twist with reference coordinate frame and timestamp. + +std_msgs/Header header +TwistWithCovariance twist +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/TwistWithCovariance +# This expresses velocity in free space with uncertainty. + +Twist twist + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -776,7 +1898,15 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Vector3 { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Vector3"; const MD5SUM: &'static str = "4a842b65f413084dc2b10fb484ea7f17"; - const DEFINITION : & 'static str = "# This represents a vector in free space.\n\n# This is semantically different than a point.\n# A vector is always anchored at the origin.\n# When a transform is applied to a vector, only the rotational component is applied.\n\nfloat64 x\nfloat64 y\nfloat64 z" ; + const DEFINITION: &'static str = r#"# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -795,7 +1925,35 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Vector3Stamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Vector3Stamped"; const MD5SUM: &'static str = "5cd361f2989a2e76d5aaf432c3bf0fb9"; - const DEFINITION : & 'static str = "# This represents a Vector3 with reference coordinate frame and timestamp\n\n# Note that this follows vector semantics with it always anchored at the origin,\n# so the rotational elements of a transform are the only parts applied when transforming.\n\nstd_msgs/Header header\nVector3 vector" ; + const DEFINITION: &'static str = r#"# This represents a Vector3 with reference coordinate frame and timestamp + +# Note that this follows vector semantics with it always anchored at the origin, +# so the rotational elements of a transform are the only parts applied when transforming. + +std_msgs/Header header +Vector3 vector +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -814,7 +1972,21 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for Wrench { const ROS_TYPE_NAME: &'static str = "geometry_msgs/Wrench"; const MD5SUM: &'static str = "4f539cf138b23283b520fd271b567936"; - const DEFINITION : & 'static str = "# This represents force in free space, separated into its linear and angular parts.\n\nVector3 force\nVector3 torque" ; + const DEFINITION: &'static str = r#"# This represents force in free space, separated into its linear and angular parts. + +Vector3 force +Vector3 torque +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -833,7 +2005,49 @@ pub mod geometry_msgs { impl ::roslibrust_codegen::RosMessageType for WrenchStamped { const ROS_TYPE_NAME: &'static str = "geometry_msgs/WrenchStamped"; const MD5SUM: &'static str = "5bc71556ab354cd6274d262a7de094a5"; - const DEFINITION : & 'static str = "# A wrench with reference coordinate frame and timestamp\n\nstd_msgs/Header header\nWrench wrench" ; + const DEFINITION: &'static str = r#"# A wrench with reference coordinate frame and timestamp + +std_msgs/Header header +Wrench wrench +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Wrench +# This represents force in free space, separated into its linear and angular parts. + +Vector3 force +Vector3 torque +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } } #[allow(unused_imports)] @@ -868,7 +2082,35 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GridCells { const ROS_TYPE_NAME: &'static str = "nav_msgs/GridCells"; const MD5SUM: &'static str = "bb9f07bfd2183241b5719f45a81f8cc5"; - const DEFINITION : & 'static str = "# An array of cells in a 2D grid\n\nstd_msgs/Header header\n\n# Width of each cell\nfloat32 cell_width\n\n# Height of each cell\nfloat32 cell_height\n\n# Each cell is represented by the Point at the center of the cell\ngeometry_msgs/Point[] cells" ; + const DEFINITION: &'static str = r#"# An array of cells in a 2D grid + +std_msgs/Header header + +# Width of each cell +float32 cell_width + +# Height of each cell +float32 cell_height + +# Each cell is represented by the Point at the center of the cell +geometry_msgs/Point[] cells +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -890,7 +2132,57 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for MapMetaData { const ROS_TYPE_NAME: &'static str = "nav_msgs/MapMetaData"; const MD5SUM: &'static str = "d10232bae3de4ae536d98f679fce2cf2"; - const DEFINITION : & 'static str = "# This hold basic information about the characteristics of the OccupancyGrid\n\n# The time at which the map was loaded\nbuiltin_interfaces/Time map_load_time\n\n# The map resolution [m/cell]\nfloat32 resolution\n\n# Map width [cells]\nuint32 width\n\n# Map height [cells]\nuint32 height\n\n# The origin of the map [m, m, rad]. This is the real-world pose of the\n# bottom left corner of cell (0,0) in the map.\ngeometry_msgs/Pose origin" ; + const DEFINITION: &'static str = r#"# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1"#; } #[allow(non_snake_case)] #[derive( @@ -910,7 +2202,117 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for OccupancyGrid { const ROS_TYPE_NAME: &'static str = "nav_msgs/OccupancyGrid"; const MD5SUM: &'static str = "2b0657f1993991bf3953916eb5ff5203"; - const DEFINITION : & 'static str = "# This represents a 2-D grid map\nstd_msgs/Header header\n\n# MetaData for the map\nMapMetaData info\n\n# The map data, in row-major order, starting with (0,0). \n# Cell (1, 0) will be listed second, representing the next cell in the x direction. \n# Cell (0, 1) will be at the index equal to info.width, followed by (1, 1).\n# The values inside are application dependent, but frequently, \n# 0 represents unoccupied, 1 represents definitely occupied, and\n# -1 represents unknown. \nint8[] data" ; + const DEFINITION: &'static str = r#"# This represents a 2-D grid map +std_msgs/Header header + +# MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). +# Cell (1, 0) will be listed second, representing the next cell in the x direction. +# Cell (0, 1) will be at the index equal to info.width, followed by (1, 1). +# The values inside are application dependent, but frequently, +# 0 represents unoccupied, 1 represents definitely occupied, and +# -1 represents unknown. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -931,7 +2333,178 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for Odometry { const ROS_TYPE_NAME: &'static str = "nav_msgs/Odometry"; const MD5SUM: &'static str = "81a0900daae2c6c0acc71c9f8df88947"; - const DEFINITION : & 'static str = "# This represents an estimate of a position and velocity in free space.\n# The pose in this message should be specified in the coordinate frame given by header.frame_id\n# The twist in this message should be specified in the coordinate frame given by the child_frame_id\n\n# Includes the frame id of the pose parent.\nstd_msgs/Header header\n\n# Frame id the pose points to. The twist is in this coordinate frame.\nstring child_frame_id\n\n# Estimated pose that is typically relative to a fixed world frame.\ngeometry_msgs/PoseWithCovariance pose\n\n# Estimated linear and angular velocity relative to child_frame_id.\ngeometry_msgs/TwistWithCovariance twist" ; + const DEFINITION: &'static str = r#"# This represents an estimate of a position and velocity in free space. +# The pose in this message should be specified in the coordinate frame given by header.frame_id +# The twist in this message should be specified in the coordinate frame given by the child_frame_id + +# Includes the frame id of the pose parent. +std_msgs/Header header + +# Frame id the pose points to. The twist is in this coordinate frame. +string child_frame_id + +# Estimated pose that is typically relative to a fixed world frame. +geometry_msgs/PoseWithCovariance pose + +# Estimated linear and angular velocity relative to child_frame_id. +geometry_msgs/TwistWithCovariance twist +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/TwistWithCovariance +# This expresses velocity in free space with uncertainty. + +Twist twist + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -950,7 +2523,109 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for Path { const ROS_TYPE_NAME: &'static str = "nav_msgs/Path"; const MD5SUM: &'static str = "9f78b006a4c2cc2a146c12ed59d1bb7f"; - const DEFINITION : & 'static str = "# An array of poses that represents a Path for a robot to follow.\n\n# Indicates the frame_id of the path.\nstd_msgs/Header header\n\n# Array of poses to follow.\ngeometry_msgs/PoseStamped[] poses" ; + const DEFINITION: &'static str = r#"# An array of poses that represents a Path for a robot to follow. + +# Indicates the frame_id of the path. +std_msgs/Header header + +# Array of poses to follow. +geometry_msgs/PoseStamped[] poses +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseStamped +# A Pose with reference coordinate frame and timestamp + +std_msgs/Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -966,7 +2641,7 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = "# Get the map as a nav_msgs/OccupancyGrid"; + const DEFINITION: &'static str = r#"# Get the map as a nav_msgs/OccupancyGrid"#; } #[allow(non_snake_case)] #[derive( @@ -984,8 +2659,219 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetMapResponse"; const MD5SUM: &'static str = "d6e8b0301af2dfe2244959ba20a4080a"; - const DEFINITION: &'static str = - "# The current map hosted by this map service.\nOccupancyGrid map"; + const DEFINITION: &'static str = r#"# The current map hosted by this map service. +OccupancyGrid map +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map +std_msgs/Header header + +# MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). +# Cell (1, 0) will be listed second, representing the next cell in the x direction. +# Cell (0, 1) will be at the index equal to info.width, followed by (1, 1). +# The values inside are application dependent, but frequently, +# 0 represents unoccupied, 1 represents definitely occupied, and +# -1 represents unknown. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } pub struct GetMap {} impl ::roslibrust_codegen::RosServiceType for GetMap { @@ -1012,7 +2898,113 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetPlanRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetPlanRequest"; const MD5SUM: &'static str = "e4855e4d3c7377c76ec90e403202286a"; - const DEFINITION : & 'static str = "# Get a plan from the current position to the goal Pose\n\n# The start pose for the plan\ngeometry_msgs/PoseStamped start\n\n# The final pose of the goal position\ngeometry_msgs/PoseStamped goal\n\n# If the goal is obstructed, how many meters the planner can\n# relax the constraint in x and y before failing.\nfloat32 tolerance" ; + const DEFINITION: &'static str = r#"# Get a plan from the current position to the goal Pose + +# The start pose for the plan +geometry_msgs/PoseStamped start + +# The final pose of the goal position +geometry_msgs/PoseStamped goal + +# If the goal is obstructed, how many meters the planner can +# relax the constraint in x and y before failing. +float32 tolerance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseStamped +# A Pose with reference coordinate frame and timestamp + +std_msgs/Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1030,8 +3022,209 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for GetPlanResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/GetPlanResponse"; const MD5SUM: &'static str = "37c13f9b42d0ee04e1dae0d4f7d14878"; - const DEFINITION: &'static str = - "# Array of poses from start to goal if one was successfully found.\nPath plan"; + const DEFINITION: &'static str = r#"# Array of poses from start to goal if one was successfully found. +Path plan +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseStamped +# A Pose with reference coordinate frame and timestamp + +std_msgs/Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/Path +# An array of poses that represents a Path for a robot to follow. + +# Indicates the frame_id of the path. +std_msgs/Header header + +# Array of poses to follow. +geometry_msgs/PoseStamped[] poses +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseStamped +# A Pose with reference coordinate frame and timestamp + +std_msgs/Header header +Pose pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } pub struct GetPlan {} impl ::roslibrust_codegen::RosServiceType for GetPlan { @@ -1056,7 +3249,10 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for LoadMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/LoadMapRequest"; const MD5SUM: &'static str = "3813ba1ae85fbcd4dc88c90f1426b90b"; - const DEFINITION : & 'static str = "# URL of map resource\n# Can be an absolute path to a file: file:///path/to/maps/floor1.yaml\n# Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml\nstring map_url" ; + const DEFINITION: &'static str = r#"# URL of map resource +# Can be an absolute path to a file: file:///path/to/maps/floor1.yaml +# Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml +string map_url"#; } #[allow(non_snake_case)] #[derive( @@ -1075,7 +3271,227 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for LoadMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/LoadMapResponse"; const MD5SUM: &'static str = "cdb849e3dfaed8b5fe66776d7a64b83e"; - const DEFINITION : & 'static str = "# Result code defintions\nuint8 RESULT_SUCCESS=0\nuint8 RESULT_MAP_DOES_NOT_EXIST=1\nuint8 RESULT_INVALID_MAP_DATA=2\nuint8 RESULT_INVALID_MAP_METADATA=3\nuint8 RESULT_UNDEFINED_FAILURE=255\n\n# Returned map is only valid if result equals RESULT_SUCCESS\nnav_msgs/OccupancyGrid map\nuint8 result" ; + const DEFINITION: &'static str = r#"# Result code defintions +uint8 RESULT_SUCCESS=0 +uint8 RESULT_MAP_DOES_NOT_EXIST=1 +uint8 RESULT_INVALID_MAP_DATA=2 +uint8 RESULT_INVALID_MAP_METADATA=3 +uint8 RESULT_UNDEFINED_FAILURE=255 + +# Returned map is only valid if result equals RESULT_SUCCESS +nav_msgs/OccupancyGrid map +uint8 result +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map +std_msgs/Header header + +# MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). +# Cell (1, 0) will be listed second, representing the next cell in the x direction. +# Cell (0, 1) will be at the index equal to info.width, followed by (1, 1). +# The values inside are application dependent, but frequently, +# 0 represents unoccupied, 1 represents definitely occupied, and +# -1 represents unknown. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } impl LoadMapResponse { pub const r#RESULT_SUCCESS: u8 = 0u8; @@ -1108,7 +3524,365 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for SetMapRequest { const ROS_TYPE_NAME: &'static str = "nav_msgs/SetMapRequest"; const MD5SUM: &'static str = "98782a373ad73e1165352caf85923850"; - const DEFINITION : & 'static str = "# Set a new map together with an initial pose\n\n# Requested 2D map to be set.\nnav_msgs/OccupancyGrid map\n\n# Estimated initial pose when setting new map.\ngeometry_msgs/PoseWithCovarianceStamped initial_pose" ; + const DEFINITION: &'static str = r#"# Set a new map together with an initial pose + +# Requested 2D map to be set. +nav_msgs/OccupancyGrid map + +# Estimated initial pose when setting new map. +geometry_msgs/PoseWithCovarianceStamped initial_pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseWithCovarianceStamped +# This expresses an estimated pose with a reference coordinate frame and timestamp + +std_msgs/Header header +PoseWithCovariance pose +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/PoseWithCovariance +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/OccupancyGrid +# This represents a 2-D grid map +std_msgs/Header header + +# MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). +# Cell (1, 0) will be listed second, representing the next cell in the x direction. +# Cell (0, 1) will be at the index equal to info.width, followed by (1, 1). +# The values inside are application dependent, but frequently, +# 0 represents unoccupied, 1 represents definitely occupied, and +# -1 represents unknown. +int8[] data +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: nav_msgs/MapMetaData +# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1126,8 +3900,8 @@ pub mod nav_msgs { impl ::roslibrust_codegen::RosMessageType for SetMapResponse { const ROS_TYPE_NAME: &'static str = "nav_msgs/SetMapResponse"; const MD5SUM: &'static str = "358e233cde0c8a8bcfea4ce193f8fc15"; - const DEFINITION: &'static str = - "# True if the map was successfully set, false otherwise.\nbool success"; + const DEFINITION: &'static str = r#"# True if the map was successfully set, false otherwise. +bool success"#; } pub struct SetMap {} impl ::roslibrust_codegen::RosServiceType for SetMap { @@ -1181,7 +3955,68 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for BatteryState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/BatteryState"; const MD5SUM: &'static str = "0e25cedcd370a46961764fe3a9d2ddcb"; - const DEFINITION : & 'static str = "# Constants are chosen to match the enums in the linux kernel\n# defined in include/linux/power_supply.h as of version 3.7\n# The one difference is for style reasons the constants are\n# all uppercase not mixed case.\n\n# Power supply status constants\nuint8 POWER_SUPPLY_STATUS_UNKNOWN = 0\nuint8 POWER_SUPPLY_STATUS_CHARGING = 1\nuint8 POWER_SUPPLY_STATUS_DISCHARGING = 2\nuint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3\nuint8 POWER_SUPPLY_STATUS_FULL = 4\n\n# Power supply health constants\nuint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0\nuint8 POWER_SUPPLY_HEALTH_GOOD = 1\nuint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2\nuint8 POWER_SUPPLY_HEALTH_DEAD = 3\nuint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4\nuint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5\nuint8 POWER_SUPPLY_HEALTH_COLD = 6\nuint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7\nuint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8\n\n# Power supply technology (chemistry) constants\nuint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0\nuint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1\nuint8 POWER_SUPPLY_TECHNOLOGY_LION = 2\nuint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3\nuint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4\nuint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5\nuint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6\n\nstd_msgs/Header header\nfloat32 voltage # Voltage in Volts (Mandatory)\nfloat32 temperature # Temperature in Degrees Celsius (If unmeasured NaN)\nfloat32 current # Negative when discharging (A) (If unmeasured NaN)\nfloat32 charge # Current charge in Ah (If unmeasured NaN)\nfloat32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN)\nfloat32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN)\nfloat32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN)\nuint8 power_supply_status # The charging status as reported. Values defined above\nuint8 power_supply_health # The battery health metric. Values defined above\nuint8 power_supply_technology # The battery chemistry. Values defined above\nbool present # True if the battery is present\n\nfloat32[] cell_voltage # An array of individual cell voltages for each cell in the pack\n # If individual voltages unknown but number of cells known set each to NaN\nfloat32[] cell_temperature # An array of individual cell temperatures for each cell in the pack\n # If individual temperatures unknown but number of cells known set each to NaN\nstring location # The location into which the battery is inserted. (slot number or plug)\nstring serial_number # The best approximation of the battery serial number" ; + const DEFINITION: &'static str = r#"# Constants are chosen to match the enums in the linux kernel +# defined in include/linux/power_supply.h as of version 3.7 +# The one difference is for style reasons the constants are +# all uppercase not mixed case. + +# Power supply status constants +uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0 +uint8 POWER_SUPPLY_STATUS_CHARGING = 1 +uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2 +uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3 +uint8 POWER_SUPPLY_STATUS_FULL = 4 + +# Power supply health constants +uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0 +uint8 POWER_SUPPLY_HEALTH_GOOD = 1 +uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2 +uint8 POWER_SUPPLY_HEALTH_DEAD = 3 +uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 +uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 +uint8 POWER_SUPPLY_HEALTH_COLD = 6 +uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 +uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 + +# Power supply technology (chemistry) constants +uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 +uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1 +uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2 +uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3 +uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4 +uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5 +uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6 + +std_msgs/Header header +float32 voltage # Voltage in Volts (Mandatory) +float32 temperature # Temperature in Degrees Celsius (If unmeasured NaN) +float32 current # Negative when discharging (A) (If unmeasured NaN) +float32 charge # Current charge in Ah (If unmeasured NaN) +float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN) +float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN) +float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN) +uint8 power_supply_status # The charging status as reported. Values defined above +uint8 power_supply_health # The battery health metric. Values defined above +uint8 power_supply_technology # The battery chemistry. Values defined above +bool present # True if the battery is present + +float32[] cell_voltage # An array of individual cell voltages for each cell in the pack + # If individual voltages unknown but number of cells known set each to NaN +float32[] cell_temperature # An array of individual cell temperatures for each cell in the pack + # If individual temperatures unknown but number of cells known set each to NaN +string location # The location into which the battery is inserted. (slot number or plug) +string serial_number # The best approximation of the battery serial number +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } impl BatteryState { pub const r#POWER_SUPPLY_STATUS_UNKNOWN: u8 = 0u8; @@ -1232,7 +4067,169 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for CameraInfo { const ROS_TYPE_NAME: &'static str = "sensor_msgs/CameraInfo"; const MD5SUM: &'static str = "47b55ddbbf2ec398f94cddf328bbc2ac"; - const DEFINITION : & 'static str = "# This message defines meta information for a camera. It should be in a\n# camera namespace on topic \"camera_info\" and accompanied by up to five\n# image topics named:\n#\n# image_raw - raw data from the camera driver, possibly Bayer encoded\n# image - monochrome, distorted\n# image_color - color, distorted\n# image_rect - monochrome, rectified\n# image_rect_color - color, rectified\n#\n# The image_pipeline contains packages (image_proc, stereo_image_proc)\n# for producing the four processed image topics from image_raw and\n# camera_info. The meaning of the camera parameters are described in\n# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n#\n# The image_geometry package provides a user-friendly interface to\n# common operations using this meta information. If you want to, e.g.,\n# project a 3d point into image coordinates, we strongly recommend\n# using image_geometry.\n#\n# If the camera is uncalibrated, the matrices D, K, R, P should be left\n# zeroed out. In particular, clients may assume that K[0] == 0.0\n# indicates an uncalibrated camera.\n\n#######################################################################\n# Image acquisition info #\n#######################################################################\n\n# Time of image acquisition, camera coordinate frame ID\nstd_msgs/Header header # Header timestamp should be acquisition time of image\n # Header frame_id should be optical frame of camera\n # origin of frame should be optical center of camera\n # +x should point to the right in the image\n # +y should point down in the image\n # +z should point into the plane of the image\n\n\n#######################################################################\n# Calibration Parameters #\n#######################################################################\n# These are fixed during camera calibration. Their values will be the #\n# same in all messages until the camera is recalibrated. Note that #\n# self-calibrating systems may \"recalibrate\" frequently. #\n# #\n# The internal parameters can be used to warp a raw (distorted) image #\n# to: #\n# 1. An undistorted image (requires D and K) #\n# 2. A rectified image (requires D, K, R) #\n# The projection matrix P projects 3D points into the rectified image.#\n#######################################################################\n\n# The image dimensions with which the camera was calibrated.\n# Normally this will be the full camera resolution in pixels.\nuint32 height\nuint32 width\n\n# The distortion model used. Supported models are listed in\n# sensor_msgs/distortion_models.hpp. For most cameras, \"plumb_bob\" - a\n# simple model of radial and tangential distortion - is sufficent.\nstring distortion_model\n\n# The distortion parameters, size depending on the distortion model.\n# For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\nfloat64[] d\n\n# Intrinsic camera matrix for the raw (distorted) images.\n# [fx 0 cx]\n# K = [ 0 fy cy]\n# [ 0 0 1]\n# Projects 3D points in the camera coordinate frame to 2D pixel\n# coordinates using the focal lengths (fx, fy) and principal point\n# (cx, cy).\nfloat64[9] k # 3x3 row-major matrix\n\n# Rectification matrix (stereo cameras only)\n# A rotation matrix aligning the camera coordinate system to the ideal\n# stereo image plane so that epipolar lines in both stereo images are\n# parallel.\nfloat64[9] r # 3x3 row-major matrix\n\n# Projection/camera matrix\n# [fx' 0 cx' Tx]\n# P = [ 0 fy' cy' Ty]\n# [ 0 0 1 0]\n# By convention, this matrix specifies the intrinsic (camera) matrix\n# of the processed (rectified) image. That is, the left 3x3 portion\n# is the normal camera intrinsic matrix for the rectified image.\n# It projects 3D points in the camera coordinate frame to 2D pixel\n# coordinates using the focal lengths (fx', fy') and principal point\n# (cx', cy') - these may differ from the values in K.\n# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n# also have R = the identity and P[1:3,1:3] = K.\n# For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n# position of the optical center of the second camera in the first\n# camera's frame. We assume Tz = 0 so both cameras are in the same\n# stereo image plane. The first camera always has Tx = Ty = 0. For\n# the right (second) camera of a horizontal stereo pair, Ty = 0 and\n# Tx = -fx' * B, where B is the baseline between the cameras.\n# Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n# the rectified image is given by:\n# [u v w]' = P * [X Y Z 1]'\n# x = u / w\n# y = v / w\n# This holds for both images of a stereo pair.\nfloat64[12] p # 3x4 row-major matrix\n\n\n#######################################################################\n# Operational Parameters #\n#######################################################################\n# These define the image region actually captured by the camera #\n# driver. Although they affect the geometry of the output image, they #\n# may be changed freely without recalibrating the camera. #\n#######################################################################\n\n# Binning refers here to any camera setting which combines rectangular\n# neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n# resolution of the output image to\n# (width / binning_x) x (height / binning_y).\n# The default values binning_x = binning_y = 0 is considered the same\n# as binning_x = binning_y = 1 (no subsampling).\nuint32 binning_x\nuint32 binning_y\n\n# Region of interest (subwindow of full camera resolution), given in\n# full resolution (unbinned) image coordinates. A particular ROI\n# always denotes the same window of pixels on the camera sensor,\n# regardless of binning settings.\n# The default setting of roi (all values 0) is considered the same as\n# full resolution (roi.width = width, roi.height = height).\nRegionOfInterest roi" ; + const DEFINITION: &'static str = r#"# This message defines meta information for a camera. It should be in a +# camera namespace on topic "camera_info" and accompanied by up to five +# image topics named: +# +# image_raw - raw data from the camera driver, possibly Bayer encoded +# image - monochrome, distorted +# image_color - color, distorted +# image_rect - monochrome, rectified +# image_rect_color - color, rectified +# +# The image_pipeline contains packages (image_proc, stereo_image_proc) +# for producing the four processed image topics from image_raw and +# camera_info. The meaning of the camera parameters are described in +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. +# +# The image_geometry package provides a user-friendly interface to +# common operations using this meta information. If you want to, e.g., +# project a 3d point into image coordinates, we strongly recommend +# using image_geometry. +# +# If the camera is uncalibrated, the matrices D, K, R, P should be left +# zeroed out. In particular, clients may assume that K[0] == 0.0 +# indicates an uncalibrated camera. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, camera coordinate frame ID +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into the plane of the image + + +####################################################################### +# Calibration Parameters # +####################################################################### +# These are fixed during camera calibration. Their values will be the # +# same in all messages until the camera is recalibrated. Note that # +# self-calibrating systems may "recalibrate" frequently. # +# # +# The internal parameters can be used to warp a raw (distorted) image # +# to: # +# 1. An undistorted image (requires D and K) # +# 2. A rectified image (requires D, K, R) # +# The projection matrix P projects 3D points into the rectified image.# +####################################################################### + +# The image dimensions with which the camera was calibrated. +# Normally this will be the full camera resolution in pixels. +uint32 height +uint32 width + +# The distortion model used. Supported models are listed in +# sensor_msgs/distortion_models.hpp. For most cameras, "plumb_bob" - a +# simple model of radial and tangential distortion - is sufficent. +string distortion_model + +# The distortion parameters, size depending on the distortion model. +# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). +float64[] d + +# Intrinsic camera matrix for the raw (distorted) images. +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy). +float64[9] k # 3x3 row-major matrix + +# Rectification matrix (stereo cameras only) +# A rotation matrix aligning the camera coordinate system to the ideal +# stereo image plane so that epipolar lines in both stereo images are +# parallel. +float64[9] r # 3x3 row-major matrix + +# Projection/camera matrix +# [fx' 0 cx' Tx] +# P = [ 0 fy' cy' Ty] +# [ 0 0 1 0] +# By convention, this matrix specifies the intrinsic (camera) matrix +# of the processed (rectified) image. That is, the left 3x3 portion +# is the normal camera intrinsic matrix for the rectified image. +# It projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx', fy') and principal point +# (cx', cy') - these may differ from the values in K. +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will +# also have R = the identity and P[1:3,1:3] = K. +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the +# position of the optical center of the second camera in the first +# camera's frame. We assume Tz = 0 so both cameras are in the same +# stereo image plane. The first camera always has Tx = Ty = 0. For +# the right (second) camera of a horizontal stereo pair, Ty = 0 and +# Tx = -fx' * B, where B is the baseline between the cameras. +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto +# the rectified image is given by: +# [u v w]' = P * [X Y Z 1]' +# x = u / w +# y = v / w +# This holds for both images of a stereo pair. +float64[12] p # 3x4 row-major matrix + + +####################################################################### +# Operational Parameters # +####################################################################### +# These define the image region actually captured by the camera # +# driver. Although they affect the geometry of the output image, they # +# may be changed freely without recalibrating the camera. # +####################################################################### + +# Binning refers here to any camera setting which combines rectangular +# neighborhoods of pixels into larger "super-pixels." It reduces the +# resolution of the output image to +# (width / binning_x) x (height / binning_y). +# The default values binning_x = binning_y = 0 is considered the same +# as binning_x = binning_y = 1 (no subsampling). +uint32 binning_x +uint32 binning_y + +# Region of interest (subwindow of full camera resolution), given in +# full resolution (unbinned) image coordinates. A particular ROI +# always denotes the same window of pixels on the camera sensor, +# regardless of binning settings. +# The default setting of roi (all values 0) is considered the same as +# full resolution (roi.width = width, roi.height = height). +RegionOfInterest roi +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1251,7 +4248,30 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for ChannelFloat32 { const ROS_TYPE_NAME: &'static str = "sensor_msgs/ChannelFloat32"; const MD5SUM: &'static str = "3d40139cdd33dfedcb71ffeeeb42ae7f"; - const DEFINITION : & 'static str = "# This message is used by the PointCloud message to hold optional data\n# associated with each point in the cloud. The length of the values\n# array should be the same as the length of the points array in the\n# PointCloud, and each value should be associated with the corresponding\n# point.\n#\n# Channel names in existing practice include:\n# \"u\", \"v\" - row and column (respectively) in the left stereo image.\n# This is opposite to usual conventions but remains for\n# historical reasons. The newer PointCloud2 message has no\n# such problem.\n# \"rgb\" - For point clouds produced by color stereo cameras. uint8\n# (R,G,B) values packed into the least significant 24 bits,\n# in order.\n# \"intensity\" - laser or pixel intensity.\n# \"distance\"\n\n# The channel name should give semantics of the channel (e.g.\n# \"intensity\" instead of \"value\").\nstring name\n\n# The values array should be 1-1 with the elements of the associated\n# PointCloud.\nfloat32[] values" ; + const DEFINITION: &'static str = r#"# This message is used by the PointCloud message to hold optional data +# associated with each point in the cloud. The length of the values +# array should be the same as the length of the points array in the +# PointCloud, and each value should be associated with the corresponding +# point. +# +# Channel names in existing practice include: +# "u", "v" - row and column (respectively) in the left stereo image. +# This is opposite to usual conventions but remains for +# historical reasons. The newer PointCloud2 message has no +# such problem. +# "rgb" - For point clouds produced by color stereo cameras. uint8 +# (R,G,B) values packed into the least significant 24 bits, +# in order. +# "intensity" - laser or pixel intensity. +# "distance" + +# The channel name should give semantics of the channel (e.g. +# "intensity" instead of "value"). +string name + +# The values array should be 1-1 with the elements of the associated +# PointCloud. +float32[] values"#; } #[allow(non_snake_case)] #[derive( @@ -1271,7 +4291,31 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for CompressedImage { const ROS_TYPE_NAME: &'static str = "sensor_msgs/CompressedImage"; const MD5SUM: &'static str = "1df88053b24348f5f499666c7cb1d980"; - const DEFINITION : & 'static str = "# This message contains a compressed image.\n\nstd_msgs/Header header # Header timestamp should be acquisition time of image\n # Header frame_id should be optical frame of camera\n # origin of frame should be optical center of cameara\n # +x should point to the right in the image\n # +y should point down in the image\n # +z should point into to plane of the image\n\nstring format # Specifies the format of the data\n # Acceptable values:\n # jpeg, png, tiff\n\nuint8[] data # Compressed image buffer" ; + const DEFINITION: &'static str = r#"# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1291,7 +4335,29 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for FluidPressure { const ROS_TYPE_NAME: &'static str = "sensor_msgs/FluidPressure"; const MD5SUM: &'static str = "4967e6ff4dcf72e6b8fca0600661e0b6"; - const DEFINITION : & 'static str = "# Single pressure reading. This message is appropriate for measuring the\n# pressure inside of a fluid (air, water, etc). This also includes\n# atmospheric or barometric pressure.\n#\n# This message is not appropriate for force/pressure contact sensors.\n\nstd_msgs/Header header # timestamp of the measurement\n # frame_id is the location of the pressure sensor\n\nfloat64 fluid_pressure # Absolute pressure reading in Pascals.\n\nfloat64 variance # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Single pressure reading. This message is appropriate for measuring the +# pressure inside of a fluid (air, water, etc). This also includes +# atmospheric or barometric pressure. +# +# This message is not appropriate for force/pressure contact sensors. + +std_msgs/Header header # timestamp of the measurement + # frame_id is the location of the pressure sensor + +float64 fluid_pressure # Absolute pressure reading in Pascals. + +float64 variance # 0 is interpreted as variance unknown +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1311,7 +4377,37 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Illuminance { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Illuminance"; const MD5SUM: &'static str = "94ccac1a1be684df74466dfc561512aa"; - const DEFINITION : & 'static str = "# Single photometric illuminance measurement. Light should be assumed to be\n# measured along the sensor's x-axis (the area of detection is the y-z plane).\n# The illuminance should have a 0 or positive value and be received with\n# the sensor's +X axis pointing toward the light source.\n#\n# Photometric illuminance is the measure of the human eye's sensitivity of the\n# intensity of light encountering or passing through a surface.\n#\n# All other Photometric and Radiometric measurements should not use this message.\n# This message cannot represent:\n# - Luminous intensity (candela/light source output)\n# - Luminance (nits/light output per area)\n# - Irradiance (watt/area), etc.\n\nstd_msgs/Header header # timestamp is the time the illuminance was measured\n # frame_id is the location and direction of the reading\n\nfloat64 illuminance # Measurement of the Photometric Illuminance in Lux.\n\nfloat64 variance # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Single photometric illuminance measurement. Light should be assumed to be +# measured along the sensor's x-axis (the area of detection is the y-z plane). +# The illuminance should have a 0 or positive value and be received with +# the sensor's +X axis pointing toward the light source. +# +# Photometric illuminance is the measure of the human eye's sensitivity of the +# intensity of light encountering or passing through a surface. +# +# All other Photometric and Radiometric measurements should not use this message. +# This message cannot represent: +# - Luminous intensity (candela/light source output) +# - Luminance (nits/light output per area) +# - Irradiance (watt/area), etc. + +std_msgs/Header header # timestamp is the time the illuminance was measured + # frame_id is the location and direction of the reading + +float64 illuminance # Measurement of the Photometric Illuminance in Lux. + +float64 variance # 0 is interpreted as variance unknown +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1335,7 +4431,43 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Image { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Image"; const MD5SUM: &'static str = "9c8b3d25a28b72f070da359dbecf985b"; - const DEFINITION : & 'static str = "# This message contains an uncompressed image\n# (0, 0) is at top-left corner of image\n\nstd_msgs/Header header # Header timestamp should be acquisition time of image\n # Header frame_id should be optical frame of camera\n # origin of frame should be optical center of cameara\n # +x should point to the right in the image\n # +y should point down in the image\n # +z should point into to plane of the image\n # If the frame_id here and the frame_id of the CameraInfo\n # message associated with the image conflict\n # the behavior is undefined\n\nuint32 height # image height, that is, number of rows\nuint32 width # image width, that is, number of columns\n\n# The legal values for encoding are in file include/sensor_msgs/image_encodings.hpp\n# If you want to standardize a new string format, join\n# ros-users@lists.ros.org and send an email proposing a new encoding.\n\nstring encoding # Encoding of pixels -- channel meaning, ordering, size\n # taken from the list of strings in include/sensor_msgs/image_encodings.hpp\n\nuint8 is_bigendian # is this data bigendian?\nuint32 step # Full row length in bytes\nuint8[] data # actual matrix data, size is (step * rows)" ; + const DEFINITION: &'static str = r#"# This message contains an uncompressed image +# (0, 0) is at top-left corner of image + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + # If the frame_id here and the frame_id of the CameraInfo + # message associated with the image conflict + # the behavior is undefined + +uint32 height # image height, that is, number of rows +uint32 width # image width, that is, number of columns + +# The legal values for encoding are in file include/sensor_msgs/image_encodings.hpp +# If you want to standardize a new string format, join +# ros-users@lists.ros.org and send an email proposing a new encoding. + +string encoding # Encoding of pixels -- channel meaning, ordering, size + # taken from the list of strings in include/sensor_msgs/image_encodings.hpp + +uint8 is_bigendian # is this data bigendian? +uint32 step # Full row length in bytes +uint8[] data # actual matrix data, size is (step * rows) +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1359,7 +4491,60 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Imu { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Imu"; const MD5SUM: &'static str = "058a92f712764b4ade1563e82041c569"; - const DEFINITION : & 'static str = "# This is a message to hold data from an IMU (Inertial Measurement Unit)\n#\n# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n#\n# If the covariance of the measurement is known, it should be filled in (if all you know is the\n# variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n# A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the\n# data a covariance will have to be assumed or gotten from some other source\n#\n# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an\n# orientation estimate), please set element 0 of the associated covariance matrix to -1\n# If you are interpreting this message, please check for a value of -1 in the first element of each\n# covariance matrix, and disregard the associated estimate.\n\nstd_msgs/Header header\n\ngeometry_msgs/Quaternion orientation\nfloat64[9] orientation_covariance # Row major about x, y, z axes\n\ngeometry_msgs/Vector3 angular_velocity\nfloat64[9] angular_velocity_covariance # Row major about x, y, z axes\n\ngeometry_msgs/Vector3 linear_acceleration\nfloat64[9] linear_acceleration_covariance # Row major x, y z" ; + const DEFINITION: &'static str = r#"# This is a message to hold data from an IMU (Inertial Measurement Unit) +# +# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec +# +# If the covariance of the measurement is known, it should be filled in (if all you know is the +# variance of each measurement, e.g. from the datasheet, just put those along the diagonal) +# A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the +# data a covariance will have to be assumed or gotten from some other source +# +# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an +# orientation estimate), please set element 0 of the associated covariance matrix to -1 +# If you are interpreting this message, please check for a value of -1 in the first element of each +# covariance matrix, and disregard the associated estimate. + +std_msgs/Header header + +geometry_msgs/Quaternion orientation +float64[9] orientation_covariance # Row major about x, y, z axes + +geometry_msgs/Vector3 angular_velocity +float64[9] angular_velocity_covariance # Row major about x, y, z axes + +geometry_msgs/Vector3 linear_acceleration +float64[9] linear_acceleration_covariance # Row major x, y z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1381,7 +4566,42 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for JointState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JointState"; const MD5SUM: &'static str = "3f61f1439a9898cdd864497d378ce55c"; - const DEFINITION : & 'static str = "# This is a message that holds data to describe the state of a set of torque controlled joints.\n#\n# The state of each joint (revolute or prismatic) is defined by:\n# * the position of the joint (rad or m),\n# * the velocity of the joint (rad/s or m/s) and\n# * the effort that is applied in the joint (Nm or N).\n#\n# Each joint is uniquely identified by its name\n# The header specifies the time at which the joint states were recorded. All the joint states\n# in one message have to be recorded at the same time.\n#\n# This message consists of a multiple arrays, one for each part of the joint state.\n# The goal is to make each of the fields optional. When e.g. your joints have no\n# effort associated with them, you can leave the effort array empty.\n#\n# All arrays in this message should have the same size, or be empty.\n# This is the only way to uniquely associate the joint name with the correct\n# states.\n\nstd_msgs/Header header\n\nstring[] name\nfloat64[] position\nfloat64[] velocity\nfloat64[] effort" ; + const DEFINITION: &'static str = r#"# This is a message that holds data to describe the state of a set of torque controlled joints. +# +# The state of each joint (revolute or prismatic) is defined by: +# * the position of the joint (rad or m), +# * the velocity of the joint (rad/s or m/s) and +# * the effort that is applied in the joint (Nm or N). +# +# Each joint is uniquely identified by its name +# The header specifies the time at which the joint states were recorded. All the joint states +# in one message have to be recorded at the same time. +# +# This message consists of a multiple arrays, one for each part of the joint state. +# The goal is to make each of the fields optional. When e.g. your joints have no +# effort associated with them, you can leave the effort array empty. +# +# All arrays in this message should have the same size, or be empty. +# This is the only way to uniquely associate the joint name with the correct +# states. + +std_msgs/Header header + +string[] name +float64[] position +float64[] velocity +float64[] effort +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1401,7 +4621,27 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Joy { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Joy"; const MD5SUM: &'static str = "967f985c9ca9013a4669430613e3e016"; - const DEFINITION : & 'static str = "# Reports the state of a joystick's axes and buttons.\n\n# The timestamp is the time at which data is received from the joystick.\nstd_msgs/Header header\n\n# The axes measurements from a joystick.\nfloat32[] axes\n\n# The buttons measurements from a joystick.\nint32[] buttons" ; + const DEFINITION: &'static str = r#"# Reports the state of a joystick's axes and buttons. + +# The timestamp is the time at which data is received from the joystick. +std_msgs/Header header + +# The axes measurements from a joystick. +float32[] axes + +# The buttons measurements from a joystick. +int32[] buttons +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1421,7 +4661,20 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for JoyFeedback { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JoyFeedback"; const MD5SUM: &'static str = "f4dcd73460360d98f36e55ee7f2e46f1"; - const DEFINITION : & 'static str = "# Declare of the type of feedback\nuint8 TYPE_LED = 0\nuint8 TYPE_RUMBLE = 1\nuint8 TYPE_BUZZER = 2\n\nuint8 type\n\n# This will hold an id number for each type of each feedback.\n# Example, the first led would be id=0, the second would be id=1\nuint8 id\n\n# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is\n# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on.\nfloat32 intensity" ; + const DEFINITION: &'static str = r#"# Declare of the type of feedback +uint8 TYPE_LED = 0 +uint8 TYPE_RUMBLE = 1 +uint8 TYPE_BUZZER = 2 + +uint8 type + +# This will hold an id number for each type of each feedback. +# Example, the first led would be id=0, the second would be id=1 +uint8 id + +# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is +# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. +float32 intensity"#; } impl JoyFeedback { pub const r#TYPE_LED: u8 = 0u8; @@ -1444,8 +4697,24 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for JoyFeedbackArray { const ROS_TYPE_NAME: &'static str = "sensor_msgs/JoyFeedbackArray"; const MD5SUM: &'static str = "cde5730a895b1fc4dee6f91b754b213d"; - const DEFINITION: &'static str = - "# This message publishes values for multiple feedback at once.\nJoyFeedback[] array"; + const DEFINITION: &'static str = r#"# This message publishes values for multiple feedback at once. +JoyFeedback[] array +================================================================================ +MSG: sensor_msgs/JoyFeedback +# Declare of the type of feedback +uint8 TYPE_LED = 0 +uint8 TYPE_RUMBLE = 1 +uint8 TYPE_BUZZER = 2 + +uint8 type + +# This will hold an id number for each type of each feedback. +# Example, the first led would be id=0, the second would be id=1 +uint8 id + +# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is +# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. +float32 intensity"#; } #[allow(non_snake_case)] #[derive( @@ -1463,7 +4732,11 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for LaserEcho { const ROS_TYPE_NAME: &'static str = "sensor_msgs/LaserEcho"; const MD5SUM: &'static str = "8bc5ae449b200fba4d552b4225586696"; - const DEFINITION : & 'static str = "# This message is a submessage of MultiEchoLaserScan and is not intended\n# to be used separately.\n\nfloat32[] echoes # Multiple values of ranges or intensities.\n # Each array represents data from the same angle increment." ; + const DEFINITION: &'static str = r#"# This message is a submessage of MultiEchoLaserScan and is not intended +# to be used separately. + +float32[] echoes # Multiple values of ranges or intensities. + # Each array represents data from the same angle increment."#; } #[allow(non_snake_case)] #[derive( @@ -1490,7 +4763,47 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for LaserScan { const ROS_TYPE_NAME: &'static str = "sensor_msgs/LaserScan"; const MD5SUM: &'static str = "f86984b4383bf67523c75820e114e988"; - const DEFINITION : & 'static str = "# Single scan from a planar laser range-finder\n#\n# If you have another ranging device with different behavior (e.g. a sonar\n# array), please find or create a different message, since applications\n# will make fairly laser-specific assumptions about this data\n\nstd_msgs/Header header # timestamp in the header is the acquisition time of\n # the first ray in the scan.\n #\n # in frame frame_id, angles are measured around\n # the positive Z axis (counterclockwise, if Z is up)\n # with zero angle being forward along the x axis\n\nfloat32 angle_min # start angle of the scan [rad]\nfloat32 angle_max # end angle of the scan [rad]\nfloat32 angle_increment # angular distance between measurements [rad]\n\nfloat32 time_increment # time between measurements [seconds] - if your scanner\n # is moving, this will be used in interpolating position\n # of 3d points\nfloat32 scan_time # time between scans [seconds]\n\nfloat32 range_min # minimum range value [m]\nfloat32 range_max # maximum range value [m]\n\nfloat32[] ranges # range data [m]\n # (Note: values < range_min or > range_max should be discarded)\nfloat32[] intensities # intensity data [device-specific units]. If your\n # device does not provide intensities, please leave\n # the array empty." ; + const DEFINITION: &'static str = r#"# Single scan from a planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +std_msgs/Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, angles are measured around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +float32[] ranges # range data [m] + # (Note: values < range_min or > range_max should be discarded) +float32[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1510,7 +4823,49 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for MagneticField { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MagneticField"; const MD5SUM: &'static str = "c8761d20eb9dc59addd882f1d4de2266"; - const DEFINITION : & 'static str = "# Measurement of the Magnetic Field vector at a specific location.\n#\n# If the covariance of the measurement is known, it should be filled in.\n# If all you know is the variance of each measurement, e.g. from the datasheet,\n# just put those along the diagonal.\n# A covariance matrix of all zeros will be interpreted as \"covariance unknown\",\n# and to use the data a covariance will have to be assumed or gotten from some\n# other source.\n\nstd_msgs/Header header # timestamp is the time the\n # field was measured\n # frame_id is the location and orientation\n # of the field measurement\n\ngeometry_msgs/Vector3 magnetic_field # x, y, and z components of the\n # field vector in Tesla\n # If your sensor does not output 3 axes,\n # put NaNs in the components not reported.\n\nfloat64[9] magnetic_field_covariance # Row major about x, y, z axes\n # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Measurement of the Magnetic Field vector at a specific location. +# +# If the covariance of the measurement is known, it should be filled in. +# If all you know is the variance of each measurement, e.g. from the datasheet, +# just put those along the diagonal. +# A covariance matrix of all zeros will be interpreted as "covariance unknown", +# and to use the data a covariance will have to be assumed or gotten from some +# other source. + +std_msgs/Header header # timestamp is the time the + # field was measured + # frame_id is the location and orientation + # of the field measurement + +geometry_msgs/Vector3 magnetic_field # x, y, and z components of the + # field vector in Tesla + # If your sensor does not output 3 axes, + # put NaNs in the components not reported. + +float64[9] magnetic_field_covariance # Row major about x, y, z axes + # 0 is interpreted as variance unknown +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1532,7 +4887,121 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for MultiDOFJointState { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MultiDOFJointState"; const MD5SUM: &'static str = "9eb02d78422731545fd7e9b60069f261"; - const DEFINITION : & 'static str = "# Representation of state for joints with multiple degrees of freedom,\n# following the structure of JointState which can only represent a single degree of freedom.\n#\n# It is assumed that a joint in a system corresponds to a transform that gets applied\n# along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw)\n# and those 3DOF can be expressed as a transformation matrix, and that transformation\n# matrix can be converted back to (x, y, yaw)\n#\n# Each joint is uniquely identified by its name\n# The header specifies the time at which the joint states were recorded. All the joint states\n# in one message have to be recorded at the same time.\n#\n# This message consists of a multiple arrays, one for each part of the joint state.\n# The goal is to make each of the fields optional. When e.g. your joints have no\n# wrench associated with them, you can leave the wrench array empty.\n#\n# All arrays in this message should have the same size, or be empty.\n# This is the only way to uniquely associate the joint name with the correct\n# states.\n\nstd_msgs/Header header\n\nstring[] joint_names\ngeometry_msgs/Transform[] transforms\ngeometry_msgs/Twist[] twist\ngeometry_msgs/Wrench[] wrench" ; + const DEFINITION: &'static str = r#"# Representation of state for joints with multiple degrees of freedom, +# following the structure of JointState which can only represent a single degree of freedom. +# +# It is assumed that a joint in a system corresponds to a transform that gets applied +# along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) +# and those 3DOF can be expressed as a transformation matrix, and that transformation +# matrix can be converted back to (x, y, yaw) +# +# Each joint is uniquely identified by its name +# The header specifies the time at which the joint states were recorded. All the joint states +# in one message have to be recorded at the same time. +# +# This message consists of a multiple arrays, one for each part of the joint state. +# The goal is to make each of the fields optional. When e.g. your joints have no +# wrench associated with them, you can leave the wrench array empty. +# +# All arrays in this message should have the same size, or be empty. +# This is the only way to uniquely associate the joint name with the correct +# states. + +std_msgs/Header header + +string[] joint_names +geometry_msgs/Transform[] transforms +geometry_msgs/Twist[] twist +geometry_msgs/Wrench[] wrench +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Wrench +# This represents force in free space, separated into its linear and angular parts. + +Vector3 force +Vector3 torque +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1559,7 +5028,56 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for MultiEchoLaserScan { const ROS_TYPE_NAME: &'static str = "sensor_msgs/MultiEchoLaserScan"; const MD5SUM: &'static str = "fda674281c16cdee9a79d075ab27d12f"; - const DEFINITION : & 'static str = "# Single scan from a multi-echo planar laser range-finder\n#\n# If you have another ranging device with different behavior (e.g. a sonar\n# array), please find or create a different message, since applications\n# will make fairly laser-specific assumptions about this data\n\nstd_msgs/Header header # timestamp in the header is the acquisition time of\n # the first ray in the scan.\n #\n # in frame frame_id, angles are measured around\n # the positive Z axis (counterclockwise, if Z is up)\n # with zero angle being forward along the x axis\n\nfloat32 angle_min # start angle of the scan [rad]\nfloat32 angle_max # end angle of the scan [rad]\nfloat32 angle_increment # angular distance between measurements [rad]\n\nfloat32 time_increment # time between measurements [seconds] - if your scanner\n # is moving, this will be used in interpolating position\n # of 3d points\nfloat32 scan_time # time between scans [seconds]\n\nfloat32 range_min # minimum range value [m]\nfloat32 range_max # maximum range value [m]\n\nLaserEcho[] ranges # range data [m]\n # (Note: NaNs, values < range_min or > range_max should be discarded)\n # +Inf measurements are out of range\n # -Inf measurements are too close to determine exact distance.\nLaserEcho[] intensities # intensity data [device-specific units]. If your\n # device does not provide intensities, please leave\n # the array empty." ; + const DEFINITION: &'static str = r#"# Single scan from a multi-echo planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +std_msgs/Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, angles are measured around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +LaserEcho[] ranges # range data [m] + # (Note: NaNs, values < range_min or > range_max should be discarded) + # +Inf measurements are out of range + # -Inf measurements are too close to determine exact distance. +LaserEcho[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. +================================================================================ +MSG: sensor_msgs/LaserEcho +# This message is a submessage of MultiEchoLaserScan and is not intended +# to be used separately. + +float32[] echoes # Multiple values of ranges or intensities. + # Each array represents data from the same angle increment. +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1583,7 +5101,86 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for NavSatFix { const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatFix"; const MD5SUM: &'static str = "faa1756146a6a934d7e4ef0e3855c531"; - const DEFINITION : & 'static str = "# Navigation Satellite fix for any Global Navigation Satellite System\n#\n# Specified using the WGS 84 reference ellipsoid\n\n# header.stamp specifies the ROS time for this measurement (the\n# corresponding satellite time may be reported using the\n# sensor_msgs/TimeReference message).\n#\n# header.frame_id is the frame of reference reported by the satellite\n# receiver, usually the location of the antenna. This is a\n# Euclidean frame relative to the vehicle, not a reference\n# ellipsoid.\nstd_msgs/Header header\n\n# Satellite fix status information.\nNavSatStatus status\n\n# Latitude [degrees]. Positive is north of equator; negative is south.\nfloat64 latitude\n\n# Longitude [degrees]. Positive is east of prime meridian; negative is west.\nfloat64 longitude\n\n# Altitude [m]. Positive is above the WGS 84 ellipsoid\n# (quiet NaN if no altitude is available).\nfloat64 altitude\n\n# Position covariance [m^2] defined relative to a tangential plane\n# through the reported position. The components are East, North, and\n# Up (ENU), in row-major order.\n#\n# Beware: this coordinate system exhibits singularities at the poles.\nfloat64[9] position_covariance\n\n# If the covariance of the fix is known, fill it in completely. If the\n# GPS receiver provides the variance of each measurement, put them\n# along the diagonal. If only Dilution of Precision is available,\n# estimate an approximate covariance from that.\n\nuint8 COVARIANCE_TYPE_UNKNOWN = 0\nuint8 COVARIANCE_TYPE_APPROXIMATED = 1\nuint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\nuint8 COVARIANCE_TYPE_KNOWN = 3\n\nuint8 position_covariance_type" ; + const DEFINITION: &'static str = r#"# Navigation Satellite fix for any Global Navigation Satellite System +# +# Specified using the WGS 84 reference ellipsoid + +# header.stamp specifies the ROS time for this measurement (the +# corresponding satellite time may be reported using the +# sensor_msgs/TimeReference message). +# +# header.frame_id is the frame of reference reported by the satellite +# receiver, usually the location of the antenna. This is a +# Euclidean frame relative to the vehicle, not a reference +# ellipsoid. +std_msgs/Header header + +# Satellite fix status information. +NavSatStatus status + +# Latitude [degrees]. Positive is north of equator; negative is south. +float64 latitude + +# Longitude [degrees]. Positive is east of prime meridian; negative is west. +float64 longitude + +# Altitude [m]. Positive is above the WGS 84 ellipsoid +# (quiet NaN if no altitude is available). +float64 altitude + +# Position covariance [m^2] defined relative to a tangential plane +# through the reported position. The components are East, North, and +# Up (ENU), in row-major order. +# +# Beware: this coordinate system exhibits singularities at the poles. +float64[9] position_covariance + +# If the covariance of the fix is known, fill it in completely. If the +# GPS receiver provides the variance of each measurement, put them +# along the diagonal. If only Dilution of Precision is available, +# estimate an approximate covariance from that. + +uint8 COVARIANCE_TYPE_UNKNOWN = 0 +uint8 COVARIANCE_TYPE_APPROXIMATED = 1 +uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 +uint8 COVARIANCE_TYPE_KNOWN = 3 + +uint8 position_covariance_type +================================================================================ +MSG: sensor_msgs/NavSatStatus +# Navigation Satellite fix status for any Global Navigation Satellite System. +# +# Whether to output an augmented fix is determined by both the fix +# type and the last time differential corrections were received. A +# fix is valid when status >= STATUS_FIX. + +int8 STATUS_NO_FIX = -1 # unable to fix position +int8 STATUS_FIX = 0 # unaugmented fix +int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation +int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation + +int8 status + +# Bits defining which Global Navigation Satellite System signals were +# used by the receiver. + +uint16 SERVICE_GPS = 1 +uint16 SERVICE_GLONASS = 2 +uint16 SERVICE_COMPASS = 4 # includes BeiDou. +uint16 SERVICE_GALILEO = 8 + +uint16 service +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } impl NavSatFix { pub const r#COVARIANCE_TYPE_UNKNOWN: u8 = 0u8; @@ -1608,7 +5205,28 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for NavSatStatus { const ROS_TYPE_NAME: &'static str = "sensor_msgs/NavSatStatus"; const MD5SUM: &'static str = "331cdbddfa4bc96ffc3b9ad98900a54c"; - const DEFINITION : & 'static str = "# Navigation Satellite fix status for any Global Navigation Satellite System.\n#\n# Whether to output an augmented fix is determined by both the fix\n# type and the last time differential corrections were received. A\n# fix is valid when status >= STATUS_FIX.\n\nint8 STATUS_NO_FIX = -1 # unable to fix position\nint8 STATUS_FIX = 0 # unaugmented fix\nint8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\nint8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n\nint8 status\n\n# Bits defining which Global Navigation Satellite System signals were\n# used by the receiver.\n\nuint16 SERVICE_GPS = 1\nuint16 SERVICE_GLONASS = 2\nuint16 SERVICE_COMPASS = 4 # includes BeiDou.\nuint16 SERVICE_GALILEO = 8\n\nuint16 service" ; + const DEFINITION: &'static str = r#"# Navigation Satellite fix status for any Global Navigation Satellite System. +# +# Whether to output an augmented fix is determined by both the fix +# type and the last time differential corrections were received. A +# fix is valid when status >= STATUS_FIX. + +int8 STATUS_NO_FIX = -1 # unable to fix position +int8 STATUS_FIX = 0 # unaugmented fix +int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation +int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation + +int8 status + +# Bits defining which Global Navigation Satellite System signals were +# used by the receiver. + +uint16 SERVICE_GPS = 1 +uint16 SERVICE_GLONASS = 2 +uint16 SERVICE_COMPASS = 4 # includes BeiDou. +uint16 SERVICE_GALILEO = 8 + +uint16 service"#; } impl NavSatStatus { pub const r#STATUS_NO_FIX: i8 = -1i8; @@ -1638,7 +5256,73 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for PointCloud { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointCloud"; const MD5SUM: &'static str = "95c9c548e015c235b38b961c79973db7"; - const DEFINITION : & 'static str = "## THIS MESSAGE IS DEPRECATED AS OF FOXY\n## Please use sensor_msgs/PointCloud2\n\n# This message holds a collection of 3d points, plus optional additional\n# information about each point.\n\n# Time of sensor data acquisition, coordinate frame ID.\nstd_msgs/Header header\n\n# Array of 3d points. Each Point32 should be interpreted as a 3d point\n# in the frame given in the header.\ngeometry_msgs/Point32[] points\n\n# Each channel should have the same number of elements as points array,\n# and the data in each channel should correspond 1:1 with each point.\n# Channel names in common practice are listed in ChannelFloat32.msg.\nChannelFloat32[] channels" ; + const DEFINITION: &'static str = r#"## THIS MESSAGE IS DEPRECATED AS OF FOXY +## Please use sensor_msgs/PointCloud2 + +# This message holds a collection of 3d points, plus optional additional +# information about each point. + +# Time of sensor data acquisition, coordinate frame ID. +std_msgs/Header header + +# Array of 3d points. Each Point32 should be interpreted as a 3d point +# in the frame given in the header. +geometry_msgs/Point32[] points + +# Each channel should have the same number of elements as points array, +# and the data in each channel should correspond 1:1 with each point. +# Channel names in common practice are listed in ChannelFloat32.msg. +ChannelFloat32[] channels +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommended to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z +================================================================================ +MSG: sensor_msgs/ChannelFloat32 +# This message is used by the PointCloud message to hold optional data +# associated with each point in the cloud. The length of the values +# array should be the same as the length of the points array in the +# PointCloud, and each value should be associated with the corresponding +# point. +# +# Channel names in existing practice include: +# "u", "v" - row and column (respectively) in the left stereo image. +# This is opposite to usual conventions but remains for +# historical reasons. The newer PointCloud2 message has no +# such problem. +# "rgb" - For point clouds produced by color stereo cameras. uint8 +# (R,G,B) values packed into the least significant 24 bits, +# in order. +# "intensity" - laser or pixel intensity. +# "distance" + +# The channel name should give semantics of the channel (e.g. +# "intensity" instead of "value"). +string name + +# The values array should be 1-1 with the elements of the associated +# PointCloud. +float32[] values +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1664,7 +5348,61 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for PointCloud2 { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointCloud2"; const MD5SUM: &'static str = "c61ffb665fe19735825e4dd31b53913d"; - const DEFINITION : & 'static str = "# This message holds a collection of N-dimensional points, which may\n# contain additional information such as normals, intensity, etc. The\n# point data is stored as a binary blob, its layout described by the\n# contents of the \"fields\" array.\n#\n# The point cloud data may be organized 2d (image-like) or 1d (unordered).\n# Point clouds organized as 2d images may be produced by camera depth sensors\n# such as stereo or time-of-flight.\n\n# Time of sensor data acquisition, and the coordinate frame ID (for 3d points).\nstd_msgs/Header header\n\n# 2D structure of the point cloud. If the cloud is unordered, height is\n# 1 and width is the length of the point cloud.\nuint32 height\nuint32 width\n\n# Describes the channels and their layout in the binary data blob.\nPointField[] fields\n\nbool is_bigendian # Is this data bigendian?\nuint32 point_step # Length of a point in bytes\nuint32 row_step # Length of a row in bytes\nuint8[] data # Actual point data, size is (row_step*height)\n\nbool is_dense # True if there are no invalid points" ; + const DEFINITION: &'static str = r#"# This message holds a collection of N-dimensional points, which may +# contain additional information such as normals, intensity, etc. The +# point data is stored as a binary blob, its layout described by the +# contents of the "fields" array. +# +# The point cloud data may be organized 2d (image-like) or 1d (unordered). +# Point clouds organized as 2d images may be produced by camera depth sensors +# such as stereo or time-of-flight. + +# Time of sensor data acquisition, and the coordinate frame ID (for 3d points). +std_msgs/Header header + +# 2D structure of the point cloud. If the cloud is unordered, height is +# 1 and width is the length of the point cloud. +uint32 height +uint32 width + +# Describes the channels and their layout in the binary data blob. +PointField[] fields + +bool is_bigendian # Is this data bigendian? +uint32 point_step # Length of a point in bytes +uint32 row_step # Length of a row in bytes +uint8[] data # Actual point data, size is (row_step*height) + +bool is_dense # True if there are no invalid points +================================================================================ +MSG: sensor_msgs/PointField +# This message holds the description of one point entry in the +# PointCloud2 message format. +uint8 INT8 = 1 +uint8 UINT8 = 2 +uint8 INT16 = 3 +uint8 UINT16 = 4 +uint8 INT32 = 5 +uint8 UINT32 = 6 +uint8 FLOAT32 = 7 +uint8 FLOAT64 = 8 + +# Common PointField names are x, y, z, intensity, rgb, rgba +string name # Name of field +uint32 offset # Offset from start of point struct +uint8 datatype # Datatype enumeration, see above +uint32 count # How many elements in the field +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1685,7 +5423,22 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for PointField { const ROS_TYPE_NAME: &'static str = "sensor_msgs/PointField"; const MD5SUM: &'static str = "268eacb2962780ceac86cbd17e328150"; - const DEFINITION : & 'static str = "# This message holds the description of one point entry in the\n# PointCloud2 message format.\nuint8 INT8 = 1\nuint8 UINT8 = 2\nuint8 INT16 = 3\nuint8 UINT16 = 4\nuint8 INT32 = 5\nuint8 UINT32 = 6\nuint8 FLOAT32 = 7\nuint8 FLOAT64 = 8\n\n# Common PointField names are x, y, z, intensity, rgb, rgba\nstring name # Name of field\nuint32 offset # Offset from start of point struct\nuint8 datatype # Datatype enumeration, see above\nuint32 count # How many elements in the field" ; + const DEFINITION: &'static str = r#"# This message holds the description of one point entry in the +# PointCloud2 message format. +uint8 INT8 = 1 +uint8 UINT8 = 2 +uint8 INT16 = 3 +uint8 UINT16 = 4 +uint8 INT32 = 5 +uint8 UINT32 = 6 +uint8 FLOAT32 = 7 +uint8 FLOAT64 = 8 + +# Common PointField names are x, y, z, intensity, rgb, rgba +string name # Name of field +uint32 offset # Offset from start of point struct +uint8 datatype # Datatype enumeration, see above +uint32 count # How many elements in the field"#; } impl PointField { pub const r#INT8: u8 = 1u8; @@ -1718,7 +5471,56 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Range { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Range"; const MD5SUM: &'static str = "1ec40687acdf15b9559a6ff690722eae"; - const DEFINITION : & 'static str = "# Single range reading from an active ranger that emits energy and reports\n# one range reading that is valid along an arc at the distance measured.\n# This message is not appropriate for laser scanners. See the LaserScan\n# message if you are working with a laser scanner.\n#\n# This message also can represent a fixed-distance (binary) ranger. This\n# sensor will have min_range===max_range===distance of detection.\n# These sensors follow REP 117 and will output -Inf if the object is detected\n# and +Inf if the object is outside of the detection range.\n\nstd_msgs/Header header # timestamp in the header is the time the ranger\n # returned the distance reading\n\n# Radiation type enums\n# If you want a value added to this list, send an email to the ros-users list\nuint8 ULTRASOUND=0\nuint8 INFRARED=1\n\nuint8 radiation_type # the type of radiation used by the sensor\n # (sound, IR, etc) [enum]\n\nfloat32 field_of_view # the size of the arc that the distance reading is\n # valid for [rad]\n # the object causing the range reading may have\n # been anywhere within -field_of_view/2 and\n # field_of_view/2 at the measured range.\n # 0 angle corresponds to the x-axis of the sensor.\n\nfloat32 min_range # minimum range value [m]\nfloat32 max_range # maximum range value [m]\n # Fixed distance rangers require min_range==max_range\n\nfloat32 range # range data [m]\n # (Note: values < range_min or > range_max should be discarded)\n # Fixed distance rangers only output -Inf or +Inf.\n # -Inf represents a detection within fixed distance.\n # (Detection too close to the sensor to quantify)\n # +Inf represents no detection within the fixed distance.\n # (Object out of range)" ; + const DEFINITION: &'static str = r#"# Single range reading from an active ranger that emits energy and reports +# one range reading that is valid along an arc at the distance measured. +# This message is not appropriate for laser scanners. See the LaserScan +# message if you are working with a laser scanner. +# +# This message also can represent a fixed-distance (binary) ranger. This +# sensor will have min_range===max_range===distance of detection. +# These sensors follow REP 117 and will output -Inf if the object is detected +# and +Inf if the object is outside of the detection range. + +std_msgs/Header header # timestamp in the header is the time the ranger + # returned the distance reading + +# Radiation type enums +# If you want a value added to this list, send an email to the ros-users list +uint8 ULTRASOUND=0 +uint8 INFRARED=1 + +uint8 radiation_type # the type of radiation used by the sensor + # (sound, IR, etc) [enum] + +float32 field_of_view # the size of the arc that the distance reading is + # valid for [rad] + # the object causing the range reading may have + # been anywhere within -field_of_view/2 and + # field_of_view/2 at the measured range. + # 0 angle corresponds to the x-axis of the sensor. + +float32 min_range # minimum range value [m] +float32 max_range # maximum range value [m] + # Fixed distance rangers require min_range==max_range + +float32 range # range data [m] + # (Note: values < range_min or > range_max should be discarded) + # Fixed distance rangers only output -Inf or +Inf. + # -Inf represents a detection within fixed distance. + # (Detection too close to the sensor to quantify) + # +Inf represents no detection within the fixed distance. + # (Object out of range) +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } impl Range { pub const r#ULTRASOUND: u8 = 0u8; @@ -1744,7 +5546,25 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for RegionOfInterest { const ROS_TYPE_NAME: &'static str = "sensor_msgs/RegionOfInterest"; const MD5SUM: &'static str = "bdb633039d588fcccb441a4d43ccfe09"; - const DEFINITION : & 'static str = "# This message is used to specify a region of interest within an image.\n#\n# When used to specify the ROI setting of the camera when the image was\n# taken, the height and width fields should either match the height and\n# width fields for the associated image; or height = width = 0\n# indicates that the full resolution image was captured.\n\nuint32 x_offset # Leftmost pixel of the ROI\n # (0 if the ROI includes the left edge of the image)\nuint32 y_offset # Topmost pixel of the ROI\n # (0 if the ROI includes the top edge of the image)\nuint32 height # Height of ROI\nuint32 width # Width of ROI\n\n# True if a distinct rectified ROI should be calculated from the \"raw\"\n# ROI in this message. Typically this should be False if the full image\n# is captured (ROI not used), and True if a subwindow is captured (ROI\n# used).\nbool do_rectify" ; + const DEFINITION: &'static str = r#"# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify"#; } #[allow(non_snake_case)] #[derive( @@ -1764,7 +5584,30 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for RelativeHumidity { const ROS_TYPE_NAME: &'static str = "sensor_msgs/RelativeHumidity"; const MD5SUM: &'static str = "71cfefa31dcc94f47083b1e89e6fa5c9"; - const DEFINITION : & 'static str = "# Single reading from a relative humidity sensor.\n# Defines the ratio of partial pressure of water vapor to the saturated vapor\n# pressure at a temperature.\n\nstd_msgs/Header header # timestamp of the measurement\n # frame_id is the location of the humidity sensor\n\nfloat64 relative_humidity # Expression of the relative humidity\n # from 0.0 to 1.0.\n # 0.0 is no partial pressure of water vapor\n # 1.0 represents partial pressure of saturation\n\nfloat64 variance # 0 is interpreted as variance unknown" ; + const DEFINITION: &'static str = r#"# Single reading from a relative humidity sensor. +# Defines the ratio of partial pressure of water vapor to the saturated vapor +# pressure at a temperature. + +std_msgs/Header header # timestamp of the measurement + # frame_id is the location of the humidity sensor + +float64 relative_humidity # Expression of the relative humidity + # from 0.0 to 1.0. + # 0.0 is no partial pressure of water vapor + # 1.0 represents partial pressure of saturation + +float64 variance # 0 is interpreted as variance unknown +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1784,7 +5627,25 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for Temperature { const ROS_TYPE_NAME: &'static str = "sensor_msgs/Temperature"; const MD5SUM: &'static str = "c6df0674fcfebff84a15927a80ebb14b"; - const DEFINITION : & 'static str = "# Single temperature reading.\n\nstd_msgs/Header header # timestamp is the time the temperature was measured\n # frame_id is the location of the temperature reading\n\nfloat64 temperature # Measurement of the Temperature in Degrees Celsius.\n\nfloat64 variance # 0 is interpreted as variance unknown." ; + const DEFINITION: &'static str = r#"# Single temperature reading. + +std_msgs/Header header # timestamp is the time the temperature was measured + # frame_id is the location of the temperature reading + +float64 temperature # Measurement of the Temperature in Degrees Celsius. + +float64 variance # 0 is interpreted as variance unknown. +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1804,7 +5665,24 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for TimeReference { const ROS_TYPE_NAME: &'static str = "sensor_msgs/TimeReference"; const MD5SUM: &'static str = "7cb7ae5aa838323e9028637e304e0ad7"; - const DEFINITION : & 'static str = "# Measurement from an external time source not actively synchronized with the system clock.\n\nstd_msgs/Header header # stamp is system time for which measurement was valid\n # frame_id is not used\n\nbuiltin_interfaces/Time time_ref # corresponding time from this external source\nstring source # (optional) name of time source" ; + const DEFINITION: &'static str = r#"# Measurement from an external time source not actively synchronized with the system clock. + +std_msgs/Header header # stamp is system time for which measurement was valid + # frame_id is not used + +builtin_interfaces/Time time_ref # corresponding time from this external source +string source # (optional) name of time source +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1822,7 +5700,212 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for SetCameraInfoRequest { const ROS_TYPE_NAME: &'static str = "sensor_msgs/SetCameraInfoRequest"; const MD5SUM: &'static str = "251c96e357751cc7c699c496178141d5"; - const DEFINITION : & 'static str = "# This service requests that a camera stores the given CameraInfo as that\n# camera's calibration information.\n#\n# The width and height in the camera_info field should match what the\n# camera is currently outputting on its camera_info topic, and the camera\n# will assume that the region of the imager that is being referred to is\n# the region that the camera is currently capturing.\n\nsensor_msgs/CameraInfo camera_info # The camera_info to store" ; + const DEFINITION: &'static str = r#"# This service requests that a camera stores the given CameraInfo as that +# camera's calibration information. +# +# The width and height in the camera_info field should match what the +# camera is currently outputting on its camera_info topic, and the camera +# will assume that the region of the imager that is being referred to is +# the region that the camera is currently capturing. + +sensor_msgs/CameraInfo camera_info # The camera_info to store +================================================================================ +MSG: sensor_msgs/CameraInfo +# This message defines meta information for a camera. It should be in a +# camera namespace on topic "camera_info" and accompanied by up to five +# image topics named: +# +# image_raw - raw data from the camera driver, possibly Bayer encoded +# image - monochrome, distorted +# image_color - color, distorted +# image_rect - monochrome, rectified +# image_rect_color - color, rectified +# +# The image_pipeline contains packages (image_proc, stereo_image_proc) +# for producing the four processed image topics from image_raw and +# camera_info. The meaning of the camera parameters are described in +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. +# +# The image_geometry package provides a user-friendly interface to +# common operations using this meta information. If you want to, e.g., +# project a 3d point into image coordinates, we strongly recommend +# using image_geometry. +# +# If the camera is uncalibrated, the matrices D, K, R, P should be left +# zeroed out. In particular, clients may assume that K[0] == 0.0 +# indicates an uncalibrated camera. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, camera coordinate frame ID +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into the plane of the image + + +####################################################################### +# Calibration Parameters # +####################################################################### +# These are fixed during camera calibration. Their values will be the # +# same in all messages until the camera is recalibrated. Note that # +# self-calibrating systems may "recalibrate" frequently. # +# # +# The internal parameters can be used to warp a raw (distorted) image # +# to: # +# 1. An undistorted image (requires D and K) # +# 2. A rectified image (requires D, K, R) # +# The projection matrix P projects 3D points into the rectified image.# +####################################################################### + +# The image dimensions with which the camera was calibrated. +# Normally this will be the full camera resolution in pixels. +uint32 height +uint32 width + +# The distortion model used. Supported models are listed in +# sensor_msgs/distortion_models.hpp. For most cameras, "plumb_bob" - a +# simple model of radial and tangential distortion - is sufficent. +string distortion_model + +# The distortion parameters, size depending on the distortion model. +# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). +float64[] d + +# Intrinsic camera matrix for the raw (distorted) images. +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy). +float64[9] k # 3x3 row-major matrix + +# Rectification matrix (stereo cameras only) +# A rotation matrix aligning the camera coordinate system to the ideal +# stereo image plane so that epipolar lines in both stereo images are +# parallel. +float64[9] r # 3x3 row-major matrix + +# Projection/camera matrix +# [fx' 0 cx' Tx] +# P = [ 0 fy' cy' Ty] +# [ 0 0 1 0] +# By convention, this matrix specifies the intrinsic (camera) matrix +# of the processed (rectified) image. That is, the left 3x3 portion +# is the normal camera intrinsic matrix for the rectified image. +# It projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx', fy') and principal point +# (cx', cy') - these may differ from the values in K. +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will +# also have R = the identity and P[1:3,1:3] = K. +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the +# position of the optical center of the second camera in the first +# camera's frame. We assume Tz = 0 so both cameras are in the same +# stereo image plane. The first camera always has Tx = Ty = 0. For +# the right (second) camera of a horizontal stereo pair, Ty = 0 and +# Tx = -fx' * B, where B is the baseline between the cameras. +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto +# the rectified image is given by: +# [u v w]' = P * [X Y Z 1]' +# x = u / w +# y = v / w +# This holds for both images of a stereo pair. +float64[12] p # 3x4 row-major matrix + + +####################################################################### +# Operational Parameters # +####################################################################### +# These define the image region actually captured by the camera # +# driver. Although they affect the geometry of the output image, they # +# may be changed freely without recalibrating the camera. # +####################################################################### + +# Binning refers here to any camera setting which combines rectangular +# neighborhoods of pixels into larger "super-pixels." It reduces the +# resolution of the output image to +# (width / binning_x) x (height / binning_y). +# The default values binning_x = binning_y = 0 is considered the same +# as binning_x = binning_y = 1 (no subsampling). +uint32 binning_x +uint32 binning_y + +# Region of interest (subwindow of full camera resolution), given in +# full resolution (unbinned) image coordinates. A particular ROI +# always denotes the same window of pixels on the camera sensor, +# regardless of binning settings. +# The default setting of roi (all values 0) is considered the same as +# full resolution (roi.width = width, roi.height = height). +RegionOfInterest roi +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -1841,7 +5924,8 @@ pub mod sensor_msgs { impl ::roslibrust_codegen::RosMessageType for SetCameraInfoResponse { const ROS_TYPE_NAME: &'static str = "sensor_msgs/SetCameraInfoResponse"; const MD5SUM: &'static str = "2ec6f3eff0161f4257b808b12bc830c2"; - const DEFINITION : & 'static str = "bool success # True if the call succeeded\nstring status_message # Used to give details about success" ; + const DEFINITION: &'static str = r#"bool success # True if the call succeeded +string status_message # Used to give details about success"#; } pub struct SetCameraInfo {} impl ::roslibrust_codegen::RosServiceType for SetCameraInfo { @@ -1881,7 +5965,24 @@ pub mod shape_msgs { impl ::roslibrust_codegen::RosMessageType for Mesh { const ROS_TYPE_NAME: &'static str = "shape_msgs/Mesh"; const MD5SUM: &'static str = "1ffdae9486cd3316a121c578b47a85cc"; - const DEFINITION : & 'static str = "# Definition of a mesh.\n\n# List of triangles; the index values refer to positions in vertices[].\nMeshTriangle[] triangles\n\n# The actual vertices that make up the mesh.\ngeometry_msgs/Point[] vertices" ; + const DEFINITION: &'static str = r#"# Definition of a mesh. + +# List of triangles; the index values refer to positions in vertices[]. +MeshTriangle[] triangles + +# The actual vertices that make up the mesh. +geometry_msgs/Point[] vertices +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: shape_msgs/MeshTriangle +# Definition of a triangle's vertices. + +uint32[3] vertex_indices"#; } #[allow(non_snake_case)] #[derive( @@ -1899,8 +6000,9 @@ pub mod shape_msgs { impl ::roslibrust_codegen::RosMessageType for MeshTriangle { const ROS_TYPE_NAME: &'static str = "shape_msgs/MeshTriangle"; const MD5SUM: &'static str = "23688b2e6d2de3d32fe8af104a903253"; - const DEFINITION: &'static str = - "# Definition of a triangle's vertices.\n\nuint32[3] vertex_indices"; + const DEFINITION: &'static str = r#"# Definition of a triangle's vertices. + +uint32[3] vertex_indices"#; } #[allow(non_snake_case)] #[derive( @@ -1918,7 +6020,13 @@ pub mod shape_msgs { impl ::roslibrust_codegen::RosMessageType for Plane { const ROS_TYPE_NAME: &'static str = "shape_msgs/Plane"; const MD5SUM: &'static str = "2c1b92ed8f31492f8e73f6a4a44ca796"; - const DEFINITION : & 'static str = "# Representation of a plane, using the plane equation ax + by + cz + d = 0.\n#\n# a := coef[0]\n# b := coef[1]\n# c := coef[2]\n# d := coef[3]\nfloat64[4] coef" ; + const DEFINITION: &'static str = r#"# Representation of a plane, using the plane equation ax + by + cz + d = 0. +# +# a := coef[0] +# b := coef[1] +# c := coef[2] +# d := coef[3] +float64[4] coef"#; } #[allow(non_snake_case)] #[derive( @@ -1938,7 +6046,87 @@ pub mod shape_msgs { impl ::roslibrust_codegen::RosMessageType for SolidPrimitive { const ROS_TYPE_NAME: &'static str = "shape_msgs/SolidPrimitive"; const MD5SUM: &'static str = "0cdf91a0a45ccd7bc1e0deb784cb2958"; - const DEFINITION : & 'static str = "# Defines box, sphere, cylinder, cone and prism.\n# All shapes are defined to have their bounding boxes centered around 0,0,0.\n\nuint8 BOX=1\nuint8 SPHERE=2\nuint8 CYLINDER=3\nuint8 CONE=4\nuint8 PRISM=5\n\n# The type of the shape\nuint8 type\n\n# The dimensions of the shape\nfloat64[<=3] dimensions # At no point will dimensions have a length > 3.\n\n# The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array.\n\n# For type BOX, the X, Y, and Z dimensions are the length of the corresponding sides of the box.\nuint8 BOX_X=0\nuint8 BOX_Y=1\nuint8 BOX_Z=2\n\n# For the SPHERE type, only one component is used, and it gives the radius of the sphere.\nuint8 SPHERE_RADIUS=0\n\n# For the CYLINDER and CONE types, the center line is oriented along the Z axis.\n# Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component of dimensions gives the\n# height of the cylinder (cone).\n# The CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the radius of\n# the base of the cylinder (cone).\n# Cone and cylinder primitives are defined to be circular. The tip of the cone\n# is pointing up, along +Z axis.\n\nuint8 CYLINDER_HEIGHT=0\nuint8 CYLINDER_RADIUS=1\n\nuint8 CONE_HEIGHT=0\nuint8 CONE_RADIUS=1\n\n# For the type PRISM, the center line is oriented along Z axis.\n# The PRISM_HEIGHT component of dimensions gives the\n# height of the prism.\n# The polygon defines the Z axis centered base of the prism.\n# The prism is constructed by extruding the base in +Z and -Z\n# directions by half of the PRISM_HEIGHT\n# Only x and y fields of the points are used in the polygon.\n# Points of the polygon are ordered counter-clockwise.\n\nuint8 PRISM_HEIGHT=0\ngeometry_msgs/Polygon polygon" ; + const DEFINITION: &'static str = r#"# Defines box, sphere, cylinder, cone and prism. +# All shapes are defined to have their bounding boxes centered around 0,0,0. + +uint8 BOX=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 CONE=4 +uint8 PRISM=5 + +# The type of the shape +uint8 type + +# The dimensions of the shape +float64[<=3] dimensions # At no point will dimensions have a length > 3. + +# The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array. + +# For type BOX, the X, Y, and Z dimensions are the length of the corresponding sides of the box. +uint8 BOX_X=0 +uint8 BOX_Y=1 +uint8 BOX_Z=2 + +# For the SPHERE type, only one component is used, and it gives the radius of the sphere. +uint8 SPHERE_RADIUS=0 + +# For the CYLINDER and CONE types, the center line is oriented along the Z axis. +# Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component of dimensions gives the +# height of the cylinder (cone). +# The CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the radius of +# the base of the cylinder (cone). +# Cone and cylinder primitives are defined to be circular. The tip of the cone +# is pointing up, along +Z axis. + +uint8 CYLINDER_HEIGHT=0 +uint8 CYLINDER_RADIUS=1 + +uint8 CONE_HEIGHT=0 +uint8 CONE_RADIUS=1 + +# For the type PRISM, the center line is oriented along Z axis. +# The PRISM_HEIGHT component of dimensions gives the +# height of the prism. +# The polygon defines the Z axis centered base of the prism. +# The prism is constructed by extruding the base in +Z and -Z +# directions by half of the PRISM_HEIGHT +# Only x and y fields of the points are used in the polygon. +# Points of the polygon are ordered counter-clockwise. + +uint8 PRISM_HEIGHT=0 +geometry_msgs/Polygon polygon +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommended to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z +================================================================================ +MSG: geometry_msgs/Polygon +# A specification of a polygon where the first and last points are assumed to be connected + +Point32[] points +================================================================================ +MSG: geometry_msgs/Point32 +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommended to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z"#; } impl SolidPrimitive { pub const r#BOX: u8 = 1u8; @@ -1986,7 +6174,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Bool { const ROS_TYPE_NAME: &'static str = "std_msgs/Bool"; const MD5SUM: &'static str = "8b94c1b53db61fb6aed406028ad6332a"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nbool data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +bool data"#; } #[allow(non_snake_case)] #[derive( @@ -2004,7 +6197,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Byte { const ROS_TYPE_NAME: &'static str = "std_msgs/Byte"; const MD5SUM: &'static str = "ad736a2e8818154c487bb80fe42ce43b"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nbyte data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +byte data"#; } #[allow(non_snake_case)] #[derive( @@ -2023,7 +6221,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for ByteMultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/ByteMultiArray"; const MD5SUM: &'static str = "70ea476cbcfd65ac2f68f3cda1e891fe"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nbyte[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +byte[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2041,7 +6301,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Char { const ROS_TYPE_NAME: &'static str = "std_msgs/Char"; const MD5SUM: &'static str = "1bf77f25acecdedba0e224b162199717"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nchar data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +char data"#; } #[allow(non_snake_case)] #[derive( @@ -2062,7 +6327,10 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for ColorRGBA { const ROS_TYPE_NAME: &'static str = "std_msgs/ColorRGBA"; const MD5SUM: &'static str = "a29a96539573343b1310c73607334b00"; - const DEFINITION: &'static str = "float32 r\nfloat32 g\nfloat32 b\nfloat32 a"; + const DEFINITION: &'static str = r#"float32 r +float32 g +float32 b +float32 a"#; } #[allow(non_snake_case)] #[derive( @@ -2078,7 +6346,7 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Empty { const ROS_TYPE_NAME: &'static str = "std_msgs/Empty"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -2096,7 +6364,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Float32 { const ROS_TYPE_NAME: &'static str = "std_msgs/Float32"; const MD5SUM: &'static str = "73fcbf46b49191e672908e50842a83d4"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nfloat32 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +float32 data"#; } #[allow(non_snake_case)] #[derive( @@ -2115,7 +6388,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Float32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Float32MultiArray"; const MD5SUM: &'static str = "6a40e0ffa6a17a503ac3f8616991b1f6"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nfloat32[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float32[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2133,7 +6468,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Float64 { const ROS_TYPE_NAME: &'static str = "std_msgs/Float64"; const MD5SUM: &'static str = "fdb28210bfa9d7c91146260178d9a584"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nfloat64 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +float64 data"#; } #[allow(non_snake_case)] #[derive( @@ -2152,7 +6492,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Float64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Float64MultiArray"; const MD5SUM: &'static str = "4b7d974086d4060e7db4613a7e6c3ba4"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nfloat64[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +float64[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2171,7 +6573,15 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Header { const ROS_TYPE_NAME: &'static str = "std_msgs/Header"; const MD5SUM: &'static str = "5ed6b5dd1ef879ffb9c2ac51bab61a63"; - const DEFINITION : & 'static str = "# Standard metadata for higher-level stamped data types.\n# This is generally used to communicate timestamped data\n# in a particular coordinate frame.\n\n# Two-integer timestamp that is expressed as seconds and nanoseconds.\nbuiltin_interfaces/Time stamp\n\n# Transform frame with which this data is associated.\nstring frame_id" ; + const DEFINITION: &'static str = r#"# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -2189,7 +6599,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int16 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int16"; const MD5SUM: &'static str = "8524586e34fbd7cb1c08c5f5f1ca0e57"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nint16 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +int16 data"#; } #[allow(non_snake_case)] #[derive( @@ -2208,7 +6623,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int16MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int16MultiArray"; const MD5SUM: &'static str = "d9338d7f523fcb692fae9d0a0e9f067c"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nint16[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int16[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2226,7 +6703,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int32 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int32"; const MD5SUM: &'static str = "da5909fbe378aeaf85e547e830cc1bb7"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nint32 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +int32 data"#; } #[allow(non_snake_case)] #[derive( @@ -2245,7 +6727,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int32MultiArray"; const MD5SUM: &'static str = "1d99f79f8b325b44fee908053e9c945b"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nint32[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int32[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2263,7 +6807,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int64 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int64"; const MD5SUM: &'static str = "34add168574510e6e17f5d23ecc077ef"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nint64 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +int64 data"#; } #[allow(non_snake_case)] #[derive( @@ -2282,7 +6831,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int64MultiArray"; const MD5SUM: &'static str = "54865aa6c65be0448113a2afc6a49270"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nint64[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int64[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2300,7 +6911,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int8 { const ROS_TYPE_NAME: &'static str = "std_msgs/Int8"; const MD5SUM: &'static str = "27ffa0c9c4b8fb8492252bcad9e5c57b"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nint8 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +int8 data"#; } #[allow(non_snake_case)] #[derive( @@ -2319,7 +6935,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for Int8MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/Int8MultiArray"; const MD5SUM: &'static str = "d7c1af35a1b4781bbe79e03dd94b7c13"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nint8[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +int8[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2339,7 +7017,14 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for MultiArrayDimension { const ROS_TYPE_NAME: &'static str = "std_msgs/MultiArrayDimension"; const MD5SUM: &'static str = "4cd0c83a8683deae40ecdac60e53bfa8"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nstring label # label of given dimension\nuint32 size # size of given dimension (in type units)\nuint32 stride # stride of given dimension" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2358,7 +7043,47 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for MultiArrayLayout { const ROS_TYPE_NAME: &'static str = "std_msgs/MultiArrayLayout"; const MD5SUM: &'static str = "0fed2a11c13e11c5571b4e2a995a91a3"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# The multiarray declares a generic multi-dimensional array of a\n# particular data type. Dimensions are ordered from outer most\n# to inner most.\n#\n# Accessors should ALWAYS be written in terms of dimension stride\n# and specified outer-most dimension first.\n#\n# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n#\n# A standard, 3-channel 640x480 image with interleaved color channels\n# would be specified as:\n#\n# dim[0].label = \"height\"\n# dim[0].size = 480\n# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n# dim[1].label = \"width\"\n# dim[1].size = 640\n# dim[1].stride = 3*640 = 1920\n# dim[2].label = \"channel\"\n# dim[2].size = 3\n# dim[2].stride = 3\n#\n# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\nMultiArrayDimension[] dim # Array of dimension properties\nuint32 data_offset # padding bytes at front of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2376,7 +7101,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for String { const ROS_TYPE_NAME: &'static str = "std_msgs/String"; const MD5SUM: &'static str = "992ce8a1687cec8c8bd883ec73ca41d1"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nstring data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string data"#; } #[allow(non_snake_case)] #[derive( @@ -2394,7 +7124,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt16 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt16"; const MD5SUM: &'static str = "1df79edf208b629fe6b81923a544552d"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nuint16 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +uint16 data"#; } #[allow(non_snake_case)] #[derive( @@ -2413,7 +7148,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt16MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt16MultiArray"; const MD5SUM: &'static str = "52f264f1c973c4b73790d384c6cb4484"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nuint16[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint16[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2431,7 +7228,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt32 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt32"; const MD5SUM: &'static str = "304a39449588c7f8ce2df6e8001c5fce"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nuint32 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +uint32 data"#; } #[allow(non_snake_case)] #[derive( @@ -2450,7 +7252,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt32MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt32MultiArray"; const MD5SUM: &'static str = "4d6a180abc9be191b96a7eda6c8a233d"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nuint32[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint32[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2468,7 +7332,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt64 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt64"; const MD5SUM: &'static str = "1b2a79973e8bf53d7b53acb71299cb57"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nuint64 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +uint64 data"#; } #[allow(non_snake_case)] #[derive( @@ -2487,7 +7356,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt64MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt64MultiArray"; const MD5SUM: &'static str = "6088f127afb1d6c72927aa1247e945af"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nuint64[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint64[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } #[allow(non_snake_case)] #[derive( @@ -2505,7 +7436,12 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt8 { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt8"; const MD5SUM: &'static str = "7c8164229e7d2c17eb95e9231617fdee"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\nuint8 data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +uint8 data"#; } #[allow(non_snake_case)] #[derive( @@ -2524,7 +7460,69 @@ pub mod std_msgs { impl ::roslibrust_codegen::RosMessageType for UInt8MultiArray { const ROS_TYPE_NAME: &'static str = "std_msgs/UInt8MultiArray"; const MD5SUM: &'static str = "82373f1612381bb6ee473b5cd6f5d89c"; - const DEFINITION : & 'static str = "# This was originally provided as an example message.\n# It is deprecated as of Foxy\n# It is recommended to create your own semantically meaningful message.\n# However if you would like to continue using this please use the equivalent in example_msgs.\n\n# Please look at the MultiArrayLayout message definition for\n# documentation on all multiarrays.\n\nMultiArrayLayout layout # specification of data layout\nuint8[] data # array of data" ; + const DEFINITION: &'static str = r#"# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# Please look at the MultiArrayLayout message definition for +# documentation on all multiarrays. + +MultiArrayLayout layout # specification of data layout +uint8[] data # array of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension +================================================================================ +MSG: std_msgs/MultiArrayLayout +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +# The multiarray declares a generic multi-dimensional array of a +# particular data type. Dimensions are ordered from outer most +# to inner most. +# +# Accessors should ALWAYS be written in terms of dimension stride +# and specified outer-most dimension first. +# +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] +# +# A standard, 3-channel 640x480 image with interleaved color channels +# would be specified as: +# +# dim[0].label = "height" +# dim[0].size = 480 +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) +# dim[1].label = "width" +# dim[1].size = 640 +# dim[1].stride = 3*640 = 1920 +# dim[2].label = "channel" +# dim[2].size = 3 +# dim[2].stride = 3 +# +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. + +MultiArrayDimension[] dim # Array of dimension properties +uint32 data_offset # padding bytes at front of data +================================================================================ +MSG: std_msgs/MultiArrayDimension +# This was originally provided as an example message. +# It is deprecated as of Foxy +# It is recommended to create your own semantically meaningful message. +# However if you would like to continue using this please use the equivalent in example_msgs. + +string label # label of given dimension +uint32 size # size of given dimension (in type units) +uint32 stride # stride of given dimension"#; } } #[allow(unused_imports)] @@ -2554,7 +7552,7 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for EmptyRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/EmptyRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -2570,7 +7568,7 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for EmptyResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/EmptyResponse"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } pub struct Empty {} impl ::roslibrust_codegen::RosServiceType for Empty { @@ -2595,7 +7593,7 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for SetBoolRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/SetBoolRequest"; const MD5SUM: &'static str = "8b94c1b53db61fb6aed406028ad6332a"; - const DEFINITION: &'static str = "bool data # e.g. for hardware enabling / disabling"; + const DEFINITION: &'static str = r#"bool data # e.g. for hardware enabling / disabling"#; } #[allow(non_snake_case)] #[derive( @@ -2614,7 +7612,8 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for SetBoolResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/SetBoolResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; - const DEFINITION : & 'static str = "bool success # indicate successful run of triggered service\nstring message # informational, e.g. for error messages" ; + const DEFINITION: &'static str = r#"bool success # indicate successful run of triggered service +string message # informational, e.g. for error messages"#; } pub struct SetBool {} impl ::roslibrust_codegen::RosServiceType for SetBool { @@ -2637,7 +7636,7 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for TriggerRequest { const ROS_TYPE_NAME: &'static str = "std_srvs/TriggerRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -2656,7 +7655,8 @@ pub mod std_srvs { impl ::roslibrust_codegen::RosMessageType for TriggerResponse { const ROS_TYPE_NAME: &'static str = "std_srvs/TriggerResponse"; const MD5SUM: &'static str = "937c9679a518e3a18d831e57125ea522"; - const DEFINITION : & 'static str = "bool success # indicate successful run of triggered service\nstring message # informational, e.g. for error messages" ; + const DEFINITION: &'static str = r#"bool success # indicate successful run of triggered service +string message # informational, e.g. for error messages"#; } pub struct Trigger {} impl ::roslibrust_codegen::RosServiceType for Trigger { @@ -2702,7 +7702,106 @@ pub mod stereo_msgs { impl ::roslibrust_codegen::RosMessageType for DisparityImage { const ROS_TYPE_NAME: &'static str = "stereo_msgs/DisparityImage"; const MD5SUM: &'static str = "cb0de8feef04280238c7b77d74b2beca"; - const DEFINITION : & 'static str = "# Separate header for compatibility with current TimeSynchronizer.\n# Likely to be removed in a later release, use image.header instead.\nstd_msgs/Header header\n\n# Floating point disparity image. The disparities are pre-adjusted for any\n# x-offset between the principal points of the two cameras (in the case\n# that they are verged). That is: d = x_l - x_r - (cx_l - cx_r)\nsensor_msgs/Image image\n\n# Stereo geometry. For disparity d, the depth from the camera is Z = fT/d.\nfloat32 f # Focal length, pixels\nfloat32 t # Baseline, world units\n\n# Subwindow of (potentially) valid disparity values.\nsensor_msgs/RegionOfInterest valid_window\n\n# The range of disparities searched.\n# In the disparity image, any disparity less than min_disparity is invalid.\n# The disparity search range defines the horopter, or 3D volume that the\n# stereo algorithm can \"see\". Points with Z outside of:\n# Z_min = fT / max_disparity\n# Z_max = fT / min_disparity\n# could not be found.\nfloat32 min_disparity\nfloat32 max_disparity\n\n# Smallest allowed disparity increment. The smallest achievable depth range\n# resolution is delta_Z = (Z^2/fT)*delta_d.\nfloat32 delta_d" ; + const DEFINITION: &'static str = r#"# Separate header for compatibility with current TimeSynchronizer. +# Likely to be removed in a later release, use image.header instead. +std_msgs/Header header + +# Floating point disparity image. The disparities are pre-adjusted for any +# x-offset between the principal points of the two cameras (in the case +# that they are verged). That is: d = x_l - x_r - (cx_l - cx_r) +sensor_msgs/Image image + +# Stereo geometry. For disparity d, the depth from the camera is Z = fT/d. +float32 f # Focal length, pixels +float32 t # Baseline, world units + +# Subwindow of (potentially) valid disparity values. +sensor_msgs/RegionOfInterest valid_window + +# The range of disparities searched. +# In the disparity image, any disparity less than min_disparity is invalid. +# The disparity search range defines the horopter, or 3D volume that the +# stereo algorithm can "see". Points with Z outside of: +# Z_min = fT / max_disparity +# Z_max = fT / min_disparity +# could not be found. +float32 min_disparity +float32 max_disparity + +# Smallest allowed disparity increment. The smallest achievable depth range +# resolution is delta_Z = (Z^2/fT)*delta_d. +float32 delta_d +================================================================================ +MSG: sensor_msgs/Image +# This message contains an uncompressed image +# (0, 0) is at top-left corner of image + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + # If the frame_id here and the frame_id of the CameraInfo + # message associated with the image conflict + # the behavior is undefined + +uint32 height # image height, that is, number of rows +uint32 width # image width, that is, number of columns + +# The legal values for encoding are in file include/sensor_msgs/image_encodings.hpp +# If you want to standardize a new string format, join +# ros-users@lists.ros.org and send an email proposing a new encoding. + +string encoding # Encoding of pixels -- channel meaning, ordering, size + # taken from the list of strings in include/sensor_msgs/image_encodings.hpp + +uint8 is_bigendian # is this data bigendian? +uint32 step # Full row length in bytes +uint8[] data # actual matrix data, size is (step * rows) +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: sensor_msgs/RegionOfInterest +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } } #[allow(unused_imports)] @@ -2745,7 +7844,22 @@ pub mod test_msgs { impl ::roslibrust_codegen::RosMessageType for Defaults { const ROS_TYPE_NAME: &'static str = "test_msgs/Defaults"; const MD5SUM: &'static str = "43c441dc2b521c313f54affd982b5314"; - const DEFINITION : & 'static str = "# This message is specifically for testing generating of default values\n# Examples based on https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html\nuint8 x 42\nint16 y -2000\nstring full_name \"John Doe\"\nint32[] samples [-200, -100, 0, 100, 200]\n\n# More complicated examples to stress the system, floats with mixed precision\nfloat32[] f_samples [-200, -1.0, 0]\nstring[] s_vec [\"hello\", \"world\"]\n# This may or may not be valid ROS, it probably is, but we don't handle yet\n# TODO handle this somehow\n# string[] s_vec_2 ['hello', 'world']\n\n# TODO ROS says this is valid, but we currently don't handle\n#string single_quote 'Jane Doe'" ; + const DEFINITION: &'static str = r#"# This message is specifically for testing generating of default values +# Examples based on https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html +uint8 x 42 +int16 y -2000 +string full_name "John Doe" +int32[] samples [-200, -100, 0, 100, 200] + +# More complicated examples to stress the system, floats with mixed precision +float32[] f_samples [-200, -1.0, 0] +string[] s_vec ["hello", "world"] +# This may or may not be valid ROS, it probably is, but we don't handle yet +# TODO handle this somehow +# string[] s_vec_2 ['hello', 'world'] + +# TODO ROS says this is valid, but we currently don't handle +#string single_quote 'Jane Doe'"#; } } #[allow(unused_imports)] @@ -2779,7 +7893,56 @@ pub mod trajectory_msgs { impl ::roslibrust_codegen::RosMessageType for JointTrajectory { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/JointTrajectory"; const MD5SUM: &'static str = "d63e3b4556d9dbd9f48b5ab4a03f1fee"; - const DEFINITION : & 'static str = "# The header is used to specify the coordinate frame and the reference time for\n# the trajectory durations\nstd_msgs/Header header\n\n# The names of the active joints in each trajectory point. These names are\n# ordered and must correspond to the values in each trajectory point.\nstring[] joint_names\n\n# Array of trajectory points, which describe the positions, velocities,\n# accelerations and/or efforts of the joints at each time point.\nJointTrajectoryPoint[] points" ; + const DEFINITION: &'static str = r#"# The header is used to specify the coordinate frame and the reference time for +# the trajectory durations +std_msgs/Header header + +# The names of the active joints in each trajectory point. These names are +# ordered and must correspond to the values in each trajectory point. +string[] joint_names + +# Array of trajectory points, which describe the positions, velocities, +# accelerations and/or efforts of the joints at each time point. +JointTrajectoryPoint[] points +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: trajectory_msgs/JointTrajectoryPoint +# Each trajectory point specifies either positions[, velocities[, accelerations]] +# or positions[, effort] for the trajectory to be executed. +# All specified values are in the same order as the joint names in JointTrajectory.msg. + +# Single DOF joint positions for each joint relative to their "0" position. +# The units depend on the specific joint type: radians for revolute or +# continuous joints, and meters for prismatic joints. +float64[] positions + +# The rate of change in position of each joint. Units are joint type dependent. +# Radians/second for revolute or continuous joints, and meters/second for +# prismatic joints. +float64[] velocities + +# Rate of change in velocity of each joint. Units are joint type dependent. +# Radians/second^2 for revolute or continuous joints, and meters/second^2 for +# prismatic joints. +float64[] accelerations + +# The torque or the force to be applied at each joint. For revolute/continuous +# joints effort denotes a torque in newton-meters. For prismatic joints, effort +# denotes a force in newtons. +float64[] effort + +# Desired time from the trajectory start to arrive at this trajectory point. +builtin_interfaces/Duration time_from_start"#; } #[allow(non_snake_case)] #[derive( @@ -2801,7 +7964,32 @@ pub mod trajectory_msgs { impl ::roslibrust_codegen::RosMessageType for JointTrajectoryPoint { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/JointTrajectoryPoint"; const MD5SUM: &'static str = "2c812f86aa886c93954e333721749ac5"; - const DEFINITION : & 'static str = "# Each trajectory point specifies either positions[, velocities[, accelerations]]\n# or positions[, effort] for the trajectory to be executed.\n# All specified values are in the same order as the joint names in JointTrajectory.msg.\n\n# Single DOF joint positions for each joint relative to their \"0\" position.\n# The units depend on the specific joint type: radians for revolute or\n# continuous joints, and meters for prismatic joints.\nfloat64[] positions\n\n# The rate of change in position of each joint. Units are joint type dependent.\n# Radians/second for revolute or continuous joints, and meters/second for\n# prismatic joints.\nfloat64[] velocities\n\n# Rate of change in velocity of each joint. Units are joint type dependent.\n# Radians/second^2 for revolute or continuous joints, and meters/second^2 for\n# prismatic joints.\nfloat64[] accelerations\n\n# The torque or the force to be applied at each joint. For revolute/continuous\n# joints effort denotes a torque in newton-meters. For prismatic joints, effort\n# denotes a force in newtons.\nfloat64[] effort\n\n# Desired time from the trajectory start to arrive at this trajectory point.\nbuiltin_interfaces/Duration time_from_start" ; + const DEFINITION: &'static str = r#"# Each trajectory point specifies either positions[, velocities[, accelerations]] +# or positions[, effort] for the trajectory to be executed. +# All specified values are in the same order as the joint names in JointTrajectory.msg. + +# Single DOF joint positions for each joint relative to their "0" position. +# The units depend on the specific joint type: radians for revolute or +# continuous joints, and meters for prismatic joints. +float64[] positions + +# The rate of change in position of each joint. Units are joint type dependent. +# Radians/second for revolute or continuous joints, and meters/second for +# prismatic joints. +float64[] velocities + +# Rate of change in velocity of each joint. Units are joint type dependent. +# Radians/second^2 for revolute or continuous joints, and meters/second^2 for +# prismatic joints. +float64[] accelerations + +# The torque or the force to be applied at each joint. For revolute/continuous +# joints effort denotes a torque in newton-meters. For prismatic joints, effort +# denotes a force in newtons. +float64[] effort + +# Desired time from the trajectory start to arrive at this trajectory point. +builtin_interfaces/Duration time_from_start"#; } #[allow(non_snake_case)] #[derive( @@ -2821,7 +8009,162 @@ pub mod trajectory_msgs { impl ::roslibrust_codegen::RosMessageType for MultiDOFJointTrajectory { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/MultiDOFJointTrajectory"; const MD5SUM: &'static str = "d00d14d97bd70c5eb648278240cfb066"; - const DEFINITION : & 'static str = "# The header is used to specify the coordinate frame and the reference time for the trajectory durations\nstd_msgs/Header header\n\n# A representation of a multi-dof joint trajectory (each point is a transformation)\n# Each point along the trajectory will include an array of positions/velocities/accelerations\n# that has the same length as the array of joint names, and has the same order of joints as \n# the joint names array.\n\nstring[] joint_names\nMultiDOFJointTrajectoryPoint[] points" ; + const DEFINITION: &'static str = r#"# The header is used to specify the coordinate frame and the reference time for the trajectory durations +std_msgs/Header header + +# A representation of a multi-dof joint trajectory (each point is a transformation) +# Each point along the trajectory will include an array of positions/velocities/accelerations +# that has the same length as the array of joint names, and has the same order of joints as +# the joint names array. + +string[] joint_names +MultiDOFJointTrajectoryPoint[] points +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: trajectory_msgs/MultiDOFJointTrajectoryPoint +# Each multi-dof joint can specify a transform (up to 6 DOF). +geometry_msgs/Transform[] transforms + +# There can be a velocity specified for the origin of the joint. +geometry_msgs/Twist[] velocities + +# There can be an acceleration specified for the origin of the joint. +geometry_msgs/Twist[] accelerations + +# Desired time from the trajectory start to arrive at this trajectory point. +builtin_interfaces/Duration time_from_start +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } #[allow(non_snake_case)] #[derive( @@ -2842,7 +8185,78 @@ pub mod trajectory_msgs { impl ::roslibrust_codegen::RosMessageType for MultiDOFJointTrajectoryPoint { const ROS_TYPE_NAME: &'static str = "trajectory_msgs/MultiDOFJointTrajectoryPoint"; const MD5SUM: &'static str = "6731945e53cbc0fbc6e93c28f7416a71"; - const DEFINITION : & 'static str = "# Each multi-dof joint can specify a transform (up to 6 DOF).\ngeometry_msgs/Transform[] transforms\n\n# There can be a velocity specified for the origin of the joint.\ngeometry_msgs/Twist[] velocities\n\n# There can be an acceleration specified for the origin of the joint.\ngeometry_msgs/Twist[] accelerations\n\n# Desired time from the trajectory start to arrive at this trajectory point.\nbuiltin_interfaces/Duration time_from_start" ; + const DEFINITION: &'static str = r#"# Each multi-dof joint can specify a transform (up to 6 DOF). +geometry_msgs/Transform[] transforms + +# There can be a velocity specified for the origin of the joint. +geometry_msgs/Twist[] velocities + +# There can be an acceleration specified for the origin of the joint. +geometry_msgs/Twist[] accelerations + +# Desired time from the trajectory start to arrive at this trajectory point. +builtin_interfaces/Duration time_from_start +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Transform +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Twist +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z"#; } } #[allow(unused_imports)] @@ -2886,7 +8300,65 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for ImageMarker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/ImageMarker"; const MD5SUM: &'static str = "829dd5d9ba39b8c3844252ebd8b47b96"; - const DEFINITION : & 'static str = "int32 CIRCLE=0\nint32 LINE_STRIP=1\nint32 LINE_LIST=2\nint32 POLYGON=3\nint32 POINTS=4\n\nint32 ADD=0\nint32 REMOVE=1\n\nstd_msgs/Header header\n# Namespace which is used with the id to form a unique id.\nstring ns\n# Unique id within the namespace.\nint32 id\n# One of the above types, e.g. CIRCLE, LINE_STRIP, etc.\nint32 type\n# Either ADD or REMOVE.\nint32 action\n# Two-dimensional coordinate position, in pixel-coordinates.\ngeometry_msgs/Point position\n# The scale of the object, e.g. the diameter for a CIRCLE.\nfloat32 scale\n# The outline color of the marker.\nstd_msgs/ColorRGBA outline_color\n# Whether or not to fill in the shape with color.\nuint8 filled\n# Fill color; in the range: [0.0-1.0]\nstd_msgs/ColorRGBA fill_color\n# How long the object should last before being automatically deleted.\n# 0 indicates forever.\nbuiltin_interfaces/Duration lifetime\n\n# Coordinates in 2D in pixel coords. Used for LINE_STRIP, LINE_LIST, POINTS, etc.\ngeometry_msgs/Point[] points\n# The color for each line, point, etc. in the points field.\nstd_msgs/ColorRGBA[] outline_colors" ; + const DEFINITION: &'static str = r#"int32 CIRCLE=0 +int32 LINE_STRIP=1 +int32 LINE_LIST=2 +int32 POLYGON=3 +int32 POINTS=4 + +int32 ADD=0 +int32 REMOVE=1 + +std_msgs/Header header +# Namespace which is used with the id to form a unique id. +string ns +# Unique id within the namespace. +int32 id +# One of the above types, e.g. CIRCLE, LINE_STRIP, etc. +int32 type +# Either ADD or REMOVE. +int32 action +# Two-dimensional coordinate position, in pixel-coordinates. +geometry_msgs/Point position +# The scale of the object, e.g. the diameter for a CIRCLE. +float32 scale +# The outline color of the marker. +std_msgs/ColorRGBA outline_color +# Whether or not to fill in the shape with color. +uint8 filled +# Fill color; in the range: [0.0-1.0] +std_msgs/ColorRGBA fill_color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime + +# Coordinates in 2D in pixel coords. Used for LINE_STRIP, LINE_LIST, POINTS, etc. +geometry_msgs/Point[] points +# The color for each line, point, etc. in the points field. +std_msgs/ColorRGBA[] outline_colors +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } impl ImageMarker { pub const r#CIRCLE: i32 = 0i32; @@ -2919,7 +8391,751 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarker"; const MD5SUM: &'static str = "d71737fa44c5bdefd6bdb4fa9b2b86e5"; - const DEFINITION : & 'static str = "# Time/frame info.\n# If header.time is set to 0, the marker will be retransformed into\n# its frame on each timestep. You will receive the pose feedback\n# in the same frame.\n# Otherwise, you might receive feedback in a different frame.\n# For rviz, this will be the current 'fixed frame' set by the user.\nstd_msgs/Header header\n\n# Initial pose. Also, defines the pivot point for rotations.\ngeometry_msgs/Pose pose\n\n# Identifying string. Must be globally unique in\n# the topic that this message is sent through.\nstring name\n\n# Short description (< 40 characters).\nstring description\n\n# Scale to be used for default controls (default=1).\nfloat32 scale\n\n# All menu and submenu entries associated with this marker.\nMenuEntry[] menu_entries\n\n# List of controls displayed for this marker.\nInteractiveMarkerControl[] controls" ; + const DEFINITION: &'static str = r#"# Time/frame info. +# If header.time is set to 0, the marker will be retransformed into +# its frame on each timestep. You will receive the pose feedback +# in the same frame. +# Otherwise, you might receive feedback in a different frame. +# For rviz, this will be the current 'fixed frame' set by the user. +std_msgs/Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name + +# Short description (< 40 characters). +string description + +# Scale to be used for default controls (default=1). +float32 scale + +# All menu and submenu entries associated with this marker. +MenuEntry[] menu_entries + +# List of controls displayed for this marker. +InteractiveMarkerControl[] controls +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v"#; } #[allow(non_snake_case)] #[derive( @@ -2944,7 +9160,375 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerControl { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerControl"; const MD5SUM: &'static str = "7b945e790a2d68f430a6eb79f33bf8df"; - const DEFINITION : & 'static str = "# Represents a control that is to be displayed together with an interactive marker\n\n# Identifying string for this control.\n# You need to assign a unique value to this to receive feedback from the GUI\n# on what actions the user performs on this control (e.g. a button click).\nstring name\n\n\n# Defines the local coordinate frame (relative to the pose of the parent\n# interactive marker) in which is being rotated and translated.\n# Default: Identity\ngeometry_msgs/Quaternion orientation\n\n\n# Orientation mode: controls how orientation changes.\n# INHERIT: Follow orientation of interactive marker\n# FIXED: Keep orientation fixed at initial state\n# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up).\nuint8 INHERIT = 0\nuint8 FIXED = 1\nuint8 VIEW_FACING = 2\n\nuint8 orientation_mode\n\n# Interaction mode for this control\n#\n# NONE: This control is only meant for visualization; no context menu.\n# MENU: Like NONE, but right-click menu is active.\n# BUTTON: Element can be left-clicked.\n# MOVE_AXIS: Translate along local x-axis.\n# MOVE_PLANE: Translate in local y-z plane.\n# ROTATE_AXIS: Rotate around local x-axis.\n# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS.\nuint8 NONE = 0\nuint8 MENU = 1\nuint8 BUTTON = 2\nuint8 MOVE_AXIS = 3\nuint8 MOVE_PLANE = 4\nuint8 ROTATE_AXIS = 5\nuint8 MOVE_ROTATE = 6\n# \"3D\" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors.\n# MOVE_3D: Translate freely in 3D space.\n# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame.\n# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin.\nuint8 MOVE_3D = 7\nuint8 ROTATE_3D = 8\nuint8 MOVE_ROTATE_3D = 9\n\nuint8 interaction_mode\n\n\n# If true, the contained markers will also be visible\n# when the gui is not in interactive mode.\nbool always_visible\n\n\n# Markers to be displayed as custom visual representation.\n# Leave this empty to use the default control handles.\n#\n# Note:\n# - The markers can be defined in an arbitrary coordinate frame,\n# but will be transformed into the local frame of the interactive marker.\n# - If the header of a marker is empty, its pose will be interpreted as\n# relative to the pose of the parent interactive marker.\nMarker[] markers\n\n\n# In VIEW_FACING mode, set this to true if you don't want the markers\n# to be aligned with the camera view point. The markers will show up\n# as in INHERIT mode.\nbool independent_marker_orientation\n\n\n# Short description (< 40 characters) of what this control does,\n# e.g. \"Move the robot\".\n# Default: A generic description based on the interaction mode\nstring description" ; + const DEFINITION: &'static str = r#"# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v"#; } impl InteractiveMarkerControl { pub const r#INHERIT: u8 = 0u8; @@ -2985,7 +9569,93 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerFeedback { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerFeedback"; const MD5SUM: &'static str = "880e5141421ed8d30906fad686bc17bd"; - const DEFINITION : & 'static str = "# Time/frame info.\nstd_msgs/Header header\n\n# Identifying string. Must be unique in the topic namespace.\nstring client_id\n\n# Feedback message sent back from the GUI, e.g.\n# when the status of an interactive marker was modified by the user.\n\n# Specifies which interactive marker and control this message refers to\nstring marker_name\nstring control_name\n\n# Type of the event\n# KEEP_ALIVE: sent while dragging to keep up control of the marker\n# MENU_SELECT: a menu entry has been selected\n# BUTTON_CLICK: a button control has been clicked\n# POSE_UPDATE: the pose has been changed using one of the controls\nuint8 KEEP_ALIVE = 0\nuint8 POSE_UPDATE = 1\nuint8 MENU_SELECT = 2\nuint8 BUTTON_CLICK = 3\n\nuint8 MOUSE_DOWN = 4\nuint8 MOUSE_UP = 5\n\nuint8 event_type\n\n# Current pose of the marker\n# Note: Has to be valid for all feedback types.\ngeometry_msgs/Pose pose\n\n# Contains the ID of the selected menu entry\n# Only valid for MENU_SELECT events.\nuint32 menu_entry_id\n\n# If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point\n# may contain the 3 dimensional position of the event on the\n# control. If it does, mouse_point_valid will be true. mouse_point\n# will be relative to the frame listed in the header.\ngeometry_msgs/Point mouse_point\nbool mouse_point_valid" ; + const DEFINITION: &'static str = r#"# Time/frame info. +std_msgs/Header header + +# Identifying string. Must be unique in the topic namespace. +string client_id + +# Feedback message sent back from the GUI, e.g. +# when the status of an interactive marker was modified by the user. + +# Specifies which interactive marker and control this message refers to +string marker_name +string control_name + +# Type of the event +# KEEP_ALIVE: sent while dragging to keep up control of the marker +# MENU_SELECT: a menu entry has been selected +# BUTTON_CLICK: a button control has been clicked +# POSE_UPDATE: the pose has been changed using one of the controls +uint8 KEEP_ALIVE = 0 +uint8 POSE_UPDATE = 1 +uint8 MENU_SELECT = 2 +uint8 BUTTON_CLICK = 3 + +uint8 MOUSE_DOWN = 4 +uint8 MOUSE_UP = 5 + +uint8 event_type + +# Current pose of the marker +# Note: Has to be valid for all feedback types. +geometry_msgs/Pose pose + +# Contains the ID of the selected menu entry +# Only valid for MENU_SELECT events. +uint32 menu_entry_id + +# If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point +# may contain the 3 dimensional position of the event on the +# control. If it does, mouse_point_valid will be true. mouse_point +# will be relative to the frame listed in the header. +geometry_msgs/Point mouse_point +bool mouse_point_valid +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } impl InteractiveMarkerFeedback { pub const r#KEEP_ALIVE: u8 = 0u8; @@ -3013,7 +9683,1486 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerInit { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerInit"; const MD5SUM: &'static str = "5d275694a5cb7ea4627f917a9eb1b4cd"; - const DEFINITION : & 'static str = "# Identifying string. Must be unique in the topic namespace\n# that this server works on.\nstring server_id\n\n# Sequence number.\n# The client will use this to detect if it has missed a subsequent\n# update. Every update message will have the same sequence number as\n# an init message. Clients will likely want to unsubscribe from the\n# init topic after a successful initialization to avoid receiving\n# duplicate data.\nuint64 seq_num\n\n# All markers.\nInteractiveMarker[] markers" ; + const DEFINITION: &'static str = r#"# Identifying string. Must be unique in the topic namespace +# that this server works on. +string server_id + +# Sequence number. +# The client will use this to detect if it has missed a subsequent +# update. Every update message will have the same sequence number as +# an init message. Clients will likely want to unsubscribe from the +# init topic after a successful initialization to avoid receiving +# duplicate data. +uint64 seq_num + +# All markers. +InteractiveMarker[] markers +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarker +# Time/frame info. +# If header.time is set to 0, the marker will be retransformed into +# its frame on each timestep. You will receive the pose feedback +# in the same frame. +# Otherwise, you might receive feedback in a different frame. +# For rviz, this will be the current 'fixed frame' set by the user. +std_msgs/Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name + +# Short description (< 40 characters). +string description + +# Scale to be used for default controls (default=1). +float32 scale + +# All menu and submenu entries associated with this marker. +MenuEntry[] menu_entries + +# List of controls displayed for this marker. +InteractiveMarkerControl[] controls +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v"#; } #[allow(non_snake_case)] #[derive( @@ -3033,7 +11182,60 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerPose { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerPose"; const MD5SUM: &'static str = "b88540594a0f8e3fe46c720be41faa03"; - const DEFINITION : & 'static str = "# Time/frame info.\nstd_msgs/Header header\n\n# Initial pose. Also, defines the pivot point for rotations.\ngeometry_msgs/Pose pose\n\n# Identifying string. Must be globally unique in\n# the topic that this message is sent through.\nstring name" ; + const DEFINITION: &'static str = r#"# Time/frame info. +std_msgs/Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id"#; } #[allow(non_snake_case)] #[derive( @@ -3056,7 +11258,1559 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for InteractiveMarkerUpdate { const ROS_TYPE_NAME: &'static str = "visualization_msgs/InteractiveMarkerUpdate"; const MD5SUM: &'static str = "8f52c675c849441ae87da82eaa4d6eb5"; - const DEFINITION : & 'static str = "# Identifying string. Must be unique in the topic namespace\n# that this server works on.\nstring server_id\n\n# Sequence number.\n# The client will use this to detect if it has missed an update.\nuint64 seq_num\n\n# Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE.\n# UPDATE: Incremental update to previous state.\n# The sequence number must be 1 higher than for\n# the previous update.\n# KEEP_ALIVE: Indicates the that the server is still living.\n# The sequence number does not increase.\n# No payload data should be filled out (markers, poses, or erases).\nuint8 KEEP_ALIVE = 0\nuint8 UPDATE = 1\n\nuint8 type\n\n# Note: No guarantees on the order of processing.\n# Contents must be kept consistent by sender.\n\n# Markers to be added or updated\nInteractiveMarker[] markers\n\n# Poses of markers that should be moved\nInteractiveMarkerPose[] poses\n\n# Names of markers to be erased\nstring[] erases" ; + const DEFINITION: &'static str = r#"# Identifying string. Must be unique in the topic namespace +# that this server works on. +string server_id + +# Sequence number. +# The client will use this to detect if it has missed an update. +uint64 seq_num + +# Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE. +# UPDATE: Incremental update to previous state. +# The sequence number must be 1 higher than for +# the previous update. +# KEEP_ALIVE: Indicates the that the server is still living. +# The sequence number does not increase. +# No payload data should be filled out (markers, poses, or erases). +uint8 KEEP_ALIVE = 0 +uint8 UPDATE = 1 + +uint8 type + +# Note: No guarantees on the order of processing. +# Contents must be kept consistent by sender. + +# Markers to be added or updated +InteractiveMarker[] markers + +# Poses of markers that should be moved +InteractiveMarkerPose[] poses + +# Names of markers to be erased +string[] erases +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarker +# Time/frame info. +# If header.time is set to 0, the marker will be retransformed into +# its frame on each timestep. You will receive the pose feedback +# in the same frame. +# Otherwise, you might receive feedback in a different frame. +# For rviz, this will be the current 'fixed frame' set by the user. +std_msgs/Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name + +# Short description (< 40 characters). +string description + +# Scale to be used for default controls (default=1). +float32 scale + +# All menu and submenu entries associated with this marker. +MenuEntry[] menu_entries + +# List of controls displayed for this marker. +InteractiveMarkerControl[] controls +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/InteractiveMarkerPose +# Time/frame info. +std_msgs/Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v"#; } impl InteractiveMarkerUpdate { pub const r#KEEP_ALIVE: u8 = 0u8; @@ -3096,7 +12850,191 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for Marker { const ROS_TYPE_NAME: &'static str = "visualization_msgs/Marker"; const MD5SUM: &'static str = "56c6324983a404ead7a426609371feed"; - const DEFINITION : & 'static str = "# See:\n# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker\n# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes\n#\n# for more information on using this message with rviz.\n\nint32 ARROW=0\nint32 CUBE=1\nint32 SPHERE=2\nint32 CYLINDER=3\nint32 LINE_STRIP=4\nint32 LINE_LIST=5\nint32 CUBE_LIST=6\nint32 SPHERE_LIST=7\nint32 POINTS=8\nint32 TEXT_VIEW_FACING=9\nint32 MESH_RESOURCE=10\nint32 TRIANGLE_LIST=11\n\nint32 ADD=0\nint32 MODIFY=0\nint32 DELETE=2\nint32 DELETEALL=3\n\n# Header for timestamp and frame id.\nstd_msgs/Header header\n# Namespace in which to place the object.\n# Used in conjunction with id to create a unique name for the object.\nstring ns\n# Object ID used in conjunction with the namespace for manipulating and deleting the object later.\nint32 id\n# Type of object.\nint32 type\n# Action to take; one of:\n# - 0 add/modify an object\n# - 1 (deprecated)\n# - 2 deletes an object (with the given ns and id)\n# - 3 deletes all objects (or those with the given ns if any)\nint32 action\n# Pose of the object with respect the frame_id specified in the header.\ngeometry_msgs/Pose pose\n# Scale of the object; 1,1,1 means default (usually 1 meter square).\ngeometry_msgs/Vector3 scale\n# Color of the object; in the range: [0.0-1.0]\nstd_msgs/ColorRGBA color\n# How long the object should last before being automatically deleted.\n# 0 indicates forever.\nbuiltin_interfaces/Duration lifetime\n# If this marker should be frame-locked, i.e. retransformed into its frame every timestep.\nbool frame_locked\n\n# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.)\ngeometry_msgs/Point[] points\n# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.)\n# The number of colors provided must either be 0 or equal to the number of points provided.\n# NOTE: alpha is not yet used\nstd_msgs/ColorRGBA[] colors\n\n# Texture resource is a special URI that can either reference a texture file in\n# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/]\n# or an embedded texture via a string matching the format:\n# \"embedded://texture_name\"\nstring texture_resource\n# An image to be loaded into the rendering engine as the texture for this marker.\n# This will be used iff texture_resource is set to embedded.\nsensor_msgs/CompressedImage texture\n# Location of each vertex within the texture; in the range: [0.0-1.0]\nUVCoordinate[] uv_coordinates\n\n# Only used for text markers\nstring text\n\n# Only used for MESH_RESOURCE markers.\n# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh.\n# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so,\n# use the following format for mesh_resource:\n# \"embedded://mesh_name\"\nstring mesh_resource\nMeshFile mesh_file\nbool mesh_use_embedded_materials" ; + const DEFINITION: &'static str = r#"# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v"#; } impl Marker { pub const r#ARROW: i32 = 0i32; @@ -3132,7 +13070,299 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for MarkerArray { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MarkerArray"; const MD5SUM: &'static str = "11e38f15427197858cf46456867167bd"; - const DEFINITION: &'static str = "Marker[] markers"; + const DEFINITION: &'static str = r#"Marker[] markers +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v"#; } #[allow(non_snake_case)] #[derive( @@ -3154,7 +13384,60 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for MenuEntry { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MenuEntry"; const MD5SUM: &'static str = "b90ec63024573de83b57aa93eb39be2d"; - const DEFINITION : & 'static str = "# MenuEntry message.\n#\n# Each InteractiveMarker message has an array of MenuEntry messages.\n# A collection of MenuEntries together describe a\n# menu/submenu/subsubmenu/etc tree, though they are stored in a flat\n# array. The tree structure is represented by giving each menu entry\n# an ID number and a \"parent_id\" field. Top-level entries are the\n# ones with parent_id = 0. Menu entries are ordered within their\n# level the same way they are ordered in the containing array. Parent\n# entries must appear before their children.\n#\n# Example:\n# - id = 3\n# parent_id = 0\n# title = \"fun\"\n# - id = 2\n# parent_id = 0\n# title = \"robot\"\n# - id = 4\n# parent_id = 2\n# title = \"pr2\"\n# - id = 5\n# parent_id = 2\n# title = \"turtle\"\n#\n# Gives a menu tree like this:\n# - fun\n# - robot\n# - pr2\n# - turtle\n\n# ID is a number for each menu entry. Must be unique within the\n# control, and should never be 0.\nuint32 id\n\n# ID of the parent of this menu entry, if it is a submenu. If this\n# menu entry is a top-level entry, set parent_id to 0.\nuint32 parent_id\n\n# menu / entry title\nstring title\n\n# Arguments to command indicated by command_type (below)\nstring command\n\n# Command_type stores the type of response desired when this menu\n# entry is clicked.\n# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id.\n# ROSRUN: execute \"rosrun\" with arguments given in the command field (above).\n# ROSLAUNCH: execute \"roslaunch\" with arguments given in the command field (above).\nuint8 FEEDBACK=0\nuint8 ROSRUN=1\nuint8 ROSLAUNCH=2\nuint8 command_type" ; + const DEFINITION: &'static str = r#"# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type"#; } impl MenuEntry { pub const r#FEEDBACK: u8 = 0u8; @@ -3178,7 +13461,14 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for MeshFile { const ROS_TYPE_NAME: &'static str = "visualization_msgs/MeshFile"; const MD5SUM: &'static str = "39f264648e441626a1045a7d9ef1ba17"; - const DEFINITION : & 'static str = "# Used to send raw mesh files.\n\n# The filename is used for both debug purposes and to provide a file extension\n# for whatever parser is used.\nstring filename\n\n# This stores the raw text of the mesh file.\nuint8[] data" ; + const DEFINITION: &'static str = r#"# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data"#; } #[allow(non_snake_case)] #[derive( @@ -3197,7 +13487,10 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for UVCoordinate { const ROS_TYPE_NAME: &'static str = "visualization_msgs/UVCoordinate"; const MD5SUM: &'static str = "4f5254e0e12914c461d4b17a0cd07f7f"; - const DEFINITION : & 'static str = "# Location of the pixel as a ratio of the width of a 2D texture.\n# Values should be in range: [0.0-1.0].\nfloat32 u\nfloat32 v" ; + const DEFINITION: &'static str = r#"# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v"#; } #[allow(non_snake_case)] #[derive( @@ -3213,7 +13506,7 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for GetInteractiveMarkersRequest { const ROS_TYPE_NAME: &'static str = "visualization_msgs/GetInteractiveMarkersRequest"; const MD5SUM: &'static str = "d41d8cd98f00b204e9800998ecf8427e"; - const DEFINITION: &'static str = ""; + const DEFINITION: &'static str = r#""#; } #[allow(non_snake_case)] #[derive( @@ -3232,7 +13525,1480 @@ pub mod visualization_msgs { impl ::roslibrust_codegen::RosMessageType for GetInteractiveMarkersResponse { const ROS_TYPE_NAME: &'static str = "visualization_msgs/GetInteractiveMarkersResponse"; const MD5SUM: &'static str = "923b76ef2c497d4ff5f83a061d424d3b"; - const DEFINITION : & 'static str = "# Sequence number.\n# Set to the sequence number of the latest update message\n# at the time the server received the request.\n# Clients use this to detect if any updates were missed.\nuint64 sequence_number\n\n# All interactive markers provided by the server.\nInteractiveMarker[] markers" ; + const DEFINITION: &'static str = r#"# Sequence number. +# Set to the sequence number of the latest update message +# at the time the server received the request. +# Clients use this to detect if any updates were missed. +uint64 sequence_number + +# All interactive markers provided by the server. +InteractiveMarker[] markers +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarker +# Time/frame info. +# If header.time is set to 0, the marker will be retransformed into +# its frame on each timestep. You will receive the pose feedback +# in the same frame. +# Otherwise, you might receive feedback in a different frame. +# For rviz, this will be the current 'fixed frame' set by the user. +std_msgs/Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name + +# Short description (< 40 characters). +string description + +# Scale to be used for default controls (default=1). +float32 scale + +# All menu and submenu entries associated with this marker. +MenuEntry[] menu_entries + +# List of controls displayed for this marker. +InteractiveMarkerControl[] controls +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/InteractiveMarkerControl +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/Marker +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Pose +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation +================================================================================ +MSG: geometry_msgs/Point +# This contains the position of a point in free space +float64 x +float64 y +float64 z +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Quaternion +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 +================================================================================ +MSG: geometry_msgs/Vector3 +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z +================================================================================ +MSG: sensor_msgs/CompressedImage +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: std_msgs/ColorRGBA +float32 r +float32 g +float32 b +float32 a +================================================================================ +MSG: std_msgs/Header +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v +================================================================================ +MSG: visualization_msgs/MenuEntry +# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type +================================================================================ +MSG: visualization_msgs/MeshFile +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data +================================================================================ +MSG: visualization_msgs/UVCoordinate +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v"#; } pub struct GetInteractiveMarkers {} impl ::roslibrust_codegen::RosServiceType for GetInteractiveMarkers { diff --git a/roslibrust_test/tests/ros1_codegen_tests.rs b/roslibrust_test/tests/ros1_codegen_tests.rs index 2417fe18..c1bbbdaa 100644 --- a/roslibrust_test/tests/ros1_codegen_tests.rs +++ b/roslibrust_test/tests/ros1_codegen_tests.rs @@ -38,3 +38,13 @@ fn fixed_sized_arrays() { let x: geometry_msgs::TwistWithCovariance = Default::default(); let _y: [f64; 36] = x.covariance; } + +#[test] +fn test_gendeps_in_message_definition() { + // ROS1 requires that the message_definition includes the expanded + // definitions of all referenced sub-messages. + // See https://wiki.ros.org/roslib/gentools for example of expected format + // Confirm here that sub messages are included in the message definition for geometry_msgs::PointStamped + assert!(geometry_msgs::PointStamped::DEFINITION.contains("MSG: geometry_msgs/Point")); + assert!(geometry_msgs::PointStamped::DEFINITION.contains("MSG: std_msgs/Header")); +}