mujoco_ros_utils
Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
MujocoRosUtils::ImagePublisher Class Reference

Plugin to publish topics of color and depth images. More...

#include <ImagePublisher.h>

Public Member Functions

 ImagePublisher (ImagePublisher &&)=default
 Copy constructor. More...
 
void reset (const mjModel *m, int plugin_id)
 Reset. More...
 
void compute (const mjModel *m, mjData *d, int plugin_id)
 Compute. More...
 
void free ()
 Free buffer. More...
 

Static Public Member Functions

static void RegisterPlugin ()
 Register plugin. More...
 
static ImagePublisherCreate (const mjModel *m, mjData *d, int plugin_id)
 Create an instance. More...
 

Protected Member Functions

 ImagePublisher (const mjModel *m, mjData *d, int sensor_id, const std::string &frame_id, std::string color_topic_name, std::string depth_topic_name, std::string info_topic_name, int height, int width, mjtNum publish_rate)
 Constructor. More...
 

Protected Attributes

int sensor_id_ = -1
 Sensor ID. More...
 
int camera_id_ = -1
 Camera ID. More...
 
std::string frame_id_
 Frame ID of topics header or TF parent. More...
 
int publish_skip_ = 0
 Iteration interval to skip ROS publish. More...
 
int sim_cnt_ = 0
 Iteration count of simulation. More...
 
unsigned char * color_buffer_
 
float * depth_buffer_
 
unsigned char * color_buffer_flipped_
 
float * depth_buffer_flipped_
 
mjvScene scene_
 
mjvCamera camera_
 
mjvOption option_
 
mjrContext context_
 
mjrRect viewport_
 
GLFWwindow * window_
 
rclcpp::Node::SharedPtr nh_
 
rclcpp::Publisher< sensor_msgs::msg::Image >::SharedPtr color_pub_
 
rclcpp::Publisher< sensor_msgs::msg::Image >::SharedPtr depth_pub_
 
rclcpp::Publisher< sensor_msgs::msg::CameraInfo >::SharedPtr info_pub_
 

Detailed Description

Plugin to publish topics of color and depth images.

Definition at line 20 of file ImagePublisher.h.

Constructor & Destructor Documentation

◆ ImagePublisher() [1/2]

MujocoRosUtils::ImagePublisher::ImagePublisher ( ImagePublisher &&  )
default

Copy constructor.

◆ ImagePublisher() [2/2]

MujocoRosUtils::ImagePublisher::ImagePublisher ( const mjModel *  m,
mjData *  d,
int  sensor_id,
const std::string &  frame_id,
std::string  color_topic_name,
std::string  depth_topic_name,
std::string  info_topic_name,
int  height,
int  width,
mjtNum  publish_rate 
)
protected

Constructor.

Parameters
mmodel
ddata
sensor_idsensor ID
frame_idframe ID of topics header or TF parent
color_topic_nametopic name of color image
depth_topic_nametopic name of depth image
info_topic_nametopic name of camera information
heightimage height
widthimage width
publish_ratepublish rate

Definition at line 170 of file ImagePublisher.cpp.

Member Function Documentation

◆ compute()

void MujocoRosUtils::ImagePublisher::compute ( const mjModel *  m,
mjData *  d,
int  plugin_id 
)

Compute.

Parameters
mmodel
ddata
plugin_idplugin ID

Definition at line 269 of file ImagePublisher.cpp.

◆ Create()

ImagePublisher * MujocoRosUtils::ImagePublisher::Create ( const mjModel *  m,
mjData *  d,
int  plugin_id 
)
static

Create an instance.

Parameters
mmodel
ddata
plugin_idplugin ID

Definition at line 71 of file ImagePublisher.cpp.

◆ free()

void MujocoRosUtils::ImagePublisher::free ( )

Free buffer.

Definition at line 360 of file ImagePublisher.cpp.

◆ RegisterPlugin()

MujocoRosUtils::ImagePublisher::RegisterPlugin ( )
static

