ros2_control - rolling
Loading...
Searching...
No Matches
mujoco_system_interface.hpp
1
20#pragma once
21
22#include <memory>
23#include <string>
24#include <thread>
25#include <vector>
26
27#include <hardware_interface/version.h>
28#include <hardware_interface/handle.hpp>
29#include <hardware_interface/hardware_info.hpp>
30#include <hardware_interface/system_interface.hpp>
31#include <hardware_interface/types/hardware_interface_return_values.hpp>
32#include <nav_msgs/msg/odometry.hpp>
33#include <rclcpp/macros.hpp>
34#include <rclcpp/rclcpp.hpp>
35#include <rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp>
36#include <rclcpp_lifecycle/state.hpp>
37#include <realtime_tools/realtime_publisher.hpp>
38#include <sensor_msgs/msg/joint_state.hpp>
39
40#include <mujoco/mujoco.h>
41
42#include "mujoco_ros2_control/data.hpp"
43#include "mujoco_ros2_control/mujoco_simulation.hpp"
44
45#include <pluginlib/class_list_macros.hpp>
46#include <pluginlib/class_loader.hpp>
47#include "mujoco_ros2_control_plugins/mujoco_ros2_control_plugins_base.hpp"
48#include "transmission_interface/transmission.hpp"
49#include "transmission_interface/transmission_interface_exception.hpp"
50#include "transmission_interface/transmission_loader.hpp"
51
52#define ROS_DISTRO_HUMBLE (HARDWARE_INTERFACE_VERSION_MAJOR < 3)
53
54// defining these for Humble, because they are defined elsewhere in future versions, and we use them in this file
55#if ROS_DISTRO_HUMBLE
57{
59constexpr char HW_IF_TORQUE[] = "torque";
61constexpr char HW_IF_FORCE[] = "force";
62} // namespace hardware_interface
63#endif
64
65namespace mujoco_ros2_control
66{
68{
69public:
78 ~MujocoSystemInterface() override;
79
80 hardware_interface::CallbackReturn
81// Jazzy introduces a new HarwareComponentInterfaceParams object which doesn't exist in humble. This adds
82// compatibility by switching to the old interface, which behaves similarly
83#if ROS_DISTRO_HUMBLE
84 on_init(const hardware_interface::HardwareInfo& info) override;
85#else
87#endif
88 std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
89 std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
90
91 hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
92 hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
93
94 hardware_interface::return_type perform_command_mode_switch(const std::vector<std::string>& start_interfaces,
95 const std::vector<std::string>& stop_interfaces) override;
96
97 hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;
98 hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) override;
99
100// In humble this method doesn't exist, so we just add it back in with the implementation
101#if ROS_DISTRO_HUMBLE
102 const hardware_interface::HardwareInfo& get_hardware_info() const
103 {
104 return info_;
105 }
106#endif
114
122
129 void get_model(mjModel*& dest);
130
137 void get_data(mjData*& dest);
138
145 void set_data(mjData* mj_data);
146
147protected:
148 rclcpp::Logger get_logger() const;
149
150private:
157 bool register_mujoco_actuators();
158
166 void register_urdf_joints(const hardware_interface::HardwareInfo& info);
167
175 bool register_transmissions(const hardware_interface::HardwareInfo& info);
176
177 bool initialize_initial_positions(const hardware_interface::HardwareInfo& info);
178
229 void register_sensors(const hardware_interface::HardwareInfo& info);
230
237 bool set_override_start_positions(const std::string& override_start_position_file);
238
242 void set_initial_pose();
243
254 void reset_simulation_state(bool fill_initial_state);
255
257
260 rclcpp::Node::SharedPtr get_node() const;
261
263
269 void load_mujoco_plugins();
270
280 bool auto_register_plugin_if_needed(const std::string& plugin_type, const std::string& plugin_ns,
281 const std::vector<std::string>& loaded_plugins);
282 void load_legacy_cameras(const std::vector<std::string>& plugins_ns);
283 void load_legacy_lidar(const std::vector<std::string>& plugins_ns);
284
285 // Logger
286 rclcpp::Logger logger_ = rclcpp::get_logger("MujocoSystemInterface");
287
288 // The simulation host: owns the Simulate app, model/data, physics & UI threads,
289 // clock publisher, and reset/pause/step services.
290 std::unique_ptr<MujocoSimulation> simulation_;
291
292 // Provides access to ROS interfaces for elements that require it
293 std::shared_ptr<rclcpp::Node> mujoco_node_;
294 std::unique_ptr<rclcpp::executors::MultiThreadedExecutor> executor_;
295 std::thread executor_thread_;
296
297 // Actuators state publisher
298 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> actuator_state_publisher_ = nullptr;
300 nullptr;
301 sensor_msgs::msg::JointState actuator_state_msg_;
302
303 // Floating base state publisher
304 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> floating_base_publisher_ = nullptr;
305 realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>::SharedPtr floating_base_realtime_publisher_ = nullptr;
306 nav_msgs::msg::Odometry floating_base_msg_;
307
308 // Free joint data
309 int free_joint_id_ = -1;
310 int free_joint_qpos_adr_ = -1;
311 int free_joint_qvel_adr_ = -1;
312
313 // Data containers for the HW interface
314 std::unordered_map<std::string, hardware_interface::ComponentInfo> joint_hw_info_;
315 std::unordered_map<std::string, hardware_interface::ComponentInfo> sensors_hw_info_;
316
317 // Container for interacting with the underlying physics sim's data. This will be used to copy physics data
318 // during `read` and to apply control inputs during `write`.
319 mjData* mj_data_control_{ nullptr };
320
321 // Data containers for the MuJoCo Actuators
322 std::vector<MuJoCoActuatorData> mujoco_actuator_data_;
323
324 // Data containers for the URDF joints
325 std::vector<URDFJointData> urdf_joint_data_;
326
327 // Transmission instances
328 std::unique_ptr<pluginlib::ClassLoader<transmission_interface::TransmissionLoader>> transmission_loader_ = nullptr;
329 std::vector<std::shared_ptr<transmission_interface::Transmission>> transmission_instances_;
330
331 // Plugin loader and instances
332 std::unique_ptr<pluginlib::ClassLoader<mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase>> plugin_loader_ =
333 nullptr;
334 std::vector<std::shared_ptr<mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase>> plugin_instances_;
335
336 std::vector<FTSensorData> ft_sensor_data_;
337 std::vector<IMUSensorData> imu_sensor_data_;
338
339 bool override_mujoco_actuator_positions_{ false };
340 bool override_urdf_joint_positions_{ false };
341
342 std::string initial_keyframe_ = "";
343};
344
345} // namespace mujoco_ros2_control
Virtual Class to implement when integrating a complex system into ros2_control.
Definition system_interface.hpp:67
Definition mujoco_system_interface.hpp:68
void get_model(mjModel *&dest)
Returns a copy of the MuJoCo model.
Definition mujoco_system_interface.cpp:2009
void set_data(mjData *mj_data)
Sets the MuJoCo data to the provided value.
Definition mujoco_system_interface.cpp:2019
MujocoSystemInterface()
ros2_control SystemInterface to wrap Mujocos Simulate application.
void joint_command_to_actuator_command()
Converts joint commands to actuator commands.
Definition mujoco_system_interface.cpp:1008
void actuator_state_to_joint_state()
Converts actuator states to joint states.
Definition mujoco_system_interface.cpp:979
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition mujoco_system_interface.cpp:492
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this hardware interface.
Definition mujoco_system_interface.cpp:641
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Write the current command values to the hardware.
Definition mujoco_system_interface.cpp:904
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the hardware.
Definition mujoco_system_interface.cpp:808
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override
Definition mujoco_system_interface.cpp:281
rclcpp::Logger get_logger() const
Get the logger of the HardwareComponentInterface.
Definition mujoco_system_interface.cpp:2024
hardware_interface::return_type perform_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Definition mujoco_system_interface.cpp:694
void get_data(mjData *&dest)
Returns a copy of the current MuJoCo data.
Definition mujoco_system_interface.cpp:2014
Definition realtime_publisher.hpp:55
Definition mujoco_system_interface.hpp:57
constexpr char HW_IF_FORCE[]
Constant defining force interface name.
Definition mujoco_system_interface.hpp:61
constexpr char HW_IF_TORQUE[]
Constant defining torque interface name.
Definition mujoco_system_interface.hpp:59
Definition data.hpp:31
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_interface_params.hpp:32
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:370