![]() |
ros2_control - rolling
|


Public Member Functions | |
| MujocoSystemInterface () | |
| ros2_control SystemInterface to wrap Mujocos Simulate application. | |
| hardware_interface::CallbackReturn | on_init (const hardware_interface::HardwareInfo &info) override |
| 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 hardware. | |
| hardware_interface::return_type | write (const rclcpp::Time &time, const rclcpp::Duration &period) override |
| Write the current command values to the hardware. | |
| 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::HardwareComponentInterface | |
| HardwareComponentInterface (const HardwareComponentInterface &other)=delete | |
| HardwareComponentInterface copy constructor is actively deleted. | |
| HardwareComponentInterface (HardwareComponentInterface &&other)=delete | |
| CallbackReturn | init (const hardware_interface::HardwareComponentParams ¶ms) |
| virtual CallbackReturn | init_hardware_status_message (control_msgs::msg::HardwareStatus &msg_template) |
| User-overridable method to configure the structure of the HardwareStatus message. | |
| virtual return_type | update_hardware_status_message (control_msgs::msg::HardwareStatus &msg) |
| User-overridable method to fill the hardware status message with real-time data. | |
| virtual CallbackReturn | on_init (const hardware_interface::HardwareComponentInterfaceParams ¶ms) |
| Initialization of the hardware interface from data parsed from the robot's URDF. | |
| virtual rclcpp::NodeOptions | define_custom_node_options () const |
| Define custom node options for the hardware component interface. | |
| virtual std::vector< hardware_interface::InterfaceDescription > | export_unlisted_state_interface_descriptions () |
| virtual std::vector< StateInterface::ConstSharedPtr > | on_export_state_interfaces () |
| virtual std::vector< hardware_interface::InterfaceDescription > | export_unlisted_command_interface_descriptions () |
| virtual std::vector< CommandInterface::SharedPtr > | on_export_command_interfaces () |
| virtual return_type | prepare_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) |
| Prepare for a new command interface switch. | |
| HardwareComponentCycleStatus | trigger_read (const rclcpp::Time &time, const rclcpp::Duration &period) |
| Triggers the read method synchronously or asynchronously depending on the HardwareInfo. | |
| HardwareComponentCycleStatus | trigger_write (const rclcpp::Time &time, const rclcpp::Duration &period) |
| Triggers the write method synchronously or asynchronously depending on the HardwareInfo. | |
| const std::string & | get_name () const |
| Get name of the hardware. | |
| const std::string & | get_group_name () const |
| Get name of the hardware group to which it belongs to. | |
| const rclcpp_lifecycle::State & | get_lifecycle_state () const |
| Get life-cycle state of the hardware. | |
| void | set_lifecycle_state (const rclcpp_lifecycle::State &new_state) |
| Set life-cycle state of the hardware. | |
| uint8_t | get_lifecycle_id () const |
| Get the lifecycle id of the hardware component interface. | |
| virtual bool | has_state (const std::string &interface_name) const |
| Does the state interface exist? | |
| virtual const StateInterface::SharedPtr & | get_state_interface_handle (const std::string &interface_name) const |
| Get the state interface handle. | |
| template<typename T > | |
| bool | set_state (const StateInterface::SharedPtr &interface_handle, const T &value, bool wait_until_set) |
| Set the value of a state interface. | |
| template<typename T > | |
| void | set_state (const std::string &interface_name, const T &value) |
| Set the value of a state interface. | |
| template<typename T > | |
| bool | get_state (const StateInterface::SharedPtr &interface_handle, T &state, bool wait_until_get) const |
| template<typename T = double> | |
| T | get_state (const std::string &interface_name) const |
| Get the value from a state interface. | |
| virtual bool | has_command (const std::string &interface_name) const |
| Does the command interface exist? | |
| virtual const CommandInterface::SharedPtr & | get_command_interface_handle (const std::string &interface_name) const |
| Get the command interface handle. | |
| template<typename T > | |
| bool | set_command (const CommandInterface::SharedPtr &interface_handle, const T &value, bool wait_until_set) |
| Set the value of a command interface. | |
| template<typename T > | |
| void | set_command (const std::string &interface_name, const T &value) |
| Set the value of a command interface. | |
| template<typename T > | |
| bool | get_command (const CommandInterface::SharedPtr &interface_handle, T &command, bool wait_until_get) const |
| template<typename T = double> | |
| T | get_command (const std::string &interface_name) const |
| Get the value from a command interface. | |
| virtual rclcpp::Clock::SharedPtr | get_clock () const |
| Get the clock. | |
| const HardwareInfo & | get_hardware_info () const |
| Get the hardware info of the HardwareComponentInterface. | |
| void | pause_async_operations () |
| Pause any asynchronous operations. | |
| void | prepare_for_activation () |
| Prepare for the activation of the hardware. | |
| void | enable_introspection (bool enable) |
| Enable or disable introspection of the hardware. | |
Protected Member Functions | |
| rclcpp::Logger | get_logger () const |
| Get the logger of the HardwareComponentInterface. | |
Additional Inherited Members | |
Protected Attributes inherited from hardware_interface::HardwareComponentInterface | |
| HardwareInfo | info_ |
| std::unordered_map< std::string, InterfaceDescription > | joint_state_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | joint_command_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | sensor_state_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | gpio_state_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | gpio_command_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | unlisted_state_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | unlisted_command_interfaces_ |
| rclcpp_lifecycle::State | lifecycle_state_ |
| std::unique_ptr< realtime_tools::AsyncFunctionHandler< return_type > > | async_handler_ |
| std::vector< StateInterface::SharedPtr > | joint_states_ |
| std::vector< CommandInterface::SharedPtr > | joint_commands_ |
| std::vector< StateInterface::SharedPtr > | sensor_states_ |
| std::vector< StateInterface::SharedPtr > | gpio_states_ |
| std::vector< CommandInterface::SharedPtr > | gpio_commands_ |
| std::vector< StateInterface::SharedPtr > | unlisted_states_ |
| std::vector< CommandInterface::SharedPtr > | unlisted_commands_ |
| pal_statistics::RegistrationsRAII | stats_registrations_ |
|
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.
Old way of exporting the CommandInterfaces. If a empty vector is returned then the on_export_command_interfaces() method is called. If a vector with CommandInterfaces is returned then the exporting of the CommandInterfaces is only done with this function and the ownership is transferred to the resource manager. The set_command(...), get_command(...), ..., can then not be used.
Note the ownership over the state interfaces is transferred to the caller.
Reimplemented from hardware_interface::HardwareComponentInterface.
|
overridevirtual |
Exports all state interfaces for this hardware interface.
Old way of exporting the StateInterfaces. If a empty vector is returned then the on_export_state_interfaces() method is called. If a vector with StateInterfaces is returned then the exporting of the StateInterfaces is only done with this function and the ownership is transferred to the resource manager. The set_command(...), get_command(...), ..., can then not be used.
Note the ownership over the state interfaces is transferred to the caller.
Reimplemented from hardware_interface::HardwareComponentInterface.
| 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. |
|
protectedvirtual |
Get the logger of the HardwareComponentInterface.
Reimplemented from hardware_interface::HardwareComponentInterface.
| 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.
|
override |
The PIDs config file
|
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::HardwareComponentInterface.
|
overridevirtual |
Read the current state values from the hardware.
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::HardwareComponentInterface.
| 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 hardware.
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.