Closed Adrian2702 closed 1 week ago
I assume that this is the problem:
MoveGroupInterface::execute() failed or timeout reached
If that's the case, it's probably not that the controller doesn't use the scaling from the teach pendant, but the MoveIt trajectory execution monitoring. Could you try #1132 fixes that problem for you?
Edit: No, you can't directly, as you use Humble. I'll provide a PR for Humble, as well, as this is going to be different...
Edit 2: Could you please try #1133
Thank you very much for your quick reply. I have added the following lines in the moveit_controllers.yaml
file from the package ur_moveit_config
as you described in #1132:
trajectory_execution:
allowed_execution_duration_scaling: 1.2
allowed_goal_duration_margin: 0.5
allowed_start_tolerance: 0.01
execution_duration_monitoring: false # Not much use when using the scaled JTC
I have tested it with the UR10e robot. It works like a charm. Both under humble and jazzy.
Affected ROS2 Driver version(s)
Humble
Used ROS distribution.
Humble
Which combination of platform is the ROS driver running on.
Ubuntu Linux with standard kernel
How is the UR ROS2 Driver installed.
Build both the ROS driver and UR Client Library from source
Which robot platform is the driver connected to.
UR E-series robot
Robot SW / URSim version(s)
5.13.0
How is the ROS driver used.
Through the robot teach pendant using External Control URCap
Issue details
Summary
Controlling a UR10e robot with the URCap “External-Control” from an external PC. Waypoints are sent from the PC to the real robot, which it also follows, but the movement is aborted due to a time-out error as soon as the speed slider is not at 100%
Issue details
We are trying to control a UR10e robot with Polyscope 5.13 via ROS2 Humble. The robot is connected to an external PC via Ethernet. The URCap “External-Control” is installed on the real robot. When I press the play button, I get the following output on the screen:
The Scaled_joint_trajectory_controller is active and receives waypoints via a C++ script. Everything works well and the robot follows the path. However, this is only possible if the speed controller is set to 100%. If I slow it down, I get the following error:
The robot moves to the first points of the path and then aborts the movement with the MoveGroup Error.
Steps to Reproduce
Start the Launch-Files
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur10e robot_ip:=192.168.1.102 launch_rviz:=false
andros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur10e
Expected Behavior
The robot will slow down his movements, when the speed slider on the teach pendant is scaled down but don't aborted the movement.
Actual Behavior
The robot moves to the first few points and then aborted the movement.
Workaround Suggestion
Maybe I misunderstand the scaled_joint_trajectory_controller, but I thought this was a special controller for the UR series that takes into account the current value of the speed controller. I can also read the corresponding topic (
ros2 topic echo /speed_scaling_state_broadcaster/speed_scaling
) and get the same values as on the teach pendant. What other configurations need to be made on the controller? I have checked theur_controllers.yaml
andmoveit_controllers.yaml
, but I have no idea where the problem is coming from.Thanks in advance for any helpful tips!
Relevant log output
Accept Public visibility