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>
40#include <mujoco/mujoco.h>
42#include "mujoco_ros2_control/data.hpp"
43#include "mujoco_ros2_control/mujoco_cameras.hpp"
44#include "mujoco_ros2_control/mujoco_lidar.hpp"
45#include "mujoco_ros2_control/mujoco_simulation.hpp"
47#include <pluginlib/class_list_macros.hpp>
48#include <pluginlib/class_loader.hpp>
49#include "mujoco_ros2_control_plugins/mujoco_ros2_control_plugins_base.hpp"
50#include "transmission_interface/transmission.hpp"
51#include "transmission_interface/transmission_interface_exception.hpp"
52#include "transmission_interface/transmission_loader.hpp"
54#define ROS_DISTRO_HUMBLE (HARDWARE_INTERFACE_VERSION_MAJOR < 3)
88 on_init(
const hardware_interface::HardwareComponentInterfaceParams& params)
override;
97 const std::vector<std::string>& stop_interfaces)
override;
99 hardware_interface::return_type
read(
const rclcpp::Time& time,
const rclcpp::Duration& period)
override;
100 hardware_interface::return_type
write(
const rclcpp::Time& time,
const rclcpp::Duration& period)
override;
150 rclcpp::Logger get_logger()
const;
159 bool register_mujoco_actuators();
239 bool set_override_start_positions(
const std::string& override_start_position_file);
244 void set_initial_pose();
256 void reset_simulation_state(
bool fill_initial_state);
262 rclcpp::Node::SharedPtr get_node()
const;
271 void load_mujoco_plugins();
274 rclcpp::Logger logger_ = rclcpp::get_logger(
"MujocoSystemInterface");
278 std::unique_ptr<MujocoSimulation> simulation_;
281 std::shared_ptr<rclcpp::Node> mujoco_node_;
282 std::unique_ptr<rclcpp::executors::MultiThreadedExecutor> executor_;
283 std::thread executor_thread_;
286 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> actuator_state_publisher_ =
nullptr;
289 sensor_msgs::msg::JointState actuator_state_msg_;
292 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> floating_base_publisher_ =
nullptr;
294 nav_msgs::msg::Odometry floating_base_msg_;
297 int free_joint_id_ = -1;
298 int free_joint_qpos_adr_ = -1;
299 int free_joint_qvel_adr_ = -1;
302 std::unique_ptr<MujocoCameras> cameras_;
305 std::unique_ptr<MujocoLidar> lidar_sensors_;
308 std::unordered_map<std::string, hardware_interface::ComponentInfo> joint_hw_info_;
309 std::unordered_map<std::string, hardware_interface::ComponentInfo> sensors_hw_info_;
312 std::vector<MuJoCoActuatorData> mujoco_actuator_data_;
315 std::vector<URDFJointData> urdf_joint_data_;
318 std::unique_ptr<pluginlib::ClassLoader<transmission_interface::TransmissionLoader>> transmission_loader_ =
nullptr;
319 std::vector<std::shared_ptr<transmission_interface::Transmission>> transmission_instances_;
322 std::unique_ptr<pluginlib::ClassLoader<mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase>> plugin_loader_ =
324 std::vector<std::shared_ptr<mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase>> plugin_instances_;
326 std::vector<FTSensorData> ft_sensor_data_;
327 std::vector<IMUSensorData> imu_sensor_data_;
329 bool override_mujoco_actuator_positions_{
false };
330 bool override_urdf_joint_positions_{
false };
332 std::string initial_keyframe_ =
"";
Definition system_interface.hpp:73
Definition mujoco_system_interface.hpp:70
void get_model(mjModel *&dest)
Returns a copy of the MuJoCo model.
Definition mujoco_system_interface.cpp:2039
void set_data(mjData *mj_data)
Sets the MuJoCo data to the provided value.
Definition mujoco_system_interface.cpp:2055
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:1041
void actuator_state_to_joint_state()
Converts actuator states to joint states.
Definition mujoco_system_interface.cpp:1012
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition mujoco_system_interface.cpp:520
std::vector< hardware_interface::CommandInterface > export_command_interfaces() override
Exports all command interfaces for this hardware interface.
Definition mujoco_system_interface.cpp:669
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Write the current command values to the actuator.
Definition mujoco_system_interface.cpp:949
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition mujoco_system_interface.cpp:840
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition mujoco_system_interface.cpp:286
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:726
void get_data(mjData *&dest)
Returns a copy of the current MuJoCo data.
Definition mujoco_system_interface.cpp:2045
Definition mujoco_system_interface.hpp:59
constexpr char HW_IF_TORQUE[]
Constant defining torque interface name.
Definition mujoco_system_interface.hpp:61
constexpr char HW_IF_FORCE[]
Constant defining force interface name.
Definition mujoco_system_interface.hpp:63
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition actuator_interface.hpp:69
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:107