moveit2 icon indicating copy to clipboard operation
moveit2 copied to clipboard

Hybrid planner crashes after succeeding

Open skaeringur97 opened this issue 3 years ago • 4 comments

Description

Sometimes when running the hybrid planner, a ABORT signal is sent just before the plan succeeds. This makes the goal handle send SUCCEEDED just after sending ABBORTED. This results in the following error msg:

[component_container_mt-1]   what():  goal_handle attempted invalid transition from state ABORTED with event SUCCEED, at ./src/rcl_action/goal_handle.c:95

Maybe some lock might be good to make sure that only one state is sent.

Your environment

  • ROS2: [Humble]
  • OS Version: Ubuntu 22.04
  • Binary build

Steps to reproduce

Maybe difficult to reproduce without running a hybrid planning demo often and for a long time.

Expected behaviour

Hybrid planning aborts.

Actual behaviour

Hybrid planning succeeds and node crashes.

Backtrace or Console output

Console output (only last few lines since it was running for a while before this happened)
[component_container_mt-1] [INFO] [1669802585.721241181] [moveit.ros_planning_interface.planning_component]: Deleting PlanningComponent 'ur_manipulator'
[component_container_mt-1] [INFO] [1669802585.721559211] [local_planner_component]: Received local planning goal request
[component_container_mt-1] [INFO] [1669802585.921812343] [local_planner_component]: The local planner is solving...
[component_container_mt-1] [INFO] [1669802586.522100202] [local_planner_component]: Collision ahead, holding current position
[component_container_mt-1] [INFO] [1669802586.522241134] [global_planner_component]: Received global planning goal request
[component_container_mt-1] [WARN] [1669802586.522747311] [moveit.ompl_planning.planning_context_manager]: Cannot find planning configuration for group 'ur_manipulator' using planner 'ompl'. Will use defaults instead.
[component_container_mt-1] [WARN] [1669802586.522868646] [moveit.ompl_planning.model_based_planning_context]: It looks like the planning volume was not specified.
[component_container_mt-1] [INFO] [1669802586.522955731] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[component_container_mt-1] [INFO] [1669802586.622116203] [local_planner_component]: Collision ahead, holding current position
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802586.721490928] [test_hybrid_planning_client]: Service timed out.
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802586.721565900] [test_hybrid_planning_client]: Local goal accepted by server
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802586.721582911] [test_hybrid_planning_client]: Global goal accepted by server
[component_container_mt-1] [INFO] [1669802588.021805685] [local_planner_component]: The local planner is solving...
[component_container_mt-1] [INFO] [1669802588.028746503] [moveit.ros_planning_interface.planning_component]: Deleting PlanningComponent 'ur_manipulator'
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802589.029018311] [test_hybrid_planning_client]: Service timed out.
[component_container_mt-1] [INFO] [1669802590.121789968] [local_planner_component]: The local planner is solving...
[component_container_mt-1] [INFO] [1669802592.221800022] [local_planner_component]: The local planner is solving...
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802592.522098211] [test_hybrid_planning_client]: Hybrid planning goal succeeded
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802592.522110598] [test_hybrid_planning_client]: Pre-grasp stage succeeded
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802592.522144688] [test_hybrid_planning_client]: Sending hybrid planning goal
[component_container_mt-1] [INFO] [1669802592.522226937] [hybrid_planning_manager]: Received goal request
[component_container_mt-1] [INFO] [1669802592.522526942] [global_planner_component]: Received global planning goal request
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802592.522636074] [test_hybrid_planning_client]: Global goal accepted by server
[component_container_mt-1] [WARN] [1669802592.522979777] [moveit.ompl_planning.planning_context_manager]: Cannot find planning configuration for group 'ur_manipulator' using planner 'ompl'. Will use defaults instead.
[component_container_mt-1] [WARN] [1669802592.523139441] [moveit.ompl_planning.model_based_planning_context]: It looks like the planning volume was not specified.
[component_container_mt-1] [INFO] [1669802592.523231453] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[component_container_mt-1] [INFO] [1669802592.865112287] [moveit.ros_planning_interface.planning_component]: Deleting PlanningComponent 'ur_manipulator'
[component_container_mt-1] [INFO] [1669802592.865378965] [local_planner_component]: Received local planning goal request
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802593.865406781] [test_hybrid_planning_client]: Service timed out.
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802593.865480845] [test_hybrid_planning_client]: Local goal accepted by server
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802593.865523960] [test_hybrid_planning_client]: Hybrid planning goal succeeded
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802593.865577130] [test_hybrid_planning_client]: Place position: 0.3, 1.1, 0.85
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802593.865593026] [test_hybrid_planning_client]: Sending hybrid planning goal
[component_container_mt-1] [INFO] [1669802593.865674716] [hybrid_planning_manager]: Received goal request
[component_container_mt-1] [INFO] [1669802593.865903293] [global_planner_component]: Received global planning goal request
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802593.866015083] [test_hybrid_planning_client]: Global goal accepted by server
[component_container_mt-1] [WARN] [1669802593.866437996] [moveit.ompl_planning.planning_context_manager]: Cannot find planning configuration for group 'ur_manipulator' using planner 'ompl'. Will use defaults instead.
[component_container_mt-1] [WARN] [1669802593.866577581] [moveit.ompl_planning.model_based_planning_context]: It looks like the planning volume was not specified.
[component_container_mt-1] [INFO] [1669802593.866693362] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[component_container_mt-1] [INFO] [1669802594.729966981] [moveit.ros_planning_interface.planning_component]: Deleting PlanningComponent 'ur_manipulator'
[component_container_mt-1] [INFO] [1669802594.730352966] [local_planner_component]: Received local planning goal request
[component_container_mt-1] [INFO] [1669802594.830641666] [local_planner_component]: The local planner is solving...
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802595.730247793] [test_hybrid_planning_client]: Service timed out.
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802595.730320272] [test_hybrid_planning_client]: Local goal accepted by server
[component_container_mt-1] [INFO] [1669802596.930613995] [local_planner_component]: The local planner is solving...
[component_container_mt-1] [INFO] [1669802598.330858586] [local_planner_component]: Collision ahead, holding current position
[component_container_mt-1] [INFO] [1669802598.330993663] [global_planner_component]: Received global planning goal request
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802598.331139460] [test_hybrid_planning_client]: Global goal accepted by server
[component_container_mt-1] [WARN] [1669802598.331508355] [moveit.ompl_planning.planning_context_manager]: Cannot find planning configuration for group 'ur_manipulator' using planner 'ompl'. Will use defaults instead.
[component_container_mt-1] [WARN] [1669802598.331655880] [moveit.ompl_planning.model_based_planning_context]: It looks like the planning volume was not specified.
[component_container_mt-1] [INFO] [1669802598.331745287] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[component_container_mt-1] [INFO] [1669802598.930638761] [local_planner_component]: The local planner is solving...
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802599.530821983] [test_hybrid_planning_client]: Hybrid planning goal succeeded
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802599.530831572] [test_hybrid_planning_client]: Place stage succeeded
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802599.530854828] [test_hybrid_planning_client]: detachFromRobot
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802599.530903302] [test_hybrid_planning_client]: removing apple40 from environment
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802599.531326587] [test_hybrid_planning_client]: Active apple: apple39
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802599.531343434] [test_hybrid_planning_client]: GetClosestObject
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802599.531352738] [test_hybrid_planning_client]: closest object is apple39 with pos x:0.767135 with pos y:0.853104 with pos z:0.276412
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802599.531364738] [test_hybrid_planning_client]: Sending hybrid planning goal
[component_container_mt-1] [INFO] [1669802599.531440050] [hybrid_planning_manager]: Received goal request
[component_container_mt-1] [INFO] [1669802599.531652827] [global_planner_component]: Received request to cancel global planning goal
[component_container_mt-1] [INFO] [1669802599.553372411] [moveit.ros_planning_interface.planning_component]: Deleting PlanningComponent 'ur_manipulator'
[component_container_mt-1] [INFO] [1669802599.553662247] [local_planner_component]: Received local planning goal request
[component_container_mt-1] [INFO] [1669802599.553717491] [global_planner_component]: Received global planning goal request
[component_container_mt-1] [WARN] [1669802599.554194401] [moveit.ompl_planning.planning_context_manager]: Cannot find planning configuration for group 'ur_manipulator' using planner 'ompl'. Will use defaults instead.
[component_container_mt-1] [WARN] [1669802599.554300071] [moveit.ompl_planning.model_based_planning_context]: It looks like the planning volume was not specified.
[component_container_mt-1] [INFO] [1669802599.554396262] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802600.553606942] [test_hybrid_planning_client]: Service timed out.
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802600.553696157] [test_hybrid_planning_client]: Local goal accepted by server
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802600.553740051] [test_hybrid_planning_client]: Global goal accepted by server
[component_container_mt-1] [INFO] [1669802600.953920914] [local_planner_component]: The local planner is solving...
[component_container_mt-1] [ERROR] [1669802601.555857541] [ompl]: ./src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:253 - ur_manipulator/ur_manipulator: Unable to sample any valid states for goal tree
[component_container_mt-1] [ERROR] [1669802601.555913143] [ompl]: ./src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:253 - ur_manipulator/ur_manipulator: Unable to sample any valid states for goal tree
[component_container_mt-1] [ERROR] [1669802601.555935904] [ompl]: ./src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:253 - ur_manipulator/ur_manipulator: Unable to sample any valid states for goal tree
[component_container_mt-1] [ERROR] [1669802601.555958221] [ompl]: ./src/ompl/geometric/planners/rrt/src/RRTConnect.cpp:253 - ur_manipulator/ur_manipulator: Unable to sample any valid states for goal tree
[component_container_mt-1] [WARN] [1669802601.556000769] [ompl]: ./src/ompl/tools/multiplan/src/ParallelPlan.cpp:138 - ParallelPlan::solve(): Unable to find solution by any of the threads in 2.001506 seconds
[component_container_mt-1] [INFO] [1669802601.952084609] [moveit.ompl_planning.model_based_planning_context]: Unable to solve the planning problem
[component_container_mt-1] [ERROR] [1669802601.952103019] [moveit.ros_planning_interface.planning_component]: Could not compute plan successfully
[component_container_mt-1] [INFO] [1669802601.952116907] [moveit.ros_planning_interface.planning_component]: Deleting PlanningComponent 'ur_manipulator'
[component_container_mt-1] [ERROR] [1669802601.952356371] [hybrid_planning_manager]: Hybrid Planning Manager failed to react to  'Global planning action aborted'
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802601.952360156] [test_hybrid_planning_client]: Hybrid planning goal was aborted
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802601.952381369] [test_hybrid_planning_client]: Pre-grasp stage failed for apple39
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802601.952398235] [test_hybrid_planning_client]: removing apple39 from environment
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802601.953844286] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.00138769 seconds
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802601.953857651] [moveit_robot_model.robot_model]: Loading robot model 'ur'...
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802601.953863772] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[pick_and_place_inside_ur10e_cage-2] [WARN] [1669802601.963020740] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802601.963113910] [test_hybrid_planning_client]: Sending hybrid planning goal
[component_container_mt-1] [INFO] [1669802601.963232304] [hybrid_planning_manager]: Received goal request
[component_container_mt-1] [INFO] [1669802601.963420229] [local_planner_component]: Received request to cancel local planning goal
[component_container_mt-1] [INFO] [1669802601.963541606] [global_planner_component]: Received global planning goal request
[pick_and_place_inside_ur10e_cage-2] [INFO] [1669802601.963686358] [test_hybrid_planning_client]: Global goal accepted by server
[component_container_mt-1] [WARN] [1669802601.964174164] [moveit.ompl_planning.planning_context_manager]: Cannot find planning configuration for group 'ur_manipulator' using planner 'ompl'. Will use defaults instead.
[component_container_mt-1] [WARN] [1669802601.964387594] [moveit.ompl_planning.model_based_planning_context]: It looks like the planning volume was not specified.
[component_container_mt-1] [INFO] [1669802601.964487970] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802602.054139753] [test_hybrid_planning_client]: Hybrid planning goal was aborted
[component_container_mt-1] [ERROR] [1669802602.054141218] [hybrid_planning_manager]: Hybrid Planning Manager failed to react to Local planning action aborted
[component_container_mt-1] [INFO] [1669802602.254129015] [moveit.ros_planning_interface.planning_component]: Deleting PlanningComponent 'ur_manipulator'
[component_container_mt-1] [INFO] [1669802602.254466175] [local_planner_component]: Received local planning goal request
[component_container_mt-1] [INFO] [1669802602.954712899] [local_planner_component]: The local planner is solving...
[pick_and_place_inside_ur10e_cage-2] [ERROR] [1669802603.254333073] [test_hybrid_planning_client]: Service timed out.
[component_container_mt-1] terminate called after throwing an instance of 'rclcpp::exceptions::RCLError'
[component_container_mt-1]   what():  goal_handle attempted invalid transition from state ABORTED with event SUCCEED, at ./src/rcl_action/goal_handle.c:95

skaeringur97 avatar Nov 30 '22 14:11 skaeringur97

This issue is being labeled as stale because it has been open 45 days with no activity. It will be automatically closed after another 45 days without follow-ups.

github-actions[bot] avatar Apr 09 '24 12:04 github-actions[bot]

Description

Sometimes when running the hybrid planner, a ABORT signal is sent just before the plan succeeds. This makes the goal handle send SUCCEEDED just after sending ABBORTED. This results in the following error msg:

[component_container_mt-1]   what():  goal_handle attempted invalid transition from state ABORTED with event SUCCEED, at ./src/rcl_action/goal_handle.c:95

Maybe some lock might be good to make sure that only one state is sent.

Your environment

  • ROS2: [Humble]
  • OS Version: Ubuntu 22.04
  • Binary build

Steps to reproduce

Maybe difficult to reproduce without running a hybrid planning demo often and for a long time.

Expected behaviour

Hybrid planning aborts.

Actual behaviour

Hybrid planning succeeds and node crashes.

Backtrace or Console output

Console output (only last few lines since it was running for a while before this happened)

Hello @skaeringur97 , I've also came across this problem. Have you figure out how to solve this now?

frankchan12138 avatar Oct 31 '24 06:10 frankchan12138

Hi @frankchan12138

Unfortunately I don't remember if I ever solved this. I stopped working on this such a long time ago. Sorry to be of no help.. Good luck :)

skaeringur97 avatar Nov 01 '24 14:11 skaeringur97

Hi @frankchan12138

Unfortunately I don't remember if I ever solved this. I stopped working on this such a long time ago. Sorry to be of no help.. Good luck :)

@skaeringur97 Thanks for reply! I will try myself.

frankchan12138 avatar Nov 07 '24 06:11 frankchan12138