![]() |
ros2_control - humble
|


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::StateInterface > | export_state_interfaces () override |
| Exports all state interfaces for this hardware interface. | |
| std::vector< hardware_interface::CommandInterface > | export_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::HardwareInfo & | get_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_ |
|
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.
| 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.
|
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.
Implements hardware_interface::SystemInterface.
|
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.
Implements hardware_interface::SystemInterface.
| 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.
| dest | Pointer to an mjData structure where the copy will be stored. The pointer will be allocated if it is nullptr. |
| 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.
| dest | Pointer to an mjModel structure where the copy will be stored. The pointer will be allocated if it is nullptr. |
| 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.
|
overridevirtual |
Initialization of the hardware interface from data parsed from the robot's URDF.
| [in] | hardware_info | structure with data from URDF. |
The PIDs config file
Reimplemented from hardware_interface::SystemInterface.
|
overridevirtual |
Perform the mode-switching for the new command interface combination.
| [in] | start_interfaces | vector of string identifiers for the command interfaces starting. |
| [in] | stop_interfaces | vector of string identifiers for the command interfaces stopping. |
Reimplemented from hardware_interface::SystemInterface.
|
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.
| [in] | time | The time at the start of this control loop iteration |
| [in] | period | The measured time taken by the last control loop iteration |
Implements hardware_interface::SystemInterface.
| 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.
| mj_data | Pointer to an mjData structure containing the new data. |
|
overridevirtual |
Write the current command values to the actuator.
The physical hardware shall be updated with the latest value from the exported command interfaces.
| [in] | time | The time at the start of this control loop iteration |
| [in] | period | The measured time taken by the last control loop iteration |
Implements hardware_interface::SystemInterface.