Skip to content

Commit d5dd094

Browse files
christophfroehlichbmagyar
authored andcommitted
[JTC] Fix dynamic reconfigure of tolerances (backport ros-controls#849)
* Fix dynamic reconfigure of tolerances * Fix static cast syntax
1 parent a04a926 commit d5dd094

File tree

3 files changed

+61
-2
lines changed

3 files changed

+61
-2
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -131,11 +131,12 @@ controller_interface::return_type JointTrajectoryController::update(
131131
if (param_listener_->is_old(params_))
132132
{
133133
params_ = param_listener_->get_params();
134-
// use_closed_loop_pid_adapter_ is updated in on_configure only
134+
default_tolerances_ = get_segment_tolerances(params_);
135+
// update the PID gains
136+
// variable use_closed_loop_pid_adapter_ is updated in on_configure only
135137
if (use_closed_loop_pid_adapter_)
136138
{
137139
update_pids();
138-
default_tolerances_ = get_segment_tolerances(params_);
139140
}
140141
}
141142

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -501,6 +501,59 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)
501501
executor.cancel();
502502
}
503503

504+
/**
505+
* @brief check if dynamic tolerances are updated
506+
*/
507+
TEST_P(TrajectoryControllerTestParameterized, update_dynamic_tolerances)
508+
{
509+
rclcpp::executors::MultiThreadedExecutor executor;
510+
511+
SetUpAndActivateTrajectoryController(executor);
512+
513+
updateController();
514+
515+
// test default parameters
516+
{
517+
auto tols = traj_controller_->get_tolerances();
518+
EXPECT_EQ(tols.goal_time_tolerance, 0.0);
519+
for (size_t i = 0; i < joint_names_.size(); ++i)
520+
{
521+
EXPECT_EQ(tols.state_tolerance.at(i).position, 0.0);
522+
EXPECT_EQ(tols.goal_state_tolerance.at(i).position, 0.0);
523+
EXPECT_EQ(tols.goal_state_tolerance.at(i).velocity, 0.01);
524+
}
525+
}
526+
527+
// change parameters, update and see what happens
528+
std::vector<rclcpp::Parameter> new_tolerances{
529+
rclcpp::Parameter("constraints.goal_time", 1.0),
530+
rclcpp::Parameter("constraints.stopped_velocity_tolerance", 0.02),
531+
rclcpp::Parameter("constraints.joint1.trajectory", 1.0),
532+
rclcpp::Parameter("constraints.joint2.trajectory", 2.0),
533+
rclcpp::Parameter("constraints.joint3.trajectory", 3.0),
534+
rclcpp::Parameter("constraints.joint1.goal", 10.0),
535+
rclcpp::Parameter("constraints.joint2.goal", 20.0),
536+
rclcpp::Parameter("constraints.joint3.goal", 30.0)};
537+
for (const auto & param : new_tolerances)
538+
{
539+
traj_controller_->get_node()->set_parameter(param);
540+
}
541+
updateController();
542+
543+
{
544+
auto tols = traj_controller_->get_tolerances();
545+
EXPECT_EQ(tols.goal_time_tolerance, 1.0);
546+
for (size_t i = 0; i < joint_names_.size(); ++i)
547+
{
548+
EXPECT_EQ(tols.state_tolerance.at(i).position, static_cast<double>(i) + 1.0);
549+
EXPECT_EQ(tols.goal_state_tolerance.at(i).position, 10.0 * (static_cast<double>(i) + 1.0));
550+
EXPECT_EQ(tols.goal_state_tolerance.at(i).velocity, 0.02);
551+
}
552+
}
553+
554+
executor.cancel();
555+
}
556+
504557
/**
505558
* @brief check if hold on startup is deactivated
506559
*/

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -132,6 +132,11 @@ class TestableJointTrajectoryController
132132

133133
std::vector<PidPtr> get_pids() const { return pids_; }
134134

135+
joint_trajectory_controller::SegmentTolerances get_tolerances() const
136+
{
137+
return default_tolerances_;
138+
}
139+
135140
bool has_active_traj() const { return has_active_trajectory(); }
136141

137142
bool has_trivial_traj() const

0 commit comments

Comments
 (0)