Class MujocoLidar
Defined in File mujoco_lidar.hpp
Class Documentation
-
class MujocoLidar
Wraps Mujoco rangefinder sensors for publishing ROS 2 LaserScan messages.
Public Functions
Constructs a new MujocoLidar wrapper object.
- Parameters:
node – Will be used to construct laserscan publishers
sim_mutex – Provides synchronized access to the mujoco_data object for grabbing rangefinder data
mujoco_data – Mujoco data for the simulation
mujoco_model – Mujoco model for the simulation
lidar_publish_rate – The rate to publish all camera images, for now all images are published at the same rate.
-
void init()
Starts the lidar processing thread in the background.
-
void close()
Stops the lidar processing thread and closes the relevant objects, call before shutdown.
-
bool register_lidar(const hardware_interface::HardwareInfo &hardware_info)
Parses lidar information from the mujoco model.
Returns true if successful, false otherwise.