Hi everybody. Let me announce package rosmsg_cpp I created to fill in the gap when working with messages metadata in C++.
If you know statically (at compile time) what message type you are working with, introspection of the message definition or MD5 sum is easy:
auto msgDefinition = ros::message_traits::definition<geometry_msgs::Vector3>();
If the type is not known at compile time (i.e. reading rosbags, generic subscribers, multi-master relays etc.), you can try either using the ShapeShifter
or rosbag::MessageInstance
classes directly or go with the almighty ros_msg_parser (formerly known as ros_type_introspection).
for (const rosbag::ConnectionInfo* connection : bag_view.getConnections())
{
const std::string& topic_name = connection->topic;
parsers.registerParser(topic_name, *connection);
}
for (rosbag::MessageInstance msg_instance : bag_view)
{
const std::string& topic_name = msg_instance.getTopic();
const auto deserialized_msg = parsers.deserialize(topic_name, msg_instance);
}
This dynamic introspection has one requirement which is not obvious - it still needs to be given the exact message definition to be able to parse the messages. In rosbag::MessageInstance
, the definition is stored in the bag connection header. With ShapeShifter
, you get the definition from the connection header, too. But without the definition, there is no introspection!
This is where rosmsg_cpp comes with help! If the only thing you have is a textual representation of a ROS message type (like std::string msgType = "geometry_msgs/Vector3";
), rosmsg_cpp can use the definitions from your local workspace to provide you the same values ros::message_traits
can tell about a message (and even more!).
Are you asking “Wait, there’s rosmsg show
, isn’t it?”, the answer is yes, but try to use it from C++!
std::vector<char> buf(1024);
int idx = 0;
std::string error;
if(!ros::names::validate(type, error))
{
ROS_WARN("Got invalid message type '%s'", type.c_str());
return "";
}
int fds[2];
if(pipe(fds) != 0)
throw std::runtime_error("Could not create pipe");
int pid = fork();
if(pid == 0)
{
close(fds[0]);
dup2(fds[1], STDOUT_FILENO);
if(execlp("rosmsg", "rosmsg", cmd.c_str(), type.c_str(), nullptr) != 0)
{
throw std::runtime_error("Could not execlp() rosmsg");
}
}
close(fds[1]);
while(1)
{
buf.resize(idx + 1024);
int size = read(fds[0], buf.data() + idx, 1024);
if(size < 0)
throw std::runtime_error("Could not read()");
else if(size == 0)
break;
idx += size;
}
close(fds[0]);
int status;
waitpid(pid, &status, 0);
if(!WIFEXITED(status) || WEXITSTATUS(status) != 0 || idx == 0)
{
ROS_WARN("Could not get rosmsg %s for type '%s'", cmd.c_str(), type.c_str());
return "";
}
std::string ret(buf.data(), idx);
Calling rosmsg
via execlp()
and such functions is not only inconvenient, it is also cumbersome, inefficient and may be even dangerous. Moreover, rosmsg show
will not output the exact message definition that is used by rosbag
and live ROS connections - it will only output the comment-stripped recursive definition, or the comment-retaining non-recursive definition. But ROS libraries expect and work with comment-retaining recursive definitions (the kind message_traits::definition()
returns).
With rosmsg_cpp, you get access to this full message definition along with other useful information:
-
getFullDef()
- get the full recursive message definition -
getMD5Sum()
- get the MD5 sum of the message used by ROS -
hasHeader()
- tell whether the message has aheader
field -
getFieldNames()
- return the names of the message fields (non-recursive) -
getFieldTypes()
- return the types of the message fields (non-recursive, types are returned as strings) -
getMsgFile()
- return the filesystem path to the.msg
file containing the definition -
getMD5Text()
- return the exact string from which the message’s MD5 sum is computed
As a direct application of the C++ library, I also added a binary called rosmsg++
which gives CLI access to all the library functions (just for convenience):
`rosmsg++ show|md5|fields|field-types|file|md5-text package/MessageType`
Implementation detail: The library does not use exec()
to call rosmsg
. It instead uses Python C API to dynamically load the Python message module and extracts the requested information via the Python C API. As the Python interpreter is only initialized once on load of the library, asking for many definitions is much faster than launching the whole interpreter for each request. However, even though this is a C++ library, it requires that the Python part of your ROS installation is working without issues.
The package has almost zero external dependencies (except for Python and roslib).
The package has been released for Melodic and Noetic :noetic: and will appear as a binary package in the subsequent releases (but not in the Melodic release that is just a few days ahead).
I think (at least) @facontidavide and @xqms might be interested in this package.
Example outputs:
$ rosmsg++ show nav_msgs/Odometry
# 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: 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/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/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/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
$ rosmsg++ md5 nav_msgs/Odometry
cd5e73d190d741a2f92e81eda573aca7
(yes, this is the same as the output of rosmsg md5 nav_msgs/Odometry
)
$ rosmsg++ md5-text nav_msgs/Odometry
2176decaecbce78abc3b96ef049fabed header
string child_frame_id
c23e848cf1b7533a8d7c259073a97e6f pose
1fe8a28e6890a4cc3ae4c3ca5c7d82e6 twist