[Documentation] [TitleIndex] [WordIndex

Summary

In preparation for releasing common_msgs as a ROS Stack, we have been making a number of changes to the Message types that reflect the lessons learned through our experimentation with these data structures. Our goal for this release is to make a long-term commitment to these Message types. Although this release represents a large number of changes, future releases will not have these destabilizing changes.

The changes have been summarized below. These changes have been integrated over the course of 2 months or more, though a large number have been made in the weeks prior to the final release.

High-level Summary

New Image Format

The sensor_msgs/Image format now corresponds closely with OpenCV's CvMat type and is much simplified over the previous representation. The new fields are

encoding

width

height

step

data

The possible values of the encoding field are listed in the file "sensor_msgs/src/image_encodings.cpp". These are:

"rgb8"
"rgba8"
"bgr8"
"bgra8"
"mono8"
"mono16"

and "8UC1" through "64FC4" for the OpenCV image types.

as a convenience, an image creator can use the fillImage() function here to construct the Image message:

#include "sensor_msgs/fill_image.h"

fillImage(img_msg,
          sensor_msgs::image_encodings::RGB8,    // encoding
          my_height,                             // height
          my_width,                              // width
          3 * my_width,                          // step
          my_image_data                          // image data
);

Code changes

image_msgs/FillImage.h -> sensor_msgs/fill_image.h

Moved Messages

image_msgs/CamInfo                -> sensor_msgs/CameraInfo
image_msgs/DisparityInfo          -> stereo_msgs/DisparityInfo
image_msgs/RawStereo              -> stereo_msgs/RawStereo
image_msgs/RegionOfInterest       -> sensor_msgs/RegionOfInterest
image_msgs/StereoInfo             -> stereo_msgs/StereoInfo 
laser_scan/LaserScan              -> sensor_msgs/LaserScan
nav_srvs/StaticMap                -> nav_srvs/GetMap
nav_srvs/Plan                     -> nav_srvs/GetPlan
robot_msgs/AttachedObject         -> tabletop_msgs/AttachedObject
robot_msgs/BatteryState           -> pr2_msgs/BatteryState
robot_msgs/CollisionMap           -> mapping_msgs/CollisionMap
robot_msgs/ControllerState        -> pr2_mechanism_controllers/ControllerState
robot_msgs/DiagnosticMessage      -> diagnostic_msgs/DiagnosticArray
robot_msgs/MapMetaData            -> nav_msgs/MapMetaData
robot_msgs/ObjectOnTable          -> tabletop_msgs/ObjectOnTable
robot_msgs/OrientedBoundingBox    -> mapping_msgs/OrientedBoundingBox
robot_msgs/ParticleCloud          -> geometry_msgs/PoseArray
robot_msgs/ChannelFloat32         -> sensor_msgs/ChannelFloat32 ***
robot_msgs/Path                   -> nav_msgs/Path
robot_msgs/PolygonalMap           -> mapping_msgs/PolygonalMap
robot_msgs/Vector3                  -> geometry_msgs/Vector3
robot_msgs/Vector3Stamped           -> geometry_msgs/Vector3Stamped
robot_msgs/Point                  -> geometry_msgs/Point
robot_msgs/PointStamped           -> geometry_msgs/PointStamped
robot_msgs/Pose                   -> geometry_msgs/Pose
robot_msgs/PoseStamped            -> geometry_msgs/PoseStamped
robot_msgs/Transform              -> geometry_msgs/Transform
robot_msgs/Table                  -> tabletop_msgs/Table
robot_msgs/Quaternion             -> geometry_msgs/Quaternion
robot_srvs/SetPoseStamped         -> robot_mechanism_controllers/SetPoseStamped
robot_srvs/KillAndSpawnController -> mechanism_msgs/KillAndSpawnController
robot_srvs/KillController         -> mechanism_msgs/KillController
robot_srvs/ListControllers        -> mechanism_msgs/ListControllers
robot_srvs/SpawnController        -> mechanism_msgs/SpawnController
robot_srvs/SwitchController       -> mechanism_msgs/SwitchController
robot_srvs/StaticMap              -> nav_srvs/GetMap

Changed Messages

robot_msgs/DiagnosticStatus       -> diagnostic_msgs/DiagnosticStatus
 - added hardware_id
 - values changed to diagnostic_msgs/KeyValue
 - strings element deleted
robot_msgs/OccGrid                -> nav_msgs/OccupancyGrid
  - Added header
robot_msgs/PointCloud             -> sensor_msgs/PointCloud
 - pts -> points
 - chan -> channels
 - chan[].vals -> channels[].values
robot_msgs/PoseWithCovariance     -> geometry_msgs/PoseWithCovariance
 - covariance is now defined around fixed axis
 - field renamed from pose_with_covariance to pose
robot_msgs/Polygon3D              -> geometry_msgs/Polygon
 - color was removed
robot_msgs/Twist                  -> geometry_msgs/Twist
 - now uses Vector3 instead of Point
 - fields are now linear and angular
robot_msgs/Wrench                 -> geometry_msgs/Wrench
 - fields are now linear and angular
 - now uses Vector3 instead of Point
robot_msgs/TransformStamped       -> geometry_msgs/TransformStamped
 - changed semantics of parent and child relationship to be consistent
  - parent_id -> header.frame_id
  - frame_id -> child_frame_id
image_msgs/Image                  -> sensor_msgs/Image
  - Image underwent major changes and now aligns with OpenCV's CvMat data structure
image_msgs/CompressedImage        -> sensor_msgs/CompressedImage
  - removed encoding: https://prdev.willowgarage.com/trac/personalrobots/ticket/1915
visualization_msgs/Polyline       -> geometry_msgs/Polygon, nav_msgs/Path, nav_msgs/GridCells
 - Split into 3 messages based on use.  Paths -> nav_msgs/Path, robot footprint -> geometry_msgs/Polygon, and the raw/inflated obstacles -> nav_msgs/GridCells

Replaced Messages

robot_msgs/Acceleration           -> geometry_msgs/Vector3
  - ax, ay, az  -> x,y,z
robot_msgs/AngularAcceleration    -> geometry_msgs/Vector3
  - ax, ay, az  -> x,y,z
robot_msgs/AngularVelocity        -> geometry_msgs/Vector3
  - vx, vy, vz  -> x,y,z
robot_msgs/Velocity        -> geometry_msgs/Vector3
  - vx, vy, vz  -> x,y,z
robot_msgs/PoseDot                -> geometry_msgs/Twist
  - vel and ang_vel               -> linear and angular
robot_msgs/PoseWithRatesStamped   -> nav_msgs/Odometry or sensor_msgs/Imu (for IMU data)
 - completely restructured with covariance added
robot_msgs/DiagnosticValue        -> diagnostic_msgs/KeyValue
 - moved to more general string key/value
robot_msgs/DiagnosticString       -> diagnostic_msgs/KeyValue
 - moved to more general string key/value pair
deprecated_msgs/BaseRobot2DOdom   -> nav_msgs/Odometry
  - completely restructured with covariance added 
image_msgs/ImagePoint             -> geometry_msgs/Point
  - ignore z

New messages

geometry_msgs/Pose2D
geometry_msgs/PoseWithCovarianceStamped
geometry_msgs/PoseWithRates
geometry_msgs/TwistWithCovariance
geometry_msgs/TwistWithCovarianceStamped
geometry_msgs/WrenchStamped
sensor_msgs/Imu

Deprecated

robot_srvs/MoveToPose -> deprecated_srvs/MoveToPose
robot_msgs/VOPose     -> deprecated_msgs/VOPose

Deleted

robot_msgs/PoseDDot (unused)
robot_msgs/PoseWithRates
robot_srvs/GetJointCmd
robot_srvs/SetJointCmd 
robot_srvs/GetValue
robot_srvs/GetVector
robot_srvs/SetVector
robot_srvs/GetQuaternion

2024-03-23 12:30