hello-robot / stretch_ros2

ROS 2 packages for the Stretch mobile manipulators from Hello Robot Inc.
https://docs.hello-robot.com/0.2/stretch-tutorials/ros2/
51 stars 19 forks source link

Driver occasionally times out gripper commands #122

Closed hello-binit closed 1 week ago

hello-binit commented 2 weeks ago

This issue was reported by a Stretch user who discovered that gripper commands occasionally fail to execute and are timed-out by the Stretch Driver. This issue is reproducible using:

  1. Launch Stretch Driver on the robot: ros2 launch stretch_core stretch_driver.launch.py
  2. Run the following code: https://gist.github.com/hello-binit/835a8c8e3eedcb287767718efea10d30

The robot will get into a loop where "gripper_aperture" joint commands to 0.091 (half open) will not be executed by the driver.

[INFO] [1714619718.111567529] [manipulation_test]: Sending goal #0 to value: 0.091...
[INFO] [1714619718.114906704] [manipulation_test]: Goal accepted :)
[INFO] [1714619719.315110372] [manipulation_test]: Goal succeeded!
[INFO] [1714619720.316612146] [manipulation_test]: Sending goal #1 to value: -0.11...
[INFO] [1714619720.318799859] [manipulation_test]: Goal accepted :)
[INFO] [1714619721.794949127] [manipulation_test]: Goal succeeded!
[INFO] [1714619722.796420900] [manipulation_test]: Sending goal #2 to value: 0.091...
[INFO] [1714619722.800403375] [manipulation_test]: Goal accepted :)
[INFO] [1714619732.821756318] [manipulation_test]: Goal failed with status: 6
[INFO] [1714619733.822682929] [manipulation_test]: Sending goal #3 to value: -0.11...
[INFO] [1714619733.826351224] [manipulation_test]: Goal accepted :)
[INFO] [1714619733.853851556] [manipulation_test]: Goal succeeded!
[INFO] [1714619734.854604053] [manipulation_test]: Sending goal #4 to value: 0.091...
[INFO] [1714619734.861060654] [manipulation_test]: Goal accepted :)
[INFO] [1714619744.892223613] [manipulation_test]: Goal failed with status: 6
[INFO] [1714619745.894105425] [manipulation_test]: Sending goal #5 to value: -0.11...
[INFO] [1714619745.898412221] [manipulation_test]: Goal accepted :)
[INFO] [1714619745.919710149] [manipulation_test]: Goal succeeded!
[INFO] [1714619746.921398613] [manipulation_test]: Sending goal #6 to value: 0.091...
[INFO] [1714619746.981396613] [manipulation_test]: Goal accepted :)
[INFO] [1714619747.040323452] [manipulation_test]: Goal failed with status: 6

The driver will stall for 10 seconds, after which time it will time out and report that it failed to execute the command.

[stretch_driver-3] [INFO] [1714619722.799725638] [joint_trajectory_action]: Received goal request
[stretch_driver-3] [INFO] [1714619722.802353732] [stretch_driver]: stretch_driver joint_traj action: New trajectory received with joint_names = ['gripper_aperture']
[stretch_driver-3] Errored goal
[stretch_driver-3] [INFO] [1714619732.819012714] [stretch_driver]: stretch_driver joint_traj action: Time to execute the current goal point = <trajectory_msgs.msg.JointTrajectoryPoint(positions=[0.091], velocities=[], accelerations=[], effort=[], time_from_start=builtin_interfaces.msg.Duration(sec=2, nanosec=0))> exceeded the default_goal_timeout = 10.0

[stretch_driver-3] [INFO] [1714619733.825135432] [joint_trajectory_action]: Received goal request
[stretch_driver-3] [INFO] [1714619733.831809619] [stretch_driver]: stretch_driver joint_traj action: New trajectory received with joint_names = ['gripper_aperture']
[stretch_driver-3] Finished goal
[stretch_driver-3] [INFO] [1714619733.851835125] [stretch_driver]: stretch_driver joint_traj action: Achieved all target points.

[stretch_driver-3] [INFO] [1714619734.860520353] [joint_trajectory_action]: Received goal request
[stretch_driver-3] [INFO] [1714619734.864865515] [stretch_driver]: stretch_driver joint_traj action: New trajectory received with joint_names = ['gripper_aperture']
[stretch_driver-3] Errored goal
[stretch_driver-3] [INFO] [1714619744.890495485] [stretch_driver]: stretch_driver joint_traj action: Time to execute the current goal point = <trajectory_msgs.msg.JointTrajectoryPoint(positions=[0.091], velocities=[], accelerations=[], effort=[], time_from_start=builtin_interfaces.msg.Duration(sec=2, nanosec=0))> exceeded the default_goal_timeout = 10.0