@@ -124,6 +124,17 @@ controller_interface::return_type JointTrajectoryController::update(
124124 {
125125 return controller_interface::return_type::OK;
126126 }
127+ // update dynamic parameters
128+ if (param_listener_->is_old (params_))
129+ {
130+ params_ = param_listener_->get_params ();
131+ // use_closed_loop_pid_adapter_ is updated in on_configure only
132+ if (use_closed_loop_pid_adapter_)
133+ {
134+ update_pids ();
135+ default_tolerances_ = get_segment_tolerances (params_);
136+ }
137+ }
127138
128139 auto compute_error_for_joint = [&](
129140 JointTrajectoryPoint & error, size_t index,
@@ -713,15 +724,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
713724 ff_velocity_scale_.resize (dof_);
714725 tmp_command_.resize (dof_, 0.0 );
715726
716- // Init PID gains from ROS parameters
717- for (size_t i = 0 ; i < dof_; ++i)
718- {
719- const auto & gains = params_.gains .joints_map .at (params_.joints [i]);
720- pids_[i] = std::make_shared<control_toolbox::Pid>(
721- gains.p , gains.i , gains.d , gains.i_clamp , -gains.i_clamp );
722-
723- ff_velocity_scale_[i] = gains.ff_velocity_scale ;
724- }
727+ update_pids ();
725728 }
726729
727730 // Configure joint position error normalization from ROS parameters (angle_wraparound)
@@ -805,8 +808,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
805808 get_interface_list (params_.command_interfaces ).c_str (),
806809 get_interface_list (params_.state_interfaces ).c_str ());
807810
808- default_tolerances_ = get_segment_tolerances (params_);
809-
811+ // parse remaining parameters
810812 const std::string interpolation_string =
811813 get_node ()->get_parameter (" interpolation_method" ).as_string ();
812814 interpolation_method_ = interpolation_methods::from_string (interpolation_string);
@@ -892,32 +894,21 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
892894 std::string (get_node ()->get_name ()) + " /query_state" ,
893895 std::bind (&JointTrajectoryController::query_state_service, this , _1, _2));
894896
895- if (params_.cmd_timeout > 0.0 )
896- {
897- if (params_.cmd_timeout > default_tolerances_.goal_time_tolerance )
898- {
899- cmd_timeout_ = params_.cmd_timeout ;
900- }
901- else
902- {
903- // deactivate timeout
904- RCLCPP_WARN (
905- logger, " Command timeout must be higher than goal_time tolerance (%f vs. %f)" ,
906- params_.cmd_timeout , default_tolerances_.goal_time_tolerance );
907- cmd_timeout_ = 0.0 ;
908- }
909- }
910- else
911- {
912- cmd_timeout_ = 0.0 ;
913- }
914-
915897 return CallbackReturn::SUCCESS;
916898}
917899
918900controller_interface::CallbackReturn JointTrajectoryController::on_activate (
919901 const rclcpp_lifecycle::State &)
920902{
903+ // update the dynamic map parameters
904+ param_listener_->refresh_dynamic_parameters ();
905+
906+ // get parameters from the listener in case they were updated
907+ params_ = param_listener_->get_params ();
908+
909+ // parse remaining parameters
910+ default_tolerances_ = get_segment_tolerances (params_);
911+
921912 // order all joints in the storage
922913 for (const auto & interface : params_.command_interfaces )
923914 {
@@ -991,6 +982,28 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
991982 }
992983 rt_is_holding_.writeFromNonRT (true );
993984
985+ // parse timeout parameter
986+ if (params_.cmd_timeout > 0.0 )
987+ {
988+ if (params_.cmd_timeout > default_tolerances_.goal_time_tolerance )
989+ {
990+ cmd_timeout_ = params_.cmd_timeout ;
991+ }
992+ else
993+ {
994+ // deactivate timeout
995+ RCLCPP_WARN (
996+ get_node ()->get_logger (),
997+ " Command timeout must be higher than goal_time tolerance (%f vs. %f)" , params_.cmd_timeout ,
998+ default_tolerances_.goal_time_tolerance );
999+ cmd_timeout_ = 0.0 ;
1000+ }
1001+ }
1002+ else
1003+ {
1004+ cmd_timeout_ = 0.0 ;
1005+ }
1006+
9941007 return CallbackReturn::SUCCESS;
9951008}
9961009
@@ -1547,6 +1560,26 @@ bool JointTrajectoryController::has_active_trajectory() const
15471560 return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg ();
15481561}
15491562
1563+ void JointTrajectoryController::update_pids ()
1564+ {
1565+ for (size_t i = 0 ; i < dof_; ++i)
1566+ {
1567+ const auto & gains = params_.gains .joints_map .at (params_.joints [i]);
1568+ if (pids_[i])
1569+ {
1570+ // update PIDs with gains from ROS parameters
1571+ pids_[i]->setGains (gains.p , gains.i , gains.d , gains.i_clamp , -gains.i_clamp );
1572+ }
1573+ else
1574+ {
1575+ // Init PIDs with gains from ROS parameters
1576+ pids_[i] = std::make_shared<control_toolbox::Pid>(
1577+ gains.p , gains.i , gains.d , gains.i_clamp , -gains.i_clamp );
1578+ }
1579+ ff_velocity_scale_[i] = gains.ff_velocity_scale ;
1580+ }
1581+ }
1582+
15501583void JointTrajectoryController::init_hold_position_msg ()
15511584{
15521585 hold_position_msg_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
0 commit comments