mujoco_ros_utils
ImagePublisher.cpp
Go to the documentation of this file.
1 #include "ImagePublisher.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::ImagePublisher";
16  plugin.capabilityflags |= mjPLUGIN_SENSOR;
17 
18  const char * attributes[] = {"frame_id", "color_topic_name", "depth_topic_name", "info_topic_name", "height",
19  "width", "publish_rate"};
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 = ImagePublisher::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  auto * plugin_instance = reinterpret_cast<class ImagePublisher *>(d->plugin_data[plugin_id]);
49  plugin_instance->free();
50  delete reinterpret_cast<ImagePublisher *>(d->plugin_data[plugin_id]);
51  d->plugin_data[plugin_id] = 0;
52  };
53 
54  plugin.reset = +[](const mjModel * m, double *, // plugin_state
55  void * plugin_data, int plugin_id)
56  {
57  auto * plugin_instance = reinterpret_cast<class ImagePublisher *>(plugin_data);
58  plugin_instance->reset(m, plugin_id);
59  };
60 
61  plugin.compute = +[](const mjModel * m, mjData * d, int plugin_id, int // capability_bit
62  )
63  {
64  auto * plugin_instance = reinterpret_cast<class ImagePublisher *>(d->plugin_data[plugin_id]);
65  plugin_instance->compute(m, d, plugin_id);
66  };
67 
68  mjp_registerPlugin(&plugin);
69 }
70 
71 ImagePublisher * ImagePublisher::Create(const mjModel * m, mjData * d, int plugin_id)
72 {
73  // frame_id
74  const char * frame_id_char = mj_getPluginConfig(m, plugin_id, "frame_id");
75  std::string frame_id = "";
76  if(strlen(frame_id_char) > 0)
77  {
78  frame_id = std::string(frame_id_char);
79  }
80 
81  // color_topic_name
82  const char * color_topic_name_char = mj_getPluginConfig(m, plugin_id, "color_topic_name");
83  std::string color_topic_name = "";
84  if(strlen(color_topic_name_char) > 0)
85  {
86  color_topic_name = std::string(color_topic_name_char);
87  }
88 
89  // depth_topic_name
90  const char * depth_topic_name_char = mj_getPluginConfig(m, plugin_id, "depth_topic_name");
91  std::string depth_topic_name = "";
92  if(strlen(depth_topic_name_char) > 0)
93  {
94  depth_topic_name = std::string(depth_topic_name_char);
95  }
96 
97  // info_topic_name
98  const char * info_topic_name_char = mj_getPluginConfig(m, plugin_id, "info_topic_name");
99  std::string info_topic_name = "";
100  if(strlen(info_topic_name_char) > 0)
101  {
102  info_topic_name = std::string(info_topic_name_char);
103  }
104 
105  // height
106  const char * height_char = mj_getPluginConfig(m, plugin_id, "height");
107  int height = 240;
108  if(strlen(height_char) > 0)
109  {
110  height = static_cast<int>(strtol(height_char, nullptr, 10));
111  }
112  if(height <= 0)
113  {
114  mju_error("[ImagePublisher] `height` must be positive.");
115  return nullptr;
116  }
117 
118  // width
119  const char * width_char = mj_getPluginConfig(m, plugin_id, "width");
120  int width = 320;
121  if(strlen(width_char) > 0)
122  {
123  width = static_cast<int>(strtol(width_char, nullptr, 10));
124  }
125  if(width <= 0)
126  {
127  mju_error("[ImagePublisher] `width` must be positive.");
128  return nullptr;
129  }
130 
131  // publish_rate
132  const char * publish_rate_char = mj_getPluginConfig(m, plugin_id, "publish_rate");
133  mjtNum publish_rate = 30.0;
134  if(strlen(publish_rate_char) > 0)
135  {
136  publish_rate = strtod(publish_rate_char, nullptr);
137  }
138  if(publish_rate <= 0)
139  {
140  mju_error("[ImagePublisher] `publish_rate` must be positive.");
141  return nullptr;
142  }
143 
144  // Set sensor_id
145  int sensor_id = 0;
146  for(; sensor_id < m->nsensor; sensor_id++)
147  {
148  if(m->sensor_type[sensor_id] == mjSENS_PLUGIN && m->sensor_plugin[sensor_id] == plugin_id)
149  {
150  break;
151  }
152  }
153  if(sensor_id == m->nsensor)
154  {
155  mju_error("[ImagePublisher] Plugin not found in sensors.");
156  return nullptr;
157  }
158  if(m->sensor_objtype[sensor_id] != mjOBJ_CAMERA)
159  {
160  mju_error("[ImagePublisher] Plugin must be attached to a camera.");
161  return nullptr;
162  }
163 
164  std::cout << "[ImagePublisher] Create." << std::endl;
165 
166  return new ImagePublisher(m, d, sensor_id, frame_id, color_topic_name, depth_topic_name, info_topic_name, height,
167  width, publish_rate);
168 }
169 
171  mjData *, // d
172  int sensor_id,
173  const std::string & frame_id,
174  std::string color_topic_name,
175  std::string depth_topic_name,
176  std::string info_topic_name,
177  int height,
178  int width,
179  mjtNum publish_rate)
180 : sensor_id_(sensor_id), camera_id_(m->sensor_objid[sensor_id]), frame_id_(frame_id),
181  publish_skip_(std::max(static_cast<int>(1.0 / (publish_rate * m->opt.timestep)), 1)), viewport_({0, 0, width, height})
182 {
183  std::string camera_name = std::string(mj_id2name(m, mjOBJ_CAMERA, camera_id_));
184  if(frame_id_.empty())
185  {
186  frame_id_ = camera_name;
187  }
188  if(color_topic_name.empty())
189  {
190  color_topic_name = "mujoco/" + camera_name + "/color";
191  }
192  if(depth_topic_name.empty())
193  {
194  depth_topic_name = "mujoco/" + camera_name + "/depth";
195  }
196  if(info_topic_name.empty())
197  {
198  info_topic_name = "mujoco/" + camera_name + "/camera_info";
199  }
200 
201  // Init OpenGL
202  if(!glfwInit())
203  {
204  mju_error("[ImagePublisher] Could not initialize GLFW.");
205  }
206 
207  // Create invisible window, single-buffered
208  glfwWindowHint(GLFW_VISIBLE, GLFW_FALSE);
209  glfwWindowHint(GLFW_DOUBLEBUFFER, GLFW_FALSE);
210  window_ = glfwCreateWindow(viewport_.width, viewport_.height, "MujocoRosUtils::ImagePublisher", nullptr, nullptr);
211  if(!window_)
212  {
213  mju_error("[ImagePublisher] Could not create GLFW window.");
214  }
215 
216  // Make context current
217  // \todo Is it OK to override the current context of OpenGL?
218  glfwMakeContextCurrent(window_);
219 
220  // Init default data for visualization structures
221  mjv_defaultCamera(&camera_);
222  mjv_defaultOption(&option_);
223  mjv_defaultScene(&scene_);
224  mjr_defaultContext(&context_);
225 
226  // Create scene and context
227  mjv_makeScene(m, &scene_, 1000);
228  mjr_makeContext(m, &context_, mjFONTSCALE_100);
229 
230  // Init camera
231  camera_.type = mjCAMERA_FIXED;
232  camera_.fixedcamid = camera_id_;
233 
234  mjr_setBuffer(mjFB_OFFSCREEN, &context_);
235  if(context_.currentBuffer != mjFB_OFFSCREEN)
236  {
237  mju_error("[ImagePublisher] Offscreen rendering not supported, using default/window framebuffer.");
238  }
239 
240  // Allocate buffer
241  size_t color_buffer_size = sizeof(unsigned char) * 3 * viewport_.width * viewport_.height;
242  size_t depth_buffer_size = sizeof(float) * viewport_.width * viewport_.height;
243  color_buffer_ = static_cast<unsigned char *>(std::malloc(color_buffer_size));
244  depth_buffer_ = static_cast<float *>(std::malloc(depth_buffer_size));
245  color_buffer_flipped_ = static_cast<unsigned char *>(std::malloc(color_buffer_size));
246  depth_buffer_flipped_ = static_cast<float *>(std::malloc(depth_buffer_size));
247 
248  // Init ROS
249  int argc = 0;
250  char ** argv = nullptr;
251  if(!rclcpp::ok())
252  {
253  rclcpp::init(argc, argv);
254  }
255  rclcpp::NodeOptions node_options;
256 
257  nh_ = rclcpp::Node::make_shared("mujoco_ros", node_options);
258  color_pub_ = nh_->create_publisher<sensor_msgs::msg::Image>(color_topic_name, 1);
259  depth_pub_ = nh_->create_publisher<sensor_msgs::msg::Image>(depth_topic_name, 1);
260  info_pub_ = nh_->create_publisher<sensor_msgs::msg::CameraInfo>(info_topic_name, 1);
261 }
262 
263 void ImagePublisher::reset(const mjModel *, // m
264  int // plugin_id
265 )
266 {
267 }
268 
269 void ImagePublisher::compute(const mjModel * m, mjData * d, int // plugin_id
270 )
271 {
272  sim_cnt_++;
273  if(sim_cnt_ % publish_skip_ != 0)
274  {
275  return;
276  }
277 
278  // Make context current
279  // \todo Is it OK to override the current context of OpenGL?
280  glfwMakeContextCurrent(window_);
281 
282  // Update abstract scene
283  mjv_updateScene(m, d, &option_, nullptr, &camera_, mjCAT_STATIC | mjCAT_DYNAMIC, &scene_);
284 
285  // Render scene in offscreen buffer
286  mjr_render(viewport_, &scene_, &context_);
287 
288  // Read rgb and depth pixels
289  mjr_readPixels(color_buffer_, depth_buffer_, viewport_, &context_);
290 
291  // Convert raw depth to distance and flip images
292  float near = static_cast<float>(m->vis.map.znear * m->stat.extent);
293  float far = static_cast<float>(m->vis.map.zfar * m->stat.extent);
294  for(int w = 0; w < viewport_.width; w++)
295  {
296  for(int h = 0; h < viewport_.height; h++)
297  {
298  int idx = h * viewport_.width + w;
299  int idx_flipped = (viewport_.height - 1 - h) * viewport_.width + w;
300 
301  // See
302  // https://github.com/deepmind/mujoco/blob/631b16e7ad192df936195658fe79f2ada85f755c/python/mujoco/renderer.py#L175-L178
303  depth_buffer_[idx] = near / (1.0f - depth_buffer_[idx] * (1.0f - near / far));
304 
305  for(int c = 0; c < 3; c++)
306  {
307  color_buffer_flipped_[3 * idx_flipped + c] = color_buffer_[3 * idx + c];
308  }
309  depth_buffer_flipped_[idx_flipped] = depth_buffer_[idx];
310  }
311  }
312 
313  // Publish topic
314  rclcpp::Time stamp_now = nh_->get_clock()->now();
315 
316  sensor_msgs::msg::Image color_msg;
317  color_msg.header.stamp = stamp_now;
318  color_msg.header.frame_id = frame_id_;
319  color_msg.height = viewport_.height;
320  color_msg.width = viewport_.width;
321  color_msg.encoding = "rgb8";
322  color_msg.is_bigendian = 0;
323  color_msg.step = static_cast<unsigned int>(sizeof(unsigned char) * 3 * viewport_.width);
324  color_msg.data.resize(sizeof(unsigned char) * 3 * viewport_.width * viewport_.height);
325  std::memcpy(&color_msg.data[0], color_buffer_flipped_,
326  sizeof(unsigned char) * 3 * viewport_.width * viewport_.height);
327  color_pub_->publish(color_msg);
328 
329  sensor_msgs::msg::Image depth_msg;
330  depth_msg.header.stamp = stamp_now;
331  depth_msg.header.frame_id = frame_id_;
332  depth_msg.height = viewport_.height;
333  depth_msg.width = viewport_.width;
334  depth_msg.encoding = "32FC1";
335  depth_msg.is_bigendian = 0;
336  depth_msg.step = static_cast<unsigned int>(sizeof(float) * viewport_.width);
337  depth_msg.data.resize(sizeof(float) * viewport_.width * viewport_.height);
338  std::memcpy(&depth_msg.data[0], depth_buffer_flipped_, sizeof(float) * viewport_.width * viewport_.height);
339  depth_pub_->publish(depth_msg);
340 
341  sensor_msgs::msg::CameraInfo info_msg;
342  info_msg.header.stamp = stamp_now;
343  info_msg.header.frame_id = frame_id_;
344  info_msg.height = viewport_.height;
345  info_msg.width = viewport_.width;
346  info_msg.distortion_model = "plumb_bob";
347  info_msg.d.resize(5, 0.0);
348  info_msg.k.fill(0.0);
349  info_msg.r.fill(0.0);
350  info_msg.p.fill(0.0);
351  double focal_scaling = (1.0 / std::tan((m->cam_fovy[camera_id_] * M_PI / 180.0) / 2.0)) * viewport_.height / 2.0;
352  info_msg.k[0] = info_msg.p[0] = focal_scaling;
353  info_msg.k[2] = info_msg.p[2] = static_cast<double>(viewport_.width) / 2.0;
354  info_msg.k[4] = info_msg.p[5] = focal_scaling;
355  info_msg.k[5] = info_msg.p[6] = static_cast<double>(viewport_.height) / 2.0;
356  info_msg.k[8] = info_msg.p[10] = 1.0;
357  info_pub_->publish(info_msg);
358 }
359 
361 {
362  std::free(color_buffer_);
363  std::free(depth_buffer_);
364  std::free(color_buffer_flipped_);
365  std::free(depth_buffer_flipped_);
366 
367  mjr_freeContext(&context_);
368  mjv_freeScene(&scene_);
369 
370  glfwDestroyWindow(window_);
371 }
372 
373 } // namespace MujocoRosUtils
Plugin to publish topics of color and depth images.
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
int publish_skip_
Iteration interval to skip ROS publish.
unsigned char * color_buffer_flipped_
rclcpp::Publisher< sensor_msgs::msg::Image >::SharedPtr color_pub_
rclcpp::Publisher< sensor_msgs::msg::Image >::SharedPtr depth_pub_
ImagePublisher(ImagePublisher &&)=default
Copy constructor.
rclcpp::Publisher< sensor_msgs::msg::CameraInfo >::SharedPtr info_pub_
int sim_cnt_
Iteration count of simulation.
std::string frame_id_
Frame ID of topics header or TF parent.
static void RegisterPlugin()
Register plugin.
void reset(const mjModel *m, int plugin_id)
Reset.
rclcpp::Node::SharedPtr nh_
static ImagePublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.