diff --git a/Cargo.toml b/Cargo.toml index 3e2ded3..13b53de 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -5,5 +5,6 @@ members = [ "roslibrust_codegen", "roslibrust_codegen_macro", "roslibrust_genmsg", - "roslibrust_test" -] \ No newline at end of file + "roslibrust_test", +] +resolver = "2" diff --git a/roslibrust_codegen/src/lib.rs b/roslibrust_codegen/src/lib.rs index 2946978..f657ec8 100644 --- a/roslibrust_codegen/src/lib.rs +++ b/roslibrust_codegen/src/lib.rs @@ -96,6 +96,10 @@ impl MessageFile { self.is_fixed_length } + pub fn get_definition(&self) -> &str { + &self.parsed.source + } + fn compute_md5sum( parsed: &ParsedMessageFile, graph: &BTreeMap, diff --git a/roslibrust_genmsg/assets/msg.h.j2 b/roslibrust_genmsg/assets/msg.h.j2 index 0627c32..06ec3cc 100644 --- a/roslibrust_genmsg/assets/msg.h.j2 +++ b/roslibrust_genmsg/assets/msg.h.j2 @@ -224,7 +224,7 @@ struct Definition< ::{{ spec.package }}::{{ spec.short_name }}_&) { return value(); } diff --git a/roslibrust_genmsg/src/spec.rs b/roslibrust_genmsg/src/spec.rs index 97538e4..c81af4f 100644 --- a/roslibrust_genmsg/src/spec.rs +++ b/roslibrust_genmsg/src/spec.rs @@ -97,7 +97,10 @@ impl From<&MessageFile> for MessageSpecification { constants: value.get_constants().iter().map(Constant::from).collect(), md5sum_first: String::from(&md5sum[..md5sum.len() / 2]), md5sum_second: String::from(&md5sum[(md5sum.len() / 2)..]), - description: String::from("Not a real description"), + description: value + .get_definition() + .replace('"', "\\\"") + .replace('\n', "\"\n\""), is_fixed_length: value.is_fixed_length(), }; spec.fields.iter_mut().for_each(|field| { diff --git a/roslibrust_genmsg/test_package/include/geometry_msgs/Point32.h b/roslibrust_genmsg/test_package/include/geometry_msgs/Point32.h index 719ad5b..3ce00c6 100644 --- a/roslibrust_genmsg/test_package/include/geometry_msgs/Point32.h +++ b/roslibrust_genmsg/test_package/include/geometry_msgs/Point32.h @@ -142,7 +142,17 @@ struct Definition< ::geometry_msgs::Point32_> { static constexpr char const* value() { - return ""; + return "# 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::Point32_&) { return value(); } diff --git a/roslibrust_genmsg/test_package/include/geometry_msgs/Polygon.h b/roslibrust_genmsg/test_package/include/geometry_msgs/Polygon.h index 8b7619f..a6352ea 100644 --- a/roslibrust_genmsg/test_package/include/geometry_msgs/Polygon.h +++ b/roslibrust_genmsg/test_package/include/geometry_msgs/Polygon.h @@ -131,7 +131,9 @@ struct Definition< ::geometry_msgs::Polygon_> { static constexpr char const* value() { - return ""; + return "#A specification of a polygon where the first and last points are assumed to be connected" +"Point32[] points" +""; } 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 06893dc..34bfac3 100644 --- a/roslibrust_genmsg/test_package/include/sensor_msgs/BatteryState.h +++ b/roslibrust_genmsg/test_package/include/sensor_msgs/BatteryState.h @@ -244,7 +244,59 @@ struct Definition< ::sensor_msgs::BatteryState_> { static constexpr char const* value() { - return ""; + 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." +"" +"# 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" +""; } 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 74f5cd3..fbd40fe 100644 --- a/roslibrust_genmsg/test_package/include/sensor_msgs/CameraInfo.h +++ b/roslibrust_genmsg/test_package/include/sensor_msgs/CameraInfo.h @@ -192,7 +192,138 @@ struct Definition< ::sensor_msgs::CameraInfo_> { static constexpr char const* value() { - return ""; + return "# 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" +""; } static const char* value(const ::sensor_msgs::CameraInfo_&) { return value(); } diff --git a/roslibrust_genmsg/test_package/include/std_msgs/Char.h b/roslibrust_genmsg/test_package/include/std_msgs/Char.h index 27a8070..0c94128 100644 --- a/roslibrust_genmsg/test_package/include/std_msgs/Char.h +++ b/roslibrust_genmsg/test_package/include/std_msgs/Char.h @@ -130,7 +130,7 @@ struct Definition< ::std_msgs::Char_> { static constexpr char const* value() { - return ""; + return "char data"; } static const char* value(const ::std_msgs::Char_&) { 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 2bfb8c1..eeda03b 100644 --- a/roslibrust_genmsg/test_package/include/std_msgs/Header.h +++ b/roslibrust_genmsg/test_package/include/std_msgs/Header.h @@ -142,7 +142,20 @@ struct Definition< ::std_msgs::Header_> { static constexpr char const* value() { - return ""; + return "# 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 ::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 7c379be..f77af60 100644 --- a/roslibrust_genmsg/test_package/include/std_srvs/TriggerResponse.h +++ b/roslibrust_genmsg/test_package/include/std_srvs/TriggerResponse.h @@ -136,7 +136,9 @@ struct Definition< ::std_srvs::TriggerResponse_> { static constexpr char const* value() { - return ""; + return "bool success # indicate successful run of triggered service" +"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 63a4fd7..ba3d3ef 100644 --- a/roslibrust_genmsg/test_package/include/test_package/Test.h +++ b/roslibrust_genmsg/test_package/include/test_package/Test.h @@ -156,7 +156,13 @@ struct Definition< ::test_package::Test_> { static constexpr char const* value() { - return ""; + return "geometry_msgs/Point32[] points" +"" +"string RUNNING_STATE = \"RUNNING\"" +"string STOPPED_STATE = \"STOPPED\"" +"" +"string test_a" +"Header header"; } static const char* value(const ::test_package::Test_&) { return value(); }