Skip to content

Commit 123d51f

Browse files
Remove plugin loader
1 parent e030760 commit 123d51f

File tree

2 files changed

+12
-11
lines changed

2 files changed

+12
-11
lines changed

mujoco_ros2_control/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ install(TARGETS
6262
)
6363

6464
# TODO: make it simple
65-
add_executable(mujoco_ros2_control src/mujoco_ros2_control_node.cpp src/mujoco_rendering.cpp src/mujoco_ros2_control.cpp)
65+
add_executable(mujoco_ros2_control src/mujoco_ros2_control_node.cpp src/mujoco_rendering.cpp src/mujoco_ros2_control.cpp src/mujoco_system.cpp src/mujoco_sensor.cpp)
6666
ament_target_dependencies(mujoco_ros2_control ${THIS_PACKAGE_DEPENDS})
6767
target_link_libraries(mujoco_ros2_control ${MUJOCO_LIB} glfw)
6868
target_include_directories(mujoco_ros2_control PUBLIC ${MUJOCO_INCLUDE_DIR} ${EIGEN3_INCLUDE_DIR})

mujoco_ros2_control/src/mujoco_ros2_control.cpp

Lines changed: 11 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,6 @@ class MJResourceManager : public hardware_interface::ResourceManager{
1010
public:
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

8990
private:
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

Comments
 (0)