ros2_control - humble
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | List of all members
mujoco_ros2_control::MujocoSystemInterface Class Reference
Inheritance diagram for mujoco_ros2_control::MujocoSystemInterface:
Inheritance graph
[legend]
Collaboration diagram for mujoco_ros2_control::MujocoSystemInterface:
Collaboration graph
[legend]

Public Member Functions

 MujocoSystemInterface ()
 ros2_control SystemInterface to wrap Mujocos Simulate application.
 
hardware_interface::CallbackReturn on_init (const hardware_interface::HardwareInfo &info) override
 Initialization of the hardware interface from data parsed from the robot's URDF.
 
std::vector< hardware_interface::StateInterfaceexport_state_interfaces () override
 Exports all state interfaces for this hardware interface.
 
std::vector< hardware_interface::CommandInterfaceexport_command_interfaces () override
 Exports all command interfaces for this hardware interface.
 
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
 Read the current state values from the actuator.
 
hardware_interface::return_type write (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Write the current command values to the actuator.
 
const hardware_interface::HardwareInfoget_hardware_info () const
 
void actuator_state_to_joint_state ()
 Converts actuator states to joint states.
 
void joint_command_to_actuator_command ()
 Converts joint commands to actuator commands.
 
void get_model (mjModel *&dest)
 Returns a copy of the MuJoCo model.
 
void get_data (mjData *&dest)
 Returns a copy of the current MuJoCo data.
 
void set_data (mjData *mj_data)
 Sets the MuJoCo data to the provided value.
 
- Public Member Functions inherited from hardware_interface::SystemInterface
 SystemInterface (const SystemInterface &other)=delete
 SystemInterface copy constructor is actively deleted.
 
 SystemInterface (SystemInterface &&other)=default
 
virtual return_type prepare_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &)
 Prepare for a new command interface switch.
 
virtual std::string get_name () const
 Get name of the actuator hardware.
 
const rclcpp_lifecycle::State & get_state () const
 Get life-cycle state of the actuator hardware.
 
void set_state (const rclcpp_lifecycle::State &new_state)
 Set life-cycle state of the actuator hardware.
 

Protected Member Functions

rclcpp::Logger get_logger () const
 

Additional Inherited Members

- Protected Attributes inherited from hardware_interface::SystemInterface
HardwareInfo info_
 
rclcpp_lifecycle::State lifecycle_state_
 

Constructor & Destructor Documentation

◆ MujocoSystemInterface()

mujoco_ros2_control::MujocoSystemInterface::MujocoSystemInterface ( )
default

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.

Member Function Documentation

◆ actuator_state_to_joint_state()

void mujoco_ros2_control::MujocoSystemInterface::actuator_state_to_joint_state ( )

Converts actuator states to joint states.

This method reads the current states of the actuators in the MuJoCo simulation and updates the corresponding joint states in the ROS 2 control interface either through transmissions or directly.

◆ export_command_interfaces()

std::vector< hardware_interface::CommandInterface > mujoco_ros2_control::MujocoSystemInterface::export_command_interfaces ( )
overridevirtual

Exports all command interfaces for this hardware interface.

The command interfaces have to be created and transferred according to the hardware info passed in for the configuration.

Note the ownership over the state interfaces is transferred to the caller.

Returns
vector of command interfaces

Implements hardware_interface::SystemInterface.

◆ export_state_interfaces()

std::vector< hardware_interface::StateInterface > mujoco_ros2_control::MujocoSystemInterface::export_state_interfaces ( )
overridevirtual

Exports all state interfaces for this hardware interface.

The state interfaces have to be created and transferred according to the hardware info passed in for the configuration.

Note the ownership over the state interfaces is transferred to the caller.

Returns
vector of state interfaces

Implements hardware_interface::SystemInterface.

◆ get_data()

void mujoco_ros2_control::MujocoSystemInterface::get_data ( mjData *&  dest)

Returns a copy of the current MuJoCo data.

This method locks the simulation mutex to ensure thread safety.

Parameters
destPointer to an mjData structure where the copy will be stored. The pointer will be allocated if it is nullptr.

◆ get_model()

void mujoco_ros2_control::MujocoSystemInterface::get_model ( mjModel *&  dest)

Returns a copy of the MuJoCo model.

This method locks the simulation mutex to ensure thread safety.

Parameters
destPointer to an mjModel structure where the copy will be stored. The pointer will be allocated if it is nullptr.

◆ joint_command_to_actuator_command()

void mujoco_ros2_control::MujocoSystemInterface::joint_command_to_actuator_command ( )

Converts joint commands to actuator commands.

This method takes the command inputs for the joints from the ROS 2 control interface and translates them into appropriate commands for the actuators in the MuJoCo simulation, considering any loaded transmissions or directly.

◆ on_init()

hardware_interface::CallbackReturn mujoco_ros2_control::MujocoSystemInterface::on_init ( const hardware_interface::HardwareInfo hardware_info)
overridevirtual

Initialization of the hardware interface from data parsed from the robot's URDF.

Parameters
[in]hardware_infostructure with data from URDF.
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

The PIDs config file

Reimplemented from hardware_interface::SystemInterface.

◆ perform_command_mode_switch()

hardware_interface::return_type mujoco_ros2_control::MujocoSystemInterface::perform_command_mode_switch ( const std::vector< std::string > &  ,
const std::vector< std::string > &   
)
overridevirtual

Perform the mode-switching for the new command interface combination.

Note
This is part of the realtime update loop, and should be fast.
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
Parameters
[in]start_interfacesvector of string identifiers for the command interfaces starting.
[in]stop_interfacesvector of string identifiers for the command interfaces stopping.
Returns
return_type::OK if the new command interface combination can be switched to, or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.

Reimplemented from hardware_interface::SystemInterface.

◆ read()

hardware_interface::return_type mujoco_ros2_control::MujocoSystemInterface::read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Read the current state values from the actuator.

The data readings from the physical hardware has to be updated and reflected accordingly in the exported state interfaces. That is, the data pointed by the interfaces shall be updated.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implements hardware_interface::SystemInterface.

◆ set_data()

void mujoco_ros2_control::MujocoSystemInterface::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_dataPointer to an mjData structure containing the new data.

◆ write()

hardware_interface::return_type mujoco_ros2_control::MujocoSystemInterface::write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

Write the current command values to the actuator.

The physical hardware shall be updated with the latest value from the exported command interfaces.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implements hardware_interface::SystemInterface.


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