3 #include <mujoco/mujoco.h>
13 mjp_defaultPlugin(&plugin);
15 plugin.name =
"MujocoRosUtils::ImagePublisher";
16 plugin.capabilityflags |= mjPLUGIN_SENSOR;
18 const char * attributes[] = {
"frame_id",
"color_topic_name",
"depth_topic_name",
"info_topic_name",
"height",
19 "width",
"publish_rate"};
21 plugin.nattribute =
sizeof(attributes) /
sizeof(attributes[0]);
22 plugin.attributes = attributes;
24 plugin.nstate = +[](
const mjModel *,
28 plugin.nsensordata = +[](
const mjModel *,
33 plugin.needstage = mjSTAGE_VEL;
35 plugin.init = +[](
const mjModel * m, mjData * d,
int plugin_id)
42 d->plugin_data[plugin_id] =
reinterpret_cast<uintptr_t
>(plugin_instance);
46 plugin.destroy = +[](mjData * d,
int plugin_id)
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;
54 plugin.
reset = +[](
const mjModel * m,
double *,
55 void * plugin_data,
int plugin_id)
57 auto * plugin_instance =
reinterpret_cast<class
ImagePublisher *
>(plugin_data);
58 plugin_instance->
reset(m, plugin_id);
61 plugin.compute = +[](
const mjModel * m, mjData * d,
int plugin_id,
int
64 auto * plugin_instance =
reinterpret_cast<class
ImagePublisher *
>(d->plugin_data[plugin_id]);
65 plugin_instance->
compute(m, d, plugin_id);
68 mjp_registerPlugin(&plugin);
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)
78 frame_id = std::string(frame_id_char);
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)
86 color_topic_name = std::string(color_topic_name_char);
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)
94 depth_topic_name = std::string(depth_topic_name_char);
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)
102 info_topic_name = std::string(info_topic_name_char);
106 const char * height_char = mj_getPluginConfig(m, plugin_id,
"height");
108 if(strlen(height_char) > 0)
110 height =
static_cast<int>(strtol(height_char,
nullptr, 10));
114 mju_error(
"[ImagePublisher] `height` must be positive.");
119 const char * width_char = mj_getPluginConfig(m, plugin_id,
"width");
121 if(strlen(width_char) > 0)
123 width =
static_cast<int>(strtol(width_char,
nullptr, 10));
127 mju_error(
"[ImagePublisher] `width` must be positive.");
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)
136 publish_rate = strtod(publish_rate_char,
nullptr);
138 if(publish_rate <= 0)
140 mju_error(
"[ImagePublisher] `publish_rate` must be positive.");
146 for(; sensor_id < m->nsensor; sensor_id++)
148 if(m->sensor_type[sensor_id] == mjSENS_PLUGIN && m->sensor_plugin[sensor_id] == plugin_id)
153 if(sensor_id == m->nsensor)
155 mju_error(
"[ImagePublisher] Plugin not found in sensors.");
158 if(m->sensor_objtype[sensor_id] != mjOBJ_CAMERA)
160 mju_error(
"[ImagePublisher] Plugin must be attached to a camera.");
164 std::cout <<
"[ImagePublisher] Create." << std::endl;
166 return new ImagePublisher(m, d, sensor_id, frame_id, color_topic_name, depth_topic_name, info_topic_name, height,
167 width, publish_rate);
173 const std::string & frame_id,
174 std::string color_topic_name,
175 std::string depth_topic_name,
176 std::string info_topic_name,
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})
183 std::string camera_name = std::string(mj_id2name(m, mjOBJ_CAMERA, camera_id_));
184 if(frame_id_.empty())
186 frame_id_ = camera_name;
188 if(color_topic_name.empty())
190 color_topic_name =
"mujoco/" + camera_name +
"/color";
192 if(depth_topic_name.empty())
194 depth_topic_name =
"mujoco/" + camera_name +
"/depth";
196 if(info_topic_name.empty())
198 info_topic_name =
"mujoco/" + camera_name +
"/camera_info";
204 mju_error(
"[ImagePublisher] Could not initialize GLFW.");
208 glfwWindowHint(GLFW_VISIBLE, GLFW_FALSE);
209 glfwWindowHint(GLFW_DOUBLEBUFFER, GLFW_FALSE);
210 window_ = glfwCreateWindow(viewport_.width, viewport_.height,
"MujocoRosUtils::ImagePublisher",
nullptr,
nullptr);
213 mju_error(
"[ImagePublisher] Could not create GLFW window.");
218 glfwMakeContextCurrent(window_);
221 mjv_defaultCamera(&camera_);
222 mjv_defaultOption(&option_);
223 mjv_defaultScene(&scene_);
224 mjr_defaultContext(&context_);
227 mjv_makeScene(m, &scene_, 1000);
228 mjr_makeContext(m, &context_, mjFONTSCALE_100);
231 camera_.type = mjCAMERA_FIXED;
232 camera_.fixedcamid = camera_id_;
234 mjr_setBuffer(mjFB_OFFSCREEN, &context_);
235 if(context_.currentBuffer != mjFB_OFFSCREEN)
237 mju_error(
"[ImagePublisher] Offscreen rendering not supported, using default/window framebuffer.");
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));
250 char ** argv =
nullptr;
253 rclcpp::init(argc, argv);
255 rclcpp::NodeOptions node_options;
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);
280 glfwMakeContextCurrent(
window_);
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);
296 for(
int h = 0; h <
viewport_.height; h++)
305 for(
int c = 0; c < 3; c++)
314 rclcpp::Time stamp_now =
nh_->get_clock()->now();
316 sensor_msgs::msg::Image color_msg;
317 color_msg.header.stamp = stamp_now;
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);
329 sensor_msgs::msg::Image depth_msg;
330 depth_msg.header.stamp = stamp_now;
334 depth_msg.encoding =
"32FC1";
335 depth_msg.is_bigendian = 0;
336 depth_msg.step =
static_cast<unsigned int>(
sizeof(float) *
viewport_.width);
341 sensor_msgs::msg::CameraInfo info_msg;
342 info_msg.header.stamp = stamp_now;
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;
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.
unsigned char * color_buffer_
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.
float * depth_buffer_flipped_