ros2_controllers
ros2_controllers copied to clipboard
JointTrajectoryController ignores tolerances sent via action client
Would be nice to have
JointTrajectoryController
ignores goal_time_tolerance
set via FollowJointTrajectory.Goal.goal_time_tolerance together with path_tolerance
and goal_tolerance
.
Potential ROS1 inspiration
Implement something like a ROS1 version updateSegmentTolerances
which is called every time new goal is received through updateTrajectoryCommand
or whenever new trajectory is received.
The parameter propagation is continued on the call of initJointTrajectory
which in the end uses updateSegmentTolerances
here
This is needed to be able to overwrite constraints that are set via parameter server on the jtc start.
It seems that the constraints.goal_time
parameter is also ignored (at least for state position + control position).
I am getting Goal finished with status: SUCCEEDED
even if the joint hasn't reached the position.
ros2 action send_goal /ur_joint_trajectory_controller/follow_joint_trajectory control_msgs/action/FollowJointTrajectory "{
> trajectory: {
> joint_names: [shoulder_pan_joint],
> points: [
> { positions: [3.02], time_from_start: { sec: 0, nanosec: 100 } },
> ]
> },
> goal_tolerance: [
> { name: shoulder_pan_joint, position: 0.00000001 },
> ]
> }"
Waiting for an action server to become available...
Sending goal:
trajectory:
header:
stamp:
sec: 0
nanosec: 0
frame_id: ''
joint_names:
- shoulder_pan_joint
points:
- positions:
- 3.02
velocities: []
accelerations: []
effort: []
time_from_start:
sec: 0
nanosec: 100
path_tolerance: []
goal_tolerance:
- name: shoulder_pan_joint
position: 1.0e-08
velocity: 0.0
acceleration: 0.0
goal_time_tolerance:
sec: 0
nanosec: 0
Goal accepted with ID: 816cd999bcca4225b6f7c027cb64998e
Result:
error_code: 0
error_string: ''
Goal finished with status: SUCCEEDED
This issue should motivate to implement an option to overwrite tolerances that are sent via action goal. This is not implemented yet. For now, if you want to enforce constraints on the state (during trajectory) and on the final (goal) configuration you should set parameters like shown here in UR example.
constraints.goal_time
just makes sure the open-loop control has correct timing on the end of trajectory (e.g. trajectory is executed within the specified time). If it is set to 0, it is ignored. For details see here