@@ -10,7 +10,6 @@ class MJResourceManager : public hardware_interface::ResourceManager{
1010public:
1111 MJResourceManager (rclcpp::Node::SharedPtr& node, mjModel*& mj_model, mjData*& mj_data)
1212 : hardware_interface::ResourceManager(node->get_node_clock_interface (), node->get_node_logging_interface()),
13- mj_system_loader_(" mujoco_ros2_control" , " mujoco_ros2_control::MujocoSystemInterface" ),
1413 logger_(node->get_logger ().get_child(" MJResourceManager" )), mj_model_(mj_model), mj_data_(mj_data)
1514 {
1615 node_ = node;
@@ -62,14 +61,16 @@ class MJResourceManager : public hardware_interface::ResourceManager{
6261 // Load hardware
6362 std::unique_ptr<MujocoSystemInterface> mjSimSystem;
6463 std::scoped_lock guard (resource_interfaces_lock_, claimed_command_interfaces_lock_);
65- try
66- {
67- mjSimSystem = std::unique_ptr<MujocoSystemInterface>(
68- mj_system_loader_.createUnmanagedInstance (robot_hw_sim_type_str_));
69- } catch (pluginlib::PluginlibException & ex) {
70- RCLCPP_ERROR_STREAM (logger_, " The plugin failed to load. Error: " << ex.what ());
71- continue ;
72- }
64+ // try
65+ // {
66+ // mjSimSystem = std::unique_ptr<MujocoSystemInterface>(
67+ // mj_system_loader_.createUnmanagedInstance(robot_hw_sim_type_str_));
68+ // } catch (pluginlib::PluginlibException & ex) {
69+ // RCLCPP_ERROR_STREAM(logger_, "The plugin failed to load. Error: " << ex.what());
70+ // continue;
71+ // }
72+
73+ mjSimSystem.reset (new MujocoSystem ());
7374
7475 // initialize simulation required resource from the hardware info.
7576 urdf::Model urdf_model;
@@ -88,7 +89,7 @@ class MJResourceManager : public hardware_interface::ResourceManager{
8889
8990private:
9091 std::shared_ptr<rclcpp::Node> node_;
91- pluginlib::ClassLoader<MujocoSystemInterface> mj_system_loader_;
92+ // pluginlib::ClassLoader<MujocoSystemInterface> mj_system_loader_;
9293 rclcpp::Logger logger_;
9394 mjModel*& mj_model_;
9495 mjData*& mj_data_;
0 commit comments