The problem arises because, when movegroup
is sending out the JointTrajectoryAction/goal
msg to a foo arm_controller
, the 'tolerance' msg fields are empty, resulting a GOAL_TOLREANCE_VIOLATED.
I also tried to spent some time on solving this issue, after digging into joint_trajectory_controller
in ros_controller, i found that the param is being retrieved here: tolerances.h.
To solve this, changes need to be made on the controller.yaml for gazebo controller. For my case, I am using a velocity_controllers
here, thus changing stopped_velocity_tolerance
from a number to 0 solved this.
arm_controller:
type: velocity_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
# vel_tolerance is 0 for due to the movegroup/follow_joint_trajectory/goal tolerance is empty
stopped_velocity_tolerance: 0
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
elbow_joint: {trajectory: 0.1, goal: 0.1}
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
gains:
shoulder_pan_joint: {p: 100, d: 1, i: 1, i_clamp: 1}
shoulder_lift_joint: {p: 100, d: 1, i: 1, i_clamp: 1}
elbow_joint: {p: 100, d: 1, i: 1, i_clamp: 1}
wrist_1_joint: {p: 100, d: 1, i: 1, i_clamp: 1}
wrist_2_joint: {p: 100, d: 1, i: 1, i_clamp: 1}
wrist_3_joint: {p: 100, d: 1, i: 1, i_clamp: 1}
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
After this change, i managed to receive SUCCESS
. Similarly, If you are using a position_controllers
, I believe the goal
for each joint need to be changed to 0. Hopefully this works for you.
Did you find a solution to GOAL_TOLERANCE_VIOLATED ?