ros_controllers icon indicating copy to clipboard operation
ros_controllers copied to clipboard

JointTrajectoryController: setHoldPosition results in unexpected movement when restarting controller

Open lprobsth opened this issue 3 years ago • 1 comments

I'm using ros_controllers in ROS melodic for controlling a robotic arm in position mode with position_controllers/JointTrajectoryController. The Controller works as expected until I switch the controllers (e.g. to velocity controller).

When the JointTrajectoryController is stopped and I switch back from a velocity controller, the TrajectoryController immediately starts moving in direction of the last known Position.

(red = actual position; blue = desired position)

I inspected the TrajectoryController with debugging and can confirm that my hardware interface sets the correct state and that the TrajectoryController uses this state in the Starting function: https://github.com/ros-controls/ros_controllers/blob/95ebe05483f4b2381b343bb76cdec6135b044007/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller_impl.h#L142-L146

I think that setHoldPosition induces the problem - it seems to me that hold_traj_builder_ works and creates a new segment with the current state as the next point in the trajectory. But instead of replacing the current trajectory in the trajectory box with the hold trajectory, the old trajectory with the last known position from when the controller was stopped is kept in place and the new point from the hold trajectory gets placed in the future. https://github.com/ros-controls/ros_controllers/blob/9bbdedd534a456d92f03d1d372bcb6e051dcd4be/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller_impl.h#L738

Then the last known state and the new hold position get interpolated by the sample function. I would have guessed that by resetting the uptime in https://github.com/ros-controls/ros_controllers/blob/9bbdedd534a456d92f03d1d372bcb6e051dcd4be/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller_impl.h#L136-L139 the sample function would immediatly start with the new point from the hold trajectory.

Am I missing something? How can I reinitialize the current trajectory so that the movement starts at the current state when restarting the controller? (possible workaround: unload & reload)

lprobsth avatar Apr 29 '22 08:04 lprobsth

I haven't dug into the code at all on a deep level, but is there any spline fitting going on for setHoldPosition? It could easily cause something like this, even if there's only a tiny position difference.

AndyZe avatar May 03 '23 13:05 AndyZe