@@ -115,6 +115,17 @@ controller_interface::return_type JointTrajectoryController::update(
115115 {
116116 return controller_interface::return_type::OK;
117117 }
118+ // update dynamic parameters
119+ if (param_listener_->is_old (params_))
120+ {
121+ params_ = param_listener_->get_params ();
122+ // use_closed_loop_pid_adapter_ is updated in on_configure only
123+ if (use_closed_loop_pid_adapter_)
124+ {
125+ update_pids ();
126+ default_tolerances_ = get_segment_tolerances (params_);
127+ }
128+ }
118129
119130 auto compute_error_for_joint = [&](
120131 JointTrajectoryPoint & error, size_t index,
@@ -704,15 +715,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
704715 ff_velocity_scale_.resize (dof_);
705716 tmp_command_.resize (dof_, 0.0 );
706717
707- // Init PID gains from ROS parameters
708- for (size_t i = 0 ; i < dof_; ++i)
709- {
710- const auto & gains = params_.gains .joints_map .at (params_.joints [i]);
711- pids_[i] = std::make_shared<control_toolbox::Pid>(
712- gains.p , gains.i , gains.d , gains.i_clamp , -gains.i_clamp );
713-
714- ff_velocity_scale_[i] = gains.ff_velocity_scale ;
715- }
718+ update_pids ();
716719 }
717720
718721 // Configure joint position error normalization from ROS parameters (angle_wraparound)
@@ -787,8 +790,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
787790 get_interface_list (params_.command_interfaces ).c_str (),
788791 get_interface_list (params_.state_interfaces ).c_str ());
789792
790- default_tolerances_ = get_segment_tolerances (params_);
791-
793+ // parse remaining parameters
792794 const std::string interpolation_string =
793795 get_node ()->get_parameter (" interpolation_method" ).as_string ();
794796 interpolation_method_ = interpolation_methods::from_string (interpolation_string);
@@ -874,32 +876,21 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
874876 std::string (get_node ()->get_name ()) + " /query_state" ,
875877 std::bind (&JointTrajectoryController::query_state_service, this , _1, _2));
876878
877- if (params_.cmd_timeout > 0.0 )
878- {
879- if (params_.cmd_timeout > default_tolerances_.goal_time_tolerance )
880- {
881- cmd_timeout_ = params_.cmd_timeout ;
882- }
883- else
884- {
885- // deactivate timeout
886- RCLCPP_WARN (
887- logger, " Command timeout must be higher than goal_time tolerance (%f vs. %f)" ,
888- params_.cmd_timeout , default_tolerances_.goal_time_tolerance );
889- cmd_timeout_ = 0.0 ;
890- }
891- }
892- else
893- {
894- cmd_timeout_ = 0.0 ;
895- }
896-
897879 return CallbackReturn::SUCCESS;
898880}
899881
900882controller_interface::CallbackReturn JointTrajectoryController::on_activate (
901883 const rclcpp_lifecycle::State &)
902884{
885+ // update the dynamic map parameters
886+ param_listener_->refresh_dynamic_parameters ();
887+
888+ // get parameters from the listener in case they were updated
889+ params_ = param_listener_->get_params ();
890+
891+ // parse remaining parameters
892+ default_tolerances_ = get_segment_tolerances (params_);
893+
903894 // order all joints in the storage
904895 for (const auto & interface : params_.command_interfaces )
905896 {
@@ -974,6 +965,28 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
974965 }
975966 rt_is_holding_.writeFromNonRT (true );
976967
968+ // parse timeout parameter
969+ if (params_.cmd_timeout > 0.0 )
970+ {
971+ if (params_.cmd_timeout > default_tolerances_.goal_time_tolerance )
972+ {
973+ cmd_timeout_ = params_.cmd_timeout ;
974+ }
975+ else
976+ {
977+ // deactivate timeout
978+ RCLCPP_WARN (
979+ get_node ()->get_logger (),
980+ " Command timeout must be higher than goal_time tolerance (%f vs. %f)" , params_.cmd_timeout ,
981+ default_tolerances_.goal_time_tolerance );
982+ cmd_timeout_ = 0.0 ;
983+ }
984+ }
985+ else
986+ {
987+ cmd_timeout_ = 0.0 ;
988+ }
989+
977990 return CallbackReturn::SUCCESS;
978991}
979992
@@ -1530,6 +1543,26 @@ bool JointTrajectoryController::has_active_trajectory() const
15301543 return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg ();
15311544}
15321545
1546+ void JointTrajectoryController::update_pids ()
1547+ {
1548+ for (size_t i = 0 ; i < dof_; ++i)
1549+ {
1550+ const auto & gains = params_.gains .joints_map .at (params_.joints [i]);
1551+ if (pids_[i])
1552+ {
1553+ // update PIDs with gains from ROS parameters
1554+ pids_[i]->setGains (gains.p , gains.i , gains.d , gains.i_clamp , -gains.i_clamp );
1555+ }
1556+ else
1557+ {
1558+ // Init PIDs with gains from ROS parameters
1559+ pids_[i] = std::make_shared<control_toolbox::Pid>(
1560+ gains.p , gains.i , gains.d , gains.i_clamp , -gains.i_clamp );
1561+ }
1562+ ff_velocity_scale_[i] = gains.ff_velocity_scale ;
1563+ }
1564+ }
1565+
15331566void JointTrajectoryController::init_hold_position_msg ()
15341567{
15351568 hold_position_msg_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
0 commit comments