Go to the documentation of this file.
5 #include <mujoco/mjdata.h>
6 #include <mujoco/mjmodel.h>
7 #include <mujoco/mjrender.h>
8 #include <mujoco/mjtnum.h>
9 #include <mujoco/mjvisualize.h>
11 #include <GLFW/glfw3.h>
39 void reset(
const mjModel * m,
int plugin_id);
46 void compute(
const mjModel * m, mjData * d,
int plugin_id);
67 const std::string & frame_id,
68 std::string color_topic_name,
69 std::string depth_topic_name,
70 std::string info_topic_name,
111 std::shared_ptr<ros::NodeHandle>
nh_;
std::string frame_id_
Frame ID of topics header or TF parent.
static void RegisterPlugin()
Register plugin.
int publish_skip_
Iteration interval to skip ROS publish.
static ImagePublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
void reset(const mjModel *m, int plugin_id)
Reset.
int sim_cnt_
Iteration count of simulation.
ros::Publisher color_pub_
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
std::shared_ptr< ros::NodeHandle > nh_
ros::Publisher depth_pub_
unsigned char * color_buffer_
unsigned char * color_buffer_flipped_
Plugin to publish topics of color and depth images.
ImagePublisher(ImagePublisher &&)=default
Copy constructor.
float * depth_buffer_flipped_