Class MujocoSystemInterface
Defined in File mujoco_system_interface.hpp
Inheritance Relationships
Base Type
public hardware_interface::SystemInterface
Class Documentation
-
class MujocoSystemInterface : public hardware_interface::SystemInterface
Public Functions
-
MujocoSystemInterface()
ros2_control SystemInterface to wrap Mujocos Simulate application.
Supports Actuators, Force Torque/IMU Sensors, and RGB-D camera, and Lidar Sensors in ROS 2 simulations. For more information on configuration refer to the docs, check the comment strings below, and refer to the example in the test folder.
-
~MujocoSystemInterface() override
-
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams ¶ms) override
-
std::vector<hardware_interface::StateInterface> export_state_interfaces() override
-
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override
-
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
-
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override
-
hardware_interface::return_type perform_command_mode_switch(const std::vector<std::string> &start_interfaces, const std::vector<std::string> &stop_interfaces) override
-
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
-
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
-
void get_model(mjModel *&dest)
Returns a copy of the MuJoCo model.
This method locks the simulation mutex to ensure thread safety.
- Parameters:
dest – Pointer to an mjModel structure where the copy will be stored. The pointer will be allocated if it is nullptr.
-
void get_data(mjData *&dest)
Returns a copy of the current MuJoCo data.
This method locks the simulation mutex to ensure thread safety.
- Parameters:
dest – Pointer to an mjData structure where the copy will be stored. The pointer will be allocated if it is nullptr.
-
void set_data(mjData *mj_data)
Sets the MuJoCo data to the provided value.
This method locks the simulation mutex to ensure thread safety.
- Parameters:
mj_data – Pointer to an mjData structure containing the new data.
-
MujocoSystemInterface()