Skip to content

Commit

Permalink
Propagate the node clock and logging interface to ResourceManager (#357)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Jul 9, 2024
1 parent 6ebb2e7 commit c5071d9
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,8 @@ class GazeboResourceManager : public hardware_interface::ResourceManager
rclcpp::Node::SharedPtr & node,
gazebo::physics::ModelPtr parent_model,
sdf::ElementPtr sdf)
: hardware_interface::ResourceManager(),
: hardware_interface::ResourceManager(
node->get_node_clock_interface(), node->get_node_logging_interface()),
gazebo_system_loader_("gazebo_ros2_control",
"gazebo_ros2_control::GazeboSystemInterface"),
logger_(node->get_logger().get_child("GazeboResourceManager"))
Expand Down

0 comments on commit c5071d9

Please sign in to comment.