![]() |
ros2_control - humble
|
Wraps MuJoCo rangefinder sensors for publishing ROS 2 LaserScan messages. More...
#include <mujoco_lidar.hpp>
Public Member Functions | |
| MujocoLidar (rclcpp::Node::SharedPtr node, std::recursive_mutex *sim_mutex, mjData *mujoco_data, mjModel *mujoco_model, double lidar_publish_rate) | |
| Constructs a new MujocoLidar wrapper object. | |
| 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. | |
Wraps MuJoCo rangefinder sensors for publishing ROS 2 LaserScan messages.
|
explicit |
Constructs a new MujocoLidar wrapper object.
| 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. |
| bool mujoco_ros2_control::MujocoLidar::register_lidar | ( | const hardware_interface::HardwareInfo & | hardware_info | ) |
Parses lidar information from the mujoco model.
Returns true if successful, false otherwise.