Is it possible to command the robot using another script when running stretch_web_interface

Hi Stretch Community!
I want to run a python script which sends commands to the robot while the web interface is running. The main purpose of running the two scripts at the same time is to get the camera feed from the web_interface. Here is the error I got:

[ERROR] [pimu]: Port /dev/hello-pimu is busy. Check if another Stretch Body process is already running
[WARNING] [pimu]: Unable to open serial port for device /dev/hello-pimu
[ERROR] [hello-motor-left-wheel]: SerialException(5): could not open port /dev/hello-motor-left-wheel: [Errno 5] Input/output error: '/dev/hello-motor-left-wheel'
[WARNING] [hello-motor-left-wheel]: Unable to open serial port for device /dev/hello-motor-left-wheel
[ERROR] [hello-motor-right-wheel]: Port /dev/hello-motor-right-wheel is busy. Check if another Stretch Body process is already running
[WARNING] [hello-motor-right-wheel]: Unable to open serial port for device /dev/hello-motor-right-wheel
[ERROR] [hello-motor-lift]: Port /dev/hello-motor-lift is busy. Check if another Stretch Body process is already running
[WARNING] [hello-motor-lift]: Unable to open serial port for device /dev/hello-motor-lift
[ERROR] [hello-motor-arm]: Port /dev/hello-motor-arm is busy. Check if another Stretch Body process is already running
[WARNING] [hello-motor-arm]: Unable to open serial port for device /dev/hello-motor-arm
[ERROR] [wacc]: Port /dev/hello-wacc is busy. Check if another Stretch Body process is already running
[WARNING] [wacc]: Unable to open serial port for device /dev/hello-wacc
Traceback (most recent call last):
File "[BluetoothAP.py](http://bluetoothap.py/)", line 23, in <module>
robot.startup()
File "/home/zackory/.local/lib/python2.7/site-packages/stretch_body/robot.py", line 159, in startup
if not self.devices[k].startup(threaded=False):
File "/home/zackory/.local/lib/python2.7/site-packages/stretch_body/head.py", line 21, in startup
return DynamixelXChain.startup(self, threaded=threaded)
File "/home/zackory/.local/lib/python2.7/site-packages/stretch_body/dynamixel_X_chain.py", line 81, in startup
if not self.motors[mk].startup(threaded=False):
File "/home/zackory/.local/lib/python2.7/site-packages/stretch_body/dynamixel_hello_XL430.py", line 160, in startup
self.motor.set_return_delay_time(self.params['return_delay_time'])
File "/home/zackory/.local/lib/python2.7/site-packages/stretch_body/dynamixel_XL430.py", line 404, in set_return_delay_time
dxl_comm_result, dxl_error = self.packet_handler.write1ByteTxRx(self.port_handler, self.dxl_id,XL430_ADDR_RETURN_DELAY_TIME, int(x))
File "/opt/ros/melodic/lib/python2.7/dist-packages/dynamixel_sdk/protocol2_packet_handler.py", line 653, in write1ByteTxRx
return self.writeTxRx(port, dxl_id, address, 1, data_write)
File "/opt/ros/melodic/lib/python2.7/dist-packages/dynamixel_sdk/protocol2_packet_handler.py", line 643, in writeTxRx
rxpacket, result, error = self.txRxPacket(port, txpacket)
File "/opt/ros/melodic/lib/python2.7/dist-packages/dynamixel_sdk/protocol2_packet_handler.py", line 346, in txRxPacket
rxpacket, result = self.rxPacket(port)
File "/opt/ros/melodic/lib/python2.7/dist-packages/dynamixel_sdk/protocol2_packet_handler.py", line 257, in rxPacket
rxpacket.extend(port.readPort(wait_length - rx_length))
File "/opt/ros/melodic/lib/python2.7/dist-packages/dynamixel_sdk/port_handler.py", line 80, in readPort
return [ord(ch) for ch in self.ser.read(length)]
File "/home/zackory/.local/lib/python2.7/site-packages/serial/serialposix.py", line 596, in read
'device reports readiness to read but returned no data '
serial.serialutil.SerialException: device reports readiness to read but returned no data (device disconnected or multiple access on port?)

Is there a way to fix this? Or are there any python codes I can use to get the real time video feed from the robot?
Thank you so much for your help!

Hi @Bread_wq, only one program can access the hardware at the same time and from the errors you’re seeing, it seems like the second script is attempting to access the hardware when it calls robot.startup().

While the web interface is running, the ROS Realsense driver is running as well. If you’d like to access the camera feed while the web interface is running, you can write another ROS node that subscribes to the Realsense topics. Here’s a tutorial (and an additional example) on the subject of using the Realsense topics.

Let me know if you have any questions. Happy to suggest changes if you link your second script here.

Hello, I believe Binit’s tips might be the more efficient solution for you in this case, but I have been working with the interface quite a bit this summer and wanted to chime in with a couple things I have learned. Here is what has been working well for me as I write separate nodes to work alongside the interface:

  • To move the base, I publish twist messages directly to the /stretch/cmd_vel topic (works well for simple translations and rotations, but I would not try anything much more complicated)

  • For full body joint control, I use the send_command function from the keyboard teleop node. The key to avoiding conflicts is to add two services calls. Before using the single joint control in the send_command function, you must call the ‘/switch_to_position_mode’ service. After the single joint command is sent, in order to be able to control the robot from the interface again, you must reset the mode by calling the ‘/switch_to_navigation_mode’ service.

I will add a disclaimer that I am working with the University of Washington’s Human-Centered Robotics Lab’s fork of the interface, which has gone through some significant changes so it is possible these tips will not apply. If you would like an example of these ideas, you can check out a node I wrote to save positions relative to ArUco tags in my development branch.

I hope this is helpful, please feel free to reach out to me with any questions!

2 Likes

Hi Binit! I think your advice is really helpful. ROS is the way to go, and I found this How to get RGB Depth stream in python ROS · Issue #1514 · IntelRealSense/realsense-ros · GitHub really helpful combined with your suggestion! If anyone is interested, just modify the line
rospy.Subscriber('/camera/aligned_depth_to_color/image_raw', Image, callback)
into
rospy.Subscriber('/camera/color/image_raw', Image, callback)
And you can access the video stream without causing conflicts with other programs controlling the robot!

1 Like

Glad to hear it @Bread_wq!