![]() |
ros2_control - humble
|
Wraps MuJoCo cameras for publishing ROS 2 RGB-D streams. More...
#include <mujoco_cameras.hpp>
Public Member Functions | |
| MujocoCameras (rclcpp::Node::SharedPtr node, std::recursive_mutex *sim_mutex, mjData *mujoco_data, mjModel *mujoco_model, double camera_publish_rate) | |
| Constructs a new MujocoCameras wrapper object. | |
| void | init () |
| Starts the image processing thread in the background. | |
| void | close () |
| Stops the camera processing thread and closes the relevant objects, call before shutdown. | |
| void | register_cameras (const hardware_interface::HardwareInfo &hardware_info) |
| Parses camera information from the mujoco model. | |
Wraps MuJoCo cameras for publishing ROS 2 RGB-D streams.
|
explicit |
Constructs a new MujocoCameras wrapper object.
| node | Will be used to construct image publishers |
| sim_mutex | Provides synchronized access to the mujoco_data object for rendering |
| mujoco_data | MuJoCo data for the simulation |
| mujoco_model | MuJoCo model for the simulation |
| camera_publish_rate | The rate to publish all camera images, for now all images are published at the same rate. |
| void mujoco_ros2_control::MujocoCameras::init | ( | ) |
Starts the image processing thread in the background.
The background thread will initialize its own offscreen glfw context for rendering images that is separate from the Simulate applications, as the context must be in the running thread.