Skip to content

Commit

Permalink
propagate gazebo remapping and other arguments to the controller node (
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Aug 23, 2024
1 parent b1b555f commit 3ca3e94
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -359,12 +359,14 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element

// Create the controller manager
RCLCPP_INFO(impl_->model_nh_->get_logger(), "Loading controller_manager");
rclcpp::NodeOptions options = controller_manager::get_cm_node_options();
options.arguments(arguments);
impl_->controller_manager_.reset(
new controller_manager::ControllerManager(
std::move(resource_manager_),
impl_->executor_,
controllerManagerNodeName,
impl_->model_nh_->get_namespace()));
impl_->model_nh_->get_namespace(), options));
impl_->executor_->add_node(impl_->controller_manager_);

auto cm_update_rate = impl_->controller_manager_->get_update_rate();
Expand Down

0 comments on commit 3ca3e94

Please sign in to comment.