ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Is there a concise way to initialize a message with specific values?

asked 2022-04-14 16:05:48 -0600

jschornak gravatar image

Whenever I need to instantiate a message with specific values (in test code, for example), I end up writing something like this:

geometry_msgs::msg::Pose my_pose;
my_pose.position.x = 0.1;
my_pose.position.y = 0.2;
my_pose.position.z = 0.3;
my_pose.orientation.x = 0.5;
my_pose.orientation.y = 0.5;
my_pose.orientation.z = 0.5;
my_pose.orientation.w = 0.5;

Is there a more concise way to do this? I was hoping for something closer to a uniform initialization approach like below, but it doesn't seem to play nicely with how the message classes are implemented.

geometry_msgs::msg::Pose my_pose{ geometry_msgs::msg::Point { 0.1, 0.2, 0.3 }, geometry_msgs::msg::Quaternion { 0.5, 0.5, 0.5, 0.5 } };
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2022-04-15 06:17:13 -0600

Kenji Miyake gravatar image

You can write like this.

geometry_msgs::build<geometry_msgs::msg::Point>().x(p.x).y(p.y).z(p.z);

See this issue for details.

edit flag offensive delete link more

Comments

1

Nice pattern! This should be better documented somewhere.

aprotyas gravatar image aprotyas  ( 2022-04-15 09:09:15 -0600 )edit

Neat! What is the correct header to include for a particular message type? For geometry_msgs::msg::Point I see #include <geometry_msgs/msg/detail/point__builder.hpp>, but the structure of the path to the header kinda implies that this is part of the internal API.

jschornak gravatar image jschornak  ( 2022-04-15 11:41:35 -0600 )edit

@jschornak I believe the message header will give you access to this templated build function too since <geometry_msgs/msg/point.hpp> includes <geometry_msgs/msg/detail/point__builder.hpp>.

aprotyas gravatar image aprotyas  ( 2022-04-15 12:11:51 -0600 )edit
0

answered 2022-04-14 20:57:40 -0600

aprotyas gravatar image

updated 2022-04-14 21:02:24 -0600

Unfortunately there isn't a concise way to do that. The message classes aren't implemented with these constructors for various reasons -- some context (from ROS 1) here: https://github.com/ros/ros_comm/issue...

I've ended up writing some utility functions that let me do things like this, but I don't know if I recommend that since it's just extra tech debt in (probably) your test code:

#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include "geometry_msgs/msg/quaternion.hpp"

namespace geometry_msgs::msg {
auto make_point(double x, double y, double z) {
  Point p;
  p.x = x; p.y = y; p.z = z;
  return p;
}

auto make_quaternion(double x = 0.0, double y = 0.0, double z = 0.0, double w = 1.0) {
  Quaternion q;
  q.x = x; q.y = y; q.z = z; q.w = w;
  return q;
}

auto make_pose(Point p, Quaternion q) {
  Pose pose;
  pose.position = p;
  pose.orientation = q;
  return pose;
}
}

{
  using namespace geometry_msgs::msg;
  Pose pose = make_pose(make_point(1, 2, 3), make_quaternion(1, 0, 0, 0));
}

Honestly, someone should just make a ROS package with interfaces like this, at least for the common message types...

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2022-04-14 16:05:48 -0600

Seen: 2,108 times

Last updated: Apr 15 '22