ROS2 UR10e Robot Position Updates In Rviz But Cannot Be Conrolled

I am currently having issues trying to control my UR10e robot via ROS2 in a WSL2 environment.

Current Setup:

add v4tov4 listenport=50001 connectaddress=172.22.222.208 connectport=50001
add v4tov4 listenport=50002 connectaddress=172.22.222.208 connectport=50002
add v4tov4 listenport=50003 connectaddress=172.22.222.208 connectport=50003

Where 172.22.222.208 is my current WSL2 IP

  • UR10e is connected directly to my PC with a straight cable
  • NIC on the PC is manually set to 192.168.1.101
  • UR10e Network Settings are set to 192.168.1.102
  • No modifications or settings updated in moveit

If I run the externalcontrol software on the pendent without running any ROS2 programs, I get a timeout on the pendent.

  • Normal.

When I run:

ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur10e robot_ip:=192.168.1.102

and then run the externalcontrol program on the UR10e, no timeout occurs

  • Normal.

After running the externalcontrol program, there is no feedback in my WSL2 ROS2 terminal. Is this

  • Normal?

After running that command, Rviz2 will open up and it shows the robot in the position that the actual robot is in.

  • Normal.

If I stop the externalcontrol software and manually move the robot arm, Rviz2 is updated with the new position in real time even though externalcontrol software is stopped.
Normal?

If I kill the terminal such that no nodes are running while the externalcontrol program is still running, I do not get a timeout.

  • Normal?

As for MoveIt, (assume this is a fresh start), I run:

ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur10e robot_ip:=192.168.1.102 launch_rviz:=false

Then in a second terminal, I run:

launch ur_moveit_config ur_moveit.launch.py ur_type:=ur10e robot_ip:=192.168.1.102

Rviz2 opens up with the moveit tools and I drag the robot to a slightly new position. I then click plan and execute which shows the planned path but then says “Failed” underneath “Plan & Execute”. The moveit terminal.

In my ur_robot_driver terminal, I get a message and an error:

 [ur_ros2_control_node-1] [INFO] [1667570357.285096200] [scaled_joint_trajectory_controller]: Received new action goal
 [ur_ros2_control_node-1] [ERROR] [1667570357.285246000] [scaled_joint_trajectory_controller]: Can't accept new action goals. Controller is not running. 

However a ros2 node list reports:

/controller_manager
/dashboard_client
/force_torque_sensor_broadcaster
/forward_position_controller
/interactive_marker_display_94736246638448
/io_and_status_controller
/joint_state_broadcaster
/move_group
/move_group_private_94458103812400
/moveit_simple_controller_manager
/robot_state_publisher
/rviz2_moveit
/rviz2_moveit
/rviz2_moveit_private_139908291465840
/scaled_joint_trajectory_controller
/servo_node
/servo_node_private_94036311342704
/speed_scaling_state_broadcaster
/transform_listener_impl_5586890a72c0
/transform_listener_impl_55e8bdd87f20
/transform_listener_impl_56297fe87f90
/transform_listener_impl_56297ffb91a0
/transform_listener_impl_562983530c00

From here, I’m not sure what I’m doing wrong. Let me know if there is any important information that I have neglected to include.

Have you tried to launch the ur_robot_driver like this:

ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur10e robot_ip:=192.168.1.102 launch_rviz:=false initial_joint_controller:=joint_trajectory_controller

I think there is a problem with the scaled_joint_trajectory_controller that’s why we have to add initial_joint_controller:=joint_trajectory_controller

Just attempted this with no noticeable changes.

I first ran the suggested command line above and then the moveit command in my original post. After those were both completed, I executed the external control software on the robot itself. No terminal feed back in either the ur_control.launch termnial or in the moveit terminal. The external pendent appears to be running fine with no time out errors.

I then made a simple position adjustment in moveit by dragging the robot to a new position and selected plan & execute.

This returned a “Failed” in Rviz2 and in the moveit terminal the follow was printed:

Based on my earlier questions about whether some of my responses were normal or not, I have a feeling something is being lost in communication with the robot through WSL2. Thoughts

If I run the externalcontrol software on the pendent without running any ROS2 programs, I get a timeout on the pendent.

  • Normal.

Yes, this is normal. The driver will open a port where the external_control program node will connect to initially. This basically receives the URScript code from the ROS pc that will be running on the controller.

ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur10e robot_ip:=192.168.1.102

and then run the externalcontrol program on the UR10e, no timeout occurs

  • Normal.

This means that the robot controller can actually connect to your host PC, on port 5002, as you have configured in the TP’s installation. On the driver’s shell you should see something like

[ur_ros2_control_node-1] [INFO] [1667911490.872676163] [UR_Client_Library]: Robot requested program
[ur_ros2_control_node-1] [INFO] [1667911490.872736828] [UR_Client_Library]: Sent program to robot

If not, your port forwarding is probably not working correctly. I am not familiar with WSL, so I won’t be able to help you with that, unfortunately.

After running the externalcontrol program, there is no feedback in my WSL2 ROS2 terminal. Is this

  • Normal?

As stated above, you should see some output when the program is started. Additionally, once the program is running (in fact, when the program is inside the external_control node), you should see

[ur_ros2_control_node-1] [INFO] [1667911490.900446351] [UR_Client_Library]: Robot connected to reverse interface. Ready to receive control commands.

If you don’t see this, you wont be able to control the robot, hence the Controller is not running.` error.

After running that command, Rviz2 will open up and it shows the robot in the position that the actual robot is in.

  • Normal.

If I stop the externalcontrol software and manually move the robot arm, Rviz2 is updated with the new position in real time even though externalcontrol software is stopped.
Normal?

Sending status information from the robot to ROS is independent of the externalcontrol URCap. Hence, the robot’s joint state will show in RViz as long as the driver is running.

If I kill the terminal such that no nodes are running while the externalcontrol program is still running, I do not get a timeout.

  • Normal?

As explained above, the program code is queried once at the beginning. If you stop the driver, reads will timeout, but more silently. Depending on whether you loop your program, it will simply start from the top (in which case the program will show as running) or simply stop. No popup will be raised.

Thank you for the detailed explanations for each of my questions. I have a feeling my port forwarding is either not set up correctly or the permissions on this machine are locked such that even if I setup portforwarding, it may not work as intended.

I will rerun these commands and look for the response examples you gave. I’ll also include rft files for each terminal in my next reply later this morning.

I’m also looking to piece together a dedicated linux machine from one of our lesser used lab computers to avoid this whole WSL2 business.

Did you manage to solve this? if not I recommend you check the driver’s bring_up parameter reverse_ip