Register plugin.

Definition at line 10 of file ImagePublisher.cpp.

◆ reset()

void MujocoRosUtils::ImagePublisher::reset ( const mjModel *  m,
int  plugin_id 
)

Reset.

Parameters
mmodel
plugin_idplugin ID

Definition at line 263 of file ImagePublisher.cpp.

Member Data Documentation

◆ camera_

mjvCamera MujocoRosUtils::ImagePublisher::camera_
protected

Variables for visualization and rendering in MuJoCo

Definition at line 104 of file ImagePublisher.h.

◆ camera_id_

int MujocoRosUtils::ImagePublisher::camera_id_ = -1
protected

Camera ID.

Definition at line 82 of file ImagePublisher.h.

◆ color_buffer_

unsigned char* MujocoRosUtils::ImagePublisher::color_buffer_
protected

Data buffer

Definition at line 95 of file ImagePublisher.h.

◆ color_buffer_flipped_

unsigned char* MujocoRosUtils::ImagePublisher::color_buffer_flipped_
protected

Data buffer

Definition at line 97 of file ImagePublisher.h.

◆ color_pub_

rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr MujocoRosUtils::ImagePublisher::color_pub_
protected

ROS variables

Definition at line 114 of file ImagePublisher.h.

◆ context_

mjrContext MujocoRosUtils::ImagePublisher::context_
protected

Variables for visualization and rendering in MuJoCo

Definition at line 106 of file ImagePublisher.h.

◆ depth_buffer_

float* MujocoRosUtils::ImagePublisher::depth_buffer_
protected

Data buffer

Definition at line 96 of file ImagePublisher.h.

◆ depth_buffer_flipped_

float* MujocoRosUtils::ImagePublisher::depth_buffer_flipped_
protected

Data buffer

Definition at line 98 of file ImagePublisher.h.

◆ depth_pub_

rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr MujocoRosUtils::ImagePublisher::depth_pub_
protected

ROS variables

Definition at line 115 of file ImagePublisher.h.

◆ frame_id_

std::string MujocoRosUtils::ImagePublisher::frame_id_
protected

Frame ID of topics header or TF parent.

Definition at line 85 of file ImagePublisher.h.

◆ info_pub_

rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr MujocoRosUtils::ImagePublisher::info_pub_
protected

ROS variables

Definition at line 116 of file ImagePublisher.h.

◆ nh_

rclcpp::Node::SharedPtr MujocoRosUtils::ImagePublisher::nh_
protected

ROS variables

Definition at line 113 of file ImagePublisher.h.

◆ option_

mjvOption MujocoRosUtils::ImagePublisher::option_
protected

Variables for visualization and rendering in MuJoCo

Definition at line 105 of file ImagePublisher.h.

◆ publish_skip_

int MujocoRosUtils::ImagePublisher::publish_skip_ = 0
protected

Iteration interval to skip ROS publish.

Definition at line 88 of file ImagePublisher.h.

◆ scene_

mjvScene MujocoRosUtils::ImagePublisher::scene_
protected

Variables for visualization and rendering in MuJoCo

Definition at line 103 of file ImagePublisher.h.

◆ sensor_id_

int MujocoRosUtils::ImagePublisher::sensor_id_ = -1
protected

Sensor ID.

Definition at line 79 of file ImagePublisher.h.

◆ sim_cnt_

int MujocoRosUtils::ImagePublisher::sim_cnt_ = 0
protected

Iteration count of simulation.

Definition at line 91 of file ImagePublisher.h.

◆ viewport_

mjrRect MujocoRosUtils::ImagePublisher::viewport_
protected

Variables for visualization and rendering in MuJoCo

Definition at line 107 of file ImagePublisher.h.

◆ window_

GLFWwindow* MujocoRosUtils::ImagePublisher::window_
protected

Variables for visualization and rendering in MuJoCo

Definition at line 108 of file ImagePublisher.h.


The documentation for this class was generated from the following files: