You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
The following sequence leads to the ros 2 driver crashing due to a SIGPIPE:
ros2 run ur_robot_driver start_ursim.sh
Shortly after that, while the robot is still booting: ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=192.168.56.101 headless_mode:=true launch_rviz:=false
Wait until robot is started and driver is connected
ros2 service call /dashboard_client/power_on std_srvs/srv/Trigger "{}"
ros2 service call /dashboard_client/brake_release std_srvs/srv/Trigger "{}"
ros2 control load_controller io_and_status_controller --set-state start
ros2 service call /io_and_status_controller/resend_robot_program std_srvs/srv/Trigger "{}"
The backtrace:
Thread 20 "ur_ros2_control" received signal SIGPIPE, Broken pipe.
[Switching to Thread 0x7fffceffd640 (LWP 153506)]
__libc_send (flags=<optimized out>, len=4420, buf=0x7fff94001cc0, fd=28) at ../sysdeps/unix/sysv/linux/send.c:28
28 ../sysdeps/unix/sysv/linux/send.c: No such file or directory.
(gdb) bt
#0 __libc_send (flags=<optimized out>, len=4420, buf=0x7fff94001cc0, fd=28) at ../sysdeps/unix/sysv/linux/send.c:28
#1 __libc_send (fd=28, buf=0x7fff94001cc0, len=4420, flags=0) at ../sysdeps/unix/sysv/linux/send.c:23
#2 0x00007fffecdfa820 in urcl::comm::TCPSocket::write (this=this@entry=0x5555558d6400,
buf=buf@entry=0x7fff94001cc0 "def externalControl():\n\t\n\t\n\t# HEADER_BEGIN\n\t\n\tsteptime = get_steptime()\n\t\n\ttextmsg(\"ExternalControl: steptime=\", steptime)\n\tMULT_jointstate = 1000000\n\t\n\t#Constants\n\tSERVO_UNINITIALIZED = -1\n\tSERVO_IDL"...,
buf_len=buf_len@entry=4420, written=@0x7fffceffbcd8: 0)
at /home/wilbrandt/robot_folders/checkout/ur_rolling/colcon_ws/src/Universal_Robots_Client_Library/src/comm/tcp_socket.cpp:187
#3 0x00007fffece1072b in urcl::comm::URStream<urcl::primary_interface::PrimaryPackage>::write (written=@0x7fffceffbcd8: 0, buf_len=4420,
buf=0x7fff94001cc0 "def externalControl():\n\t\n\t\n\t# HEADER_BEGIN\n\t\n\tsteptime = get_steptime()\n\t\n\ttextmsg(\"ExternalControl: steptime=\", steptime)\n\tMULT_jointstate = 1000000\n\t\n\t#Constants\n\tSERVO_UNINITIALIZED = -1\n\tSERVO_IDL"..., this=0x5555558d6400)
at /home/wilbrandt/robot_folders/checkout/ur_rolling/colcon_ws/src/Universal_Robots_Client_Library/include/ur_client_library/comm/stream.h:133
#4 urcl::UrDriver::sendScript (this=0x5555558702f0, program=...)
at /home/wilbrandt/robot_folders/checkout/ur_rolling/colcon_ws/src/Universal_Robots_Client_Library/src/ur/ur_driver.cpp:299
#5 0x00007fffecef4930 in ur_robot_driver::URPositionHardwareInterface::checkAsyncIO (this=0x5555558c4390)
at /home/wilbrandt/robot_folders/checkout/ur_rolling/colcon_ws/src/Universal_Robots_ROS2_Driver/ur_robot_driver/src/hardware_interface.cpp:633
#6 0x00007fffecef50b8 in ur_robot_driver::URPositionHardwareInterface::asyncThread (this=0x5555558c4390)
at /home/wilbrandt/robot_folders/checkout/ur_rolling/colcon_ws/src/Universal_Robots_ROS2_Driver/ur_robot_driver/src/hardware_interface.cpp:464
#7 0x00007ffff7b602c3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#8 0x00007ffff78d0b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#9 0x00007ffff7962a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81
The send function in TCPSocket is called on a secondary interface connection that is disconnected. This not only returns an EPIPE error, but additionally sends the SIGPIPE signal which is not handled and therefore kills the process.
The text was updated successfully, but these errors were encountered:
The following sequence leads to the ros 2 driver crashing due to a
SIGPIPE
:ros2 run ur_robot_driver start_ursim.sh
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=192.168.56.101 headless_mode:=true launch_rviz:=false
ros2 service call /dashboard_client/power_on std_srvs/srv/Trigger "{}"
ros2 service call /dashboard_client/brake_release std_srvs/srv/Trigger "{}"
ros2 control load_controller io_and_status_controller --set-state start
ros2 service call /io_and_status_controller/resend_robot_program std_srvs/srv/Trigger "{}"
The backtrace:
The
send
function inTCPSocket
is called on a secondary interface connection that is disconnected. This not only returns anEPIPE
error, but additionally sends theSIGPIPE
signal which is not handled and therefore kills the process.The text was updated successfully, but these errors were encountered: