mujoco_ros_utils
PosePublisher.cpp
Go to the documentation of this file.
1 #include "PosePublisher.h"
2 
3 #include <mujoco/mujoco.h>
4 
5 #include <iostream>
6 
7 namespace MujocoRosUtils
8 {
9 
11 {
12  mjpPlugin plugin;
13  mjp_defaultPlugin(&plugin);
14 
15  plugin.name = "MujocoRosUtils::PosePublisher";
16  plugin.capabilityflags |= mjPLUGIN_SENSOR;
17 
18  const char * attributes[] = {"frame_id", "pose_topic_name", "vel_topic_name",
19  "publish_rate", "output_tf", "tf_child_frame_id"};
20 
21  plugin.nattribute = sizeof(attributes) / sizeof(attributes[0]);
22  plugin.attributes = attributes;
23 
24  plugin.nstate = +[](const mjModel *, // m
25  int // plugin_id
26  ) { return 0; };
27 
28  plugin.nsensordata = +[](const mjModel *, // m
29  int, // plugin_id
30  int // sensor_id
31  ) { return 0; };
32 
33  plugin.needstage = mjSTAGE_VEL;
34 
35  plugin.init = +[](const mjModel * m, mjData * d, int plugin_id)
36  {
37  auto * plugin_instance = PosePublisher::Create(m, d, plugin_id);
38  if(!plugin_instance)
39  {
40  return -1;
41  }
42  d->plugin_data[plugin_id] = reinterpret_cast<uintptr_t>(plugin_instance);
43  return 0;
44  };
45 
46  plugin.destroy = +[](mjData * d, int plugin_id)
47  {
48  delete reinterpret_cast<PosePublisher *>(d->plugin_data[plugin_id]);
49  d->plugin_data[plugin_id] = 0;
50  };
51 
52  plugin.reset = +[](const mjModel * m, double *, // plugin_state
53  void * plugin_data, int plugin_id)
54  {
55  auto * plugin_instance = reinterpret_cast<class PosePublisher *>(plugin_data);
56  plugin_instance->reset(m, plugin_id);
57  };
58 
59  plugin.compute = +[](const mjModel * m, mjData * d, int plugin_id, int // capability_bit
60  )
61  {
62  auto * plugin_instance = reinterpret_cast<class PosePublisher *>(d->plugin_data[plugin_id]);
63  plugin_instance->compute(m, d, plugin_id);
64  };
65 
66  mjp_registerPlugin(&plugin);
67 }
68 
69 PosePublisher * PosePublisher::Create(const mjModel * m, mjData * d, int plugin_id)
70 {
71  // frame_id
72  const char * frame_id_char = mj_getPluginConfig(m, plugin_id, "frame_id");
73  std::string frame_id = "";
74  if(strlen(frame_id_char) > 0)
75  {
76  frame_id = std::string(frame_id_char);
77  }
78 
79  // pose_topic_name
80  const char * pose_topic_name_char = mj_getPluginConfig(m, plugin_id, "pose_topic_name");
81  std::string pose_topic_name = "";
82  if(strlen(pose_topic_name_char) > 0)
83  {
84  pose_topic_name = std::string(pose_topic_name_char);
85  }
86 
87  // vel_topic_name
88  const char * vel_topic_name_char = mj_getPluginConfig(m, plugin_id, "vel_topic_name");
89  std::string vel_topic_name = "";
90  if(strlen(vel_topic_name_char) > 0)
91  {
92  vel_topic_name = std::string(vel_topic_name_char);
93  }
94 
95  // publish_rate
96  const char * publish_rate_char = mj_getPluginConfig(m, plugin_id, "publish_rate");
97  mjtNum publish_rate = 30.0;
98  if(strlen(publish_rate_char) > 0)
99  {
100  publish_rate = strtod(publish_rate_char, nullptr);
101  }
102  if(publish_rate <= 0)
103  {
104  mju_error("[PosePublisher] `publish_rate` must be positive.");
105  return nullptr;
106  }
107 
108  // output_tf
109  const char * output_tf_char = mj_getPluginConfig(m, plugin_id, "output_tf");
110  bool output_tf = false;
111  if(strlen(output_tf_char) > 0)
112  {
113  if(!(strcmp(output_tf_char, "true") == 0 || strcmp(output_tf_char, "false") == 0))
114  {
115  mju_error("[PosePublisher] `output_tf` must be `true` or `false`.");
116  return nullptr;
117  }
118  output_tf = (strcmp(output_tf_char, "true") == 0);
119  }
120 
121  // tf_child_frame_id
122  const char * tf_child_frame_id_char = mj_getPluginConfig(m, plugin_id, "tf_child_frame_id");
123  std::string tf_child_frame_id = "";
124  if(strlen(tf_child_frame_id_char) > 0)
125  {
126  tf_child_frame_id = std::string(tf_child_frame_id_char);
127  }
128 
129  // Set sensor_id
130  int sensor_id = 0;
131  for(; sensor_id < m->nsensor; sensor_id++)
132  {
133  if(m->sensor_type[sensor_id] == mjSENS_PLUGIN && m->sensor_plugin[sensor_id] == plugin_id)
134  {
135  break;
136  }
137  }
138  if(sensor_id == m->nsensor)
139  {
140  mju_error("[PosePublisher] Plugin not found in sensors.");
141  return nullptr;
142  }
143  if(m->sensor_objtype[sensor_id] != mjOBJ_XBODY)
144  {
145  mju_error("[PosePublisher] Plugin must be attached to a xbody.");
146  return nullptr;
147  }
148 
149  std::cout << "[PosePublisher] Create." << std::endl;
150 
151  return new PosePublisher(m, d, sensor_id, frame_id, pose_topic_name, vel_topic_name, publish_rate, output_tf,
152  tf_child_frame_id);
153 }
154 
156  mjData *, // d
157  int sensor_id,
158  const std::string & frame_id,
159  const std::string & pose_topic_name,
160  const std::string & vel_topic_name,
161  mjtNum publish_rate,
162  bool output_tf,
163  const std::string & tf_child_frame_id)
164 : sensor_id_(sensor_id), body_id_(m->sensor_objid[sensor_id]), frame_id_(frame_id), pose_topic_name_(pose_topic_name),
165  vel_topic_name_(vel_topic_name), publish_skip_(std::max(static_cast<int>(1.0 / (publish_rate * m->opt.timestep)), 1)),
166  output_tf_(output_tf), tf_child_frame_id_(tf_child_frame_id)
167 {
168  std::string body_name = std::string(mj_id2name(m, mjOBJ_XBODY, body_id_));
169  if(frame_id_.empty())
170  {
171  frame_id_ = "map";
172  }
173  if(pose_topic_name_.empty())
174  {
175  pose_topic_name_ = "mujoco/" + body_name + "/pose";
176  }
177  if(vel_topic_name_.empty())
178  {
179  vel_topic_name_ = "mujoco/" + body_name + "/vel";
180  }
181  if(tf_child_frame_id_.empty())
182  {
183  tf_child_frame_id_ = body_name;
184  }
185 
186  int argc = 0;
187  char ** argv = nullptr;
188  if(!rclcpp::ok())
189  {
190  rclcpp::init(argc, argv);
191  }
192  rclcpp::NodeOptions node_options;
193 
194  nh_ = rclcpp::Node::make_shared("mujoco_ros", node_options);
195  if(output_tf_)
196  {
197  tf_br_ = std::make_unique<tf2_ros::TransformBroadcaster>(nh_);
198  }
199  else
200  {
201  pose_pub_ = nh_->create_publisher<geometry_msgs::msg::PoseStamped>(pose_topic_name, 1);
202  vel_pub_ = nh_->create_publisher<geometry_msgs::msg::TwistStamped>(vel_topic_name, 1);
203  }
204 }
205 
206 void PosePublisher::reset(const mjModel *, // m
207  int // plugin_id
208 )
209 {
210 }
211 
212 void PosePublisher::compute(const mjModel * m, mjData * d, int // plugin_id
213 )
214 {
215  sim_cnt_++;
216  if(sim_cnt_ % publish_skip_ != 0)
217  {
218  return;
219  }
220 
221  rclcpp::Time stamp_now = nh_->get_clock()->now();
222 
223  if(output_tf_)
224  {
225  geometry_msgs::msg::TransformStamped msg;
226  msg.header.stamp = stamp_now;
227  msg.header.frame_id = frame_id_;
228  msg.child_frame_id = tf_child_frame_id_;
229  msg.transform.translation.x = d->xpos[3 * body_id_ + 0];
230  msg.transform.translation.y = d->xpos[3 * body_id_ + 1];
231  msg.transform.translation.z = d->xpos[3 * body_id_ + 2];
232  msg.transform.rotation.w = d->xquat[4 * body_id_ + 0];
233  msg.transform.rotation.x = d->xquat[4 * body_id_ + 1];
234  msg.transform.rotation.y = d->xquat[4 * body_id_ + 2];
235  msg.transform.rotation.z = d->xquat[4 * body_id_ + 3];
236  tf_br_->sendTransform(msg);
237  }
238  else
239  {
240  geometry_msgs::msg::PoseStamped pose_msg;
241  pose_msg.header.stamp = stamp_now;
242  pose_msg.header.frame_id = frame_id_;
243  pose_msg.pose.position.x = d->xpos[3 * body_id_ + 0];
244  pose_msg.pose.position.y = d->xpos[3 * body_id_ + 1];
245  pose_msg.pose.position.z = d->xpos[3 * body_id_ + 2];
246  pose_msg.pose.orientation.w = d->xquat[4 * body_id_ + 0];
247  pose_msg.pose.orientation.x = d->xquat[4 * body_id_ + 1];
248  pose_msg.pose.orientation.y = d->xquat[4 * body_id_ + 2];
249  pose_msg.pose.orientation.z = d->xquat[4 * body_id_ + 3];
250  pose_pub_->publish(pose_msg);
251 
252  geometry_msgs::msg::TwistStamped vel_msg;
253  mjtNum vel[6];
254  mj_objectVelocity(m, d, mjOBJ_XBODY, body_id_, vel, 0);
255  vel_msg.header.stamp = stamp_now;
256  vel_msg.header.frame_id = frame_id_;
257  vel_msg.twist.linear.x = vel[3];
258  vel_msg.twist.linear.y = vel[4];
259  vel_msg.twist.linear.z = vel[5];
260  vel_msg.twist.angular.x = vel[0];
261  vel_msg.twist.angular.y = vel[1];
262  vel_msg.twist.angular.z = vel[2];
263  vel_pub_->publish(vel_msg);
264  }
265 }
266 
267 } // namespace MujocoRosUtils
Plugin to publish topics or broadcast TF of pose and velocity of the body.
Definition: PosePublisher.h:21
static void RegisterPlugin()
Register plugin.
std::string frame_id_
Frame ID of topics header or TF parent.
Definition: PosePublisher.h:92
std::string vel_topic_name_
Topic name of velocity.
Definition: PosePublisher.h:98
std::string tf_child_frame_id_
Child frame ID for TF.
rclcpp::Node::SharedPtr nh_
ROS node handle.
Definition: PosePublisher.h:80
void reset(const mjModel *m, int plugin_id)
Reset.
PosePublisher(PosePublisher &&)=default
Copy constructor.
std::string pose_topic_name_
Topic name of pose.
Definition: PosePublisher.h:95
rclcpp::Publisher< geometry_msgs::msg::PoseStamped >::SharedPtr pose_pub_
ROS publisher for pose.
Definition: PosePublisher.h:83
int publish_skip_
Iteration interval to skip ROS publish.
std::unique_ptr< tf2_ros::TransformBroadcaster > tf_br_
TF broadcaster.
Definition: PosePublisher.h:89
static PosePublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
bool output_tf_
Whether to broadcast TF.
rclcpp::Publisher< geometry_msgs::msg::TwistStamped >::SharedPtr vel_pub_
ROS publisher for velocity.
Definition: PosePublisher.h:86
int sim_cnt_
Iteration count of simulation.