Skip to content

Commit 84bd61b

Browse files
authored
[JTC] Activate update of dynamic parameters (#761) (#838)
1 parent fb5959c commit 84bd61b

File tree

4 files changed

+104
-31
lines changed

4 files changed

+104
-31
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -271,6 +271,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
271271
std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response);
272272

273273
private:
274+
void update_pids();
275+
274276
bool contains_interface_type(
275277
const std::vector<std::string> & interface_type_list, const std::string & interface_type);
276278

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 64 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -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

918900
controller_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+
15501583
void JointTrajectoryController::init_hold_position_msg()
15511584
{
15521585
hold_position_msg_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -414,6 +414,42 @@ TEST_P(TrajectoryControllerTestParameterized, state_topic_consistency)
414414
}
415415
}
416416

417+
/**
418+
* @brief check if dynamic parameters are updated
419+
*/
420+
TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)
421+
{
422+
rclcpp::executors::MultiThreadedExecutor executor;
423+
424+
SetUpAndActivateTrajectoryController(executor);
425+
426+
updateController();
427+
auto pids = traj_controller_->get_pids();
428+
429+
if (traj_controller_->use_closed_loop_pid_adapter())
430+
{
431+
EXPECT_EQ(pids.size(), 3);
432+
auto gain_0 = pids.at(0)->getGains();
433+
EXPECT_EQ(gain_0.p_gain_, 0.0);
434+
435+
double kp = 1.0;
436+
SetPidParameters(kp);
437+
updateController();
438+
439+
pids = traj_controller_->get_pids();
440+
EXPECT_EQ(pids.size(), 3);
441+
gain_0 = pids.at(0)->getGains();
442+
EXPECT_EQ(gain_0.p_gain_, kp);
443+
}
444+
else
445+
{
446+
// nothing to check here, skip further test
447+
EXPECT_EQ(pids.size(), 0);
448+
}
449+
450+
executor.cancel();
451+
}
452+
417453
/**
418454
* @brief check if hold on startup is deactivated
419455
*/

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,8 @@ class TestableJointTrajectoryController
130130

131131
bool is_open_loop() const { return params_.open_loop_control; }
132132

133+
std::vector<PidPtr> get_pids() const { return pids_; }
134+
133135
bool has_active_traj() const { return has_active_trajectory(); }
134136

135137
bool has_trivial_traj() const

0 commit comments

Comments
 (0)