80 hardware_interface::CallbackReturn
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;
95 const std::vector<std::string>& stop_interfaces)
override;
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;
157 bool register_mujoco_actuators();
237 bool set_override_start_positions(
const std::string& override_start_position_file);
242 void set_initial_pose();
254 void reset_simulation_state(
bool fill_initial_state);
260 rclcpp::Node::SharedPtr get_node()
const;
269 void load_mujoco_plugins();
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);
286 rclcpp::Logger logger_ = rclcpp::get_logger(
"MujocoSystemInterface");
290 std::unique_ptr<MujocoSimulation> simulation_;
293 std::shared_ptr<rclcpp::Node> mujoco_node_;
294 std::unique_ptr<rclcpp::executors::MultiThreadedExecutor> executor_;
295 std::thread executor_thread_;
298 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> actuator_state_publisher_ =
nullptr;
301 sensor_msgs::msg::JointState actuator_state_msg_;
304 std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> floating_base_publisher_ =
nullptr;
306 nav_msgs::msg::Odometry floating_base_msg_;
309 int free_joint_id_ = -1;
310 int free_joint_qpos_adr_ = -1;
311 int free_joint_qvel_adr_ = -1;
314 std::unordered_map<std::string, hardware_interface::ComponentInfo> joint_hw_info_;
315 std::unordered_map<std::string, hardware_interface::ComponentInfo> sensors_hw_info_;
319 mjData* mj_data_control_{
nullptr };
322 std::vector<MuJoCoActuatorData> mujoco_actuator_data_;
325 std::vector<URDFJointData> urdf_joint_data_;
328 std::unique_ptr<pluginlib::ClassLoader<transmission_interface::TransmissionLoader>> transmission_loader_ =
nullptr;
329 std::vector<std::shared_ptr<transmission_interface::Transmission>> transmission_instances_;
332 std::unique_ptr<pluginlib::ClassLoader<mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase>> plugin_loader_ =
334 std::vector<std::shared_ptr<mujoco_ros2_control_plugins::MuJoCoROS2ControlPluginBase>> plugin_instances_;
336 std::vector<FTSensorData> ft_sensor_data_;
337 std::vector<IMUSensorData> imu_sensor_data_;
339 bool override_mujoco_actuator_positions_{
false };
340 bool override_urdf_joint_positions_{
false };
342 std::string initial_keyframe_ =
"";