Class MujocoCameras
Defined in File mujoco_cameras.hpp
Class Documentation
-
class MujocoCameras
Wraps MuJoCo cameras for publishing ROS 2 RGB-D streams.
Public Types
-
using GlfwInitFn = std::function<int()>
Signature of the GLFW initializer; injectable for testing.
Public Functions
Constructs a new MujocoCameras wrapper object.
- Parameters:
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 init(GlfwInitFn glfw_init_fn = glfwInit)
Starts the image processing thread in the background.
Does nothing when no cameras have been registered. The background thread will initialize its own offscreen GLFW context for rendering images that is separate from the Simulate application, as the context must be created in the running thread.
- Parameters:
glfw_init_fn – Callable used to initialize GLFW; defaults to ::glfwInit. Override in tests to simulate a display-capable environment without a real GPU.
-
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.
-
using GlfwInitFn = std::function<int()>