ros2_control - humble
Loading...
Searching...
No Matches
Public Member Functions | List of all members
mujoco_ros2_control::MujocoLidar Class Reference

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.
 

Detailed Description

Wraps MuJoCo rangefinder sensors for publishing ROS 2 LaserScan messages.

Constructor & Destructor Documentation

◆ MujocoLidar()

mujoco_ros2_control::MujocoLidar::MujocoLidar ( rclcpp::Node::SharedPtr  node,
std::recursive_mutex *  sim_mutex,
mjData *  mujoco_data,
mjModel *  mujoco_model,
double  lidar_publish_rate 
)
explicit

Constructs a new MujocoLidar wrapper object.

Parameters
nodeWill be used to construct laserscan publishers
sim_mutexProvides synchronized access to the mujoco_data object for grabbing rangefinder data
mujoco_dataMuJoCo data for the simulation
mujoco_modelMuJoCo model for the simulation
lidar_publish_rateThe rate to publish all camera images, for now all images are published at the same rate.

Member Function Documentation

◆ register_lidar()

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.


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