Skip to content

Commit

Permalink
Fix ros2_control resource manager in galatic (ros-controls#96)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <ahcorde@gmail.com>
  • Loading branch information
ahcorde authored and ksotebeer committed Jun 14, 2022
1 parent 5110781 commit f04505a
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -302,7 +302,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
return;
}

resource_manager_->import_component(std::move(gazeboSystem));
resource_manager_->import_component(std::move(gazeboSystem), control_hardware[i]);
}

impl_->executor_ = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def generate_launch_description():
)

load_imu_sensor_broadcaster = ExecuteProcess(
cmd=['ros2', 'control', 'load_start_controller', 'imu_sensor_broadcaster'],
cmd=['ros2', 'control', 'load_controller', 'imu_sensor_broadcaster'],
output='screen'
)

Expand Down

0 comments on commit f04505a

Please sign in to comment.