-
Notifications
You must be signed in to change notification settings - Fork 463
Description
Describe the bug
PR #716 introduces the concept of active tolerances to the Joint Trajectory Controller, in order to respect the tolerances sent with the action goal. From that point on, the tolerances that were used on the update step of the controller were taken from a RealtimeBuffer. There seems to be just one place where this change wasn't propagated and where the live tolerances are being used.
To Reproduce
Steps to reproduce the behavior:
- Go to
ros2_controllers/joint_trajectory_controller/src/joint_trajectory_controller.cpp
Line 258 in c703235
auto active_tol = active_tolerances_.readFromRT();
This is where the active tolerances for the current update step are read. - Scroll down to
ros2_controllers/joint_trajectory_controller/src/joint_trajectory_controller.cpp
Line 303 in c703235
state_error_, index, default_tolerances_.goal_state_tolerance[index],
This is where the livedefault_tolerances_are still being used, even though all other checks around this useactive_tol
Expected behavior
I would expect this to be
check_state_tolerance_per_joint(
state_error_, index, active_tol->goal_state_tolerance[index],
true /* show_errors */);
Otherwise, it would technically be possible to change the goal state tolerances while the trajectory is being executed, something that the controller is trying to avoid in the current implementation.