Skip to content

Commit ee6afe3

Browse files
christophfroehlichbmagyar
authored andcommitted
[JTC] Fix dynamic reconfigure of tolerances (backport #849)
* Fix dynamic reconfigure of tolerances * Fix static cast syntax
1 parent 36317e2 commit ee6afe3

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
@@ -128,11 +128,12 @@ controller_interface::return_type JointTrajectoryController::update(
128128
if (param_listener_->is_old(params_))
129129
{
130130
params_ = param_listener_->get_params();
131-
// use_closed_loop_pid_adapter_ is updated in on_configure only
131+
default_tolerances_ = get_segment_tolerances(params_);
132+
// update the PID gains
133+
// variable use_closed_loop_pid_adapter_ is updated in on_configure only
132134
if (use_closed_loop_pid_adapter_)
133135
{
134136
update_pids();
135-
default_tolerances_ = get_segment_tolerances(params_);
136137
}
137138
}
138139

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -449,6 +449,59 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)
449449
executor.cancel();
450450
}
451451

452+
/**
453+
* @brief check if dynamic tolerances are updated
454+
*/
455+
TEST_P(TrajectoryControllerTestParameterized, update_dynamic_tolerances)
456+
{
457+
rclcpp::executors::MultiThreadedExecutor executor;
458+
459+
SetUpAndActivateTrajectoryController(executor);
460+
461+
updateController();
462+
463+
// test default parameters
464+
{
465+
auto tols = traj_controller_->get_tolerances();
466+
EXPECT_EQ(tols.goal_time_tolerance, 0.0);
467+
for (size_t i = 0; i < joint_names_.size(); ++i)
468+
{
469+
EXPECT_EQ(tols.state_tolerance.at(i).position, 0.0);
470+
EXPECT_EQ(tols.goal_state_tolerance.at(i).position, 0.0);
471+
EXPECT_EQ(tols.goal_state_tolerance.at(i).velocity, 0.01);
472+
}
473+
}
474+
475+
// change parameters, update and see what happens
476+
std::vector<rclcpp::Parameter> new_tolerances{
477+
rclcpp::Parameter("constraints.goal_time", 1.0),
478+
rclcpp::Parameter("constraints.stopped_velocity_tolerance", 0.02),
479+
rclcpp::Parameter("constraints.joint1.trajectory", 1.0),
480+
rclcpp::Parameter("constraints.joint2.trajectory", 2.0),
481+
rclcpp::Parameter("constraints.joint3.trajectory", 3.0),
482+
rclcpp::Parameter("constraints.joint1.goal", 10.0),
483+
rclcpp::Parameter("constraints.joint2.goal", 20.0),
484+
rclcpp::Parameter("constraints.joint3.goal", 30.0)};
485+
for (const auto & param : new_tolerances)
486+
{
487+
traj_controller_->get_node()->set_parameter(param);
488+
}
489+
updateController();
490+
491+
{
492+
auto tols = traj_controller_->get_tolerances();
493+
EXPECT_EQ(tols.goal_time_tolerance, 1.0);
494+
for (size_t i = 0; i < joint_names_.size(); ++i)
495+
{
496+
EXPECT_EQ(tols.state_tolerance.at(i).position, static_cast<double>(i) + 1.0);
497+
EXPECT_EQ(tols.goal_state_tolerance.at(i).position, 10.0 * (static_cast<double>(i) + 1.0));
498+
EXPECT_EQ(tols.goal_state_tolerance.at(i).velocity, 0.02);
499+
}
500+
}
501+
502+
executor.cancel();
503+
}
504+
452505
/**
453506
* @brief check if hold on startup is deactivated
454507
*/

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)