rmw_fastrtps
rmw_fastrtps copied to clipboard
[Question] Client will not receive response
- Operating System:
- Ubuntu 20.04 (in Docker)
- Ros version:
- ros2 foxy (install from binary)
- Installation type:
- binaries, ros-foxy-rmw_fastrtps-cpp 1.2.5
- DDS implementation:
- Fast-RTPS, ros-foxy-fastrtps 2.0.2
Sometimes when running the pipeline I get this error:
[cluster_node-10] terminate called after throwing an instance of 'rclcpp::exceptions::RCLError'
[cluster_node-10] what(): failed to send response: client will not receive response, at /tmp/binarydeb/ros-foxy-rmw-fastrtps-shared-cpp-1.2.5/src/rmw_response.cpp:126, at /tmp/binarydeb/ros-foxy-rcl-1.1.11/src/rcl/service.c:356
[ERROR] [cluster_node-10]: process has died [pid 14929, exit code -6, cmd ...
After restarting the pipeline, everything works fine. Especially often nodes that work with Services crash with this error. I saw the error only in c ++ nodes, but maybe python just doesn't show it. It seems that this error began to appear more often with an increase in the number of nodes, but I may be wrong.
What could be the problem?
@TuMePJlaH we'll need a some more information before we can investigate this.
Check ROS 2 Developer Guide on what you should include in your bug report.
@hidmic this is not a bug report. The error appears rarely and unpredictably (it appeared several times on a node that does not use services). I would like to come up with a synthetic test to reproduce it. To do this, I would like to understand under what circumstances is this even possible?
failed to send response: client will not receive response
The error message is pretty clear. See here. The client is likely gone by the time the server sends a response.
Thank you for your response! But how can this happen in a node that does not use services?
But how can this happen in a node that does not use services?
Client libraries such as rclcpp
use services under the hood (e.g. here).
We are seeing a similar error on ROS2 Humble release, full traceback, the service is in CPP and client is in python
[move_group-2]
[move_group-2] ********************************************************
[move_group-2] * MoveGroup using:
[move_group-2] * - QoowaGoalSamplingCapability
[move_group-2] * - QoowaPlanningCapability
[move_group-2] * - QoowaPlanningSceneCapability
[move_group-2] ********************************************************
[move_group-2]
[move_group-2] [INFO] [1655927843.863770288] [moveit_move_group_capabilities_base.move_group_context]: MoveGroup context using planning plugin qoowa_planning_capability/QoowaOMPLPlanner
[move_group-2] [INFO] [1655927843.863776150] [moveit_move_group_capabilities_base.move_group_context]: MoveGroup context initialization complete
[move_group-2]
[move_group-2] You can start planning now!
[move_group-2]
[move_group-2] terminate called after throwing an instance of 'rclcpp::exceptions::RCLError'
[move_group-2] what(): failed to send response: client will not receive response, at ./src/rmw_response.cpp:129, at ./src/rcl/service.c:314
[move_group-2] Stack trace (most recent call last) in thread 181:
[move_group-2] #16 Object "", at 0xffffffffffffffff, in
[move_group-2] #15 Source "../sysdeps/unix/sysv/linux/x86_64/clone3.S", line 81, in __clone3 [0x7f62564b39ff]
[move_group-2] #14 Source "./nptl/pthread_create.c", line 442, in start_thread [0x7f6256421b42]
[move_group-2] #13 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f62566b12c2, in
[move_group-2] #12 Object "/opt/ros/humble/lib/librclcpp.so", at 0x7f625694d659, in rclcpp::executors::MultiThreadedExecutor::run(unsigned long)
[move_group-2] #11 Object "/opt/ros/humble/lib/librclcpp.so", at 0x7f62569455a5, in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&)
[move_group-2] #10 Object "/opt/ros/humble/lib/librclcpp.so", at 0x7f6256945239, in rclcpp::Executor::execute_service(std::shared_ptr<rclcpp::ServiceBase>)
[move_group-2] #9 Object "/opt/ros/humble/lib/librclcpp.so", at 0x7f6256947915, in
[move_group-2] #8 | Source "/opt/ros/humble/include/rclcpp/rclcpp/service.hpp", line 475, in send_response
[move_group-2] | 473: auto response = any_callback_.dispatch(this->shared_from_this(), request_header, typed_request);
[move_group-2] | 474: if (response) {
[move_group-2] | > 475: send_response(*request_header, *response);
[move_group-2] | 476: }
[move_group-2] | 477: }
[move_group-2] Source "/opt/ros/humble/include/rclcpp/rclcpp/service.hpp", line 485, in handle_request [0x7f624c7610c4]
[move_group-2] 482: rcl_ret_t ret = rcl_send_response(get_service_handle().get(), &req_id, &response);
[move_group-2] 483:
[move_group-2] 484: if (ret != RCL_RET_OK) {
[move_group-2] > 485: rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send response");
[move_group-2] 486: }
[move_group-2] 487: }
[move_group-2] #7 Object "/opt/ros/humble/lib/librclcpp.so", at 0x7f625693f9c8, in rclcpp::exceptions::throw_from_rcl_error(int, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rcutils_error_state_s const*, void (*)())
[move_group-2] #6 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f625668327d, in std::rethrow_exception(std::__exception_ptr::exception_ptr)
[move_group-2] #5 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f62566832f6, in std::terminate()
[move_group-2] #4 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f625668328b, in
[move_group-2] #3 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f6256677bfd, in
[move_group-2] #2 Source "./stdlib/abort.c", line 79, in abort [0x7f62563b57f2]
[move_group-2] #1 Source "../sysdeps/posix/raise.c", line 26, in raise [0x7f62563cf475]
[move_group-2] #0 | Source "./nptl/pthread_kill.c", line 89, in __pthread_kill_internal
[move_group-2] | Source "./nptl/pthread_kill.c", line 78, in __pthread_kill_implementation
[move_group-2] Source "./nptl/pthread_kill.c", line 44, in __pthread_kill [0x7f6256423a7c]
[move_group-2] Aborted (Signal sent by tkill() 152 0)
[ERROR] [move_group-2]: process has died [pid 152, exit code -6, cmd '/root/ws_moveit/install/moveit_ros_move_group/lib/moveit_ros_move_group/move_group --ros-args --log-level info --ros-args --params-file /tmp/launch_params_yhs8papp --params-file /tmp/launch_params_hzqrenjx --params-file /moveit_ws/install/qoowa_moveit_config/share/qoowa_moveit_config/config/ur/kinematics.yaml --params-file /tmp/launch_params_faj5br8r --params-file /tmp/launch_params_4xh9hrqf --params-file /tmp/launch_params_4goqwskv --params-file /tmp/launch_params_ihfvqk84 --params-file /tmp/launch_params_7q_gxo5p --params-file /tmp/launch_params_zx597ivh --params-file /tmp/launch_params_eo0spj8x --params-file /tmp/launch_params_i2zw6y1y'].
related to https://github.com/ros2/ros2/issues/1253
i will go ahead to close this, see https://github.com/ros2/ros2/issues/1253#issuecomment-1702937597