moveit / moveit2

:robot: MoveIt for ROS 2
https://moveit.ai/
BSD 3-Clause "New" or "Revised" License
982 stars 492 forks source link

Incorrect Implementations inside MoveGroupInterface for waiting response from server #2859

Open CihatAltiparmak opened 1 month ago

CihatAltiparmak commented 1 month ago

Description

Hello everyone, Firstly, thanks for this great project. I want to inform you about some bad practices in move_group_interface . There occur some functionality problem in
the part of plan method of MoveGroupInterface https://github.com/moveit/moveit2/blob/672e0ecd48f471fe05057f81e6233272a692a156/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp#L691-L710 ,

the part of move method of MoveGroupInterface https://github.com/moveit/moveit2/blob/672e0ecd48f471fe05057f81e6233272a692a156/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp#L767-L782

and maybe this part of execute method of MoveGroupInterface https://github.com/moveit/moveit2/blob/672e0ecd48f471fe05057f81e6233272a692a156/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp#L831-L850

I also want to make a critic about node spinning inside separate thread in move_group_interface. For users who don't know node starts to spin in separate thread when move group interface is created, this logic maybe can be problem. I think we need better implementation for this part as well.

https://github.com/moveit/moveit2/blob/672e0ecd48f471fe05057f81e6233272a692a156/moveit_ros/planning_interface/move_group_interface/src/move_group_interface.cpp#L117-L120

Problem is that there is a possibility that request is sent by client but is not received forever by server, especially move_group_server. This can bring about move_group_interface to get stuck inside while loop and plan method not to finish its own job.

In addition, these implementations normally work for rmw_fastrtps and rmw_cyclonedds, but get stuck with rmw_zenoh.

If you want, i can deal with it and can try to come up with better implementation.

Your environment

Steps to reproduce

Firstly, run zenoh router (be sure that rmw_zenoh_cpp is built at your workspace)

export RMW_IMPLEMENTATION=rmw_zenoh_cpp
ros2 run rmw_zenoh_cpp rmw_zenohd

Secondly, Follow the MoveIt tutorials(but use this tutorial repository i forked) and run demo launch of MoveIt2 using following command.

export RMW_IMPLEMENTATION=rmw_zenoh_cpp
ros2 run moveit2_tutorials perception_pipeline_demo.launch.py

Run this benchmark code from this repository using below command

export RMW_IMPLEMENTATION=rmw_zenoh_cpp
ros2 run moveit_middleware_benchmark test_scenario_perception_pipeline

Expected behaviour

plan method of MoveGroupInterface should not get stuck. If planning has timeout due to the fact that server doesn't receive request even though sending request from move_group_interface client is successfull, it is returned timeout error by plan method of move_group_interface.

Actual behaviour

plan method gets stuck inside while loop.

Backtrace or Console output

I have no console output and backtrace logs at the moment.

CihatAltiparmak commented 1 month ago

CC : @henningkayser @sjahr