Skip to content

Segmentation Fault in move_group when executing the solution found by MTC #731

@lesurJ

Description

@lesurJ

Hey,

Just trying to plan and execute a simple trajectory using MTC crashes the program:

[INFO] [launch]: All log files can be found below /home/user/.ros/log/2025-11-21-12-24-34-133773-user-asus-m16-317915
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [robot_state_publisher-1]: process started with pid [317960]
[INFO] [move_group-2]: process started with pid [317961]
[INFO] [ros2_control_node-3]: process started with pid [317962]
[INFO] [rviz2-4]: process started with pid [317963]
[INFO] [spawner-5]: process started with pid [317964]
[INFO] [spawner-6]: process started with pid [317965]
[INFO] [spawner-7]: process started with pid [317966]
[INFO] [simple_mover-8]: process started with pid [317967]
[robot_state_publisher-1] [INFO] [1763724274.437405184] [robot_state_publisher]: Robot initialized
[ros2_control_node-3] [INFO] [1763724274.460106738] [controller_manager]: Using Steady (Monotonic) clock for triggering controller manager cycles.
[ros2_control_node-3] [INFO] [1763724274.461949180] [controller_manager]: Subscribing to '/robot_description' topic for robot description.
[move_group-2] [INFO] [1763724274.465021828] [move_group.moveit.moveit.ros.rdf_loader]: Loaded robot model in 0.00271176 seconds
[move_group-2] [INFO] [1763724274.465086514] [move_group.moveit.moveit.core.robot_model]: Loading robot model 'mp3'...
[move_group-2] [INFO] [1763724274.465097590] [move_group.moveit.moveit.core.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ros2_control_node-3] [INFO] [1763724274.472781561] [controller_manager]: update rate is 100 Hz
[ros2_control_node-3] [INFO] [1763724274.472820668] [controller_manager]: Overruns handling is : enabled
[ros2_control_node-3] [INFO] [1763724274.472834876] [controller_manager]: Spawning controller_manager RT thread with scheduler priority: 50
[ros2_control_node-3] [WARN] [1763724274.472953929] [controller_manager]: Could not enable FIFO RT scheduling policy: with error number <1>(Operation not permitted). See [https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] for details on how to enable realtime scheduling.
[ros2_control_node-3] [INFO] [1763724274.473848698] [controller_manager]: Received robot description from topic.
[move_group-2] [INFO] [1763724274.477971715] [move_group.moveit.moveit.kinematics.kdl_kinematics_plugin]: Joint weights for group 'arm': 1 1 1 1 1 1 1
[ros2_control_node-3] [INFO] [1763724274.478392070] [controller_manager]: Loading hardware 'MP3_arm_mock' 
[ros2_control_node-3] [INFO] [1763724274.479089851] [controller_manager]: Loaded hardware 'MP3_arm_mock' from plugin 'mock_components/GenericSystem'
[ros2_control_node-3] [INFO] [1763724274.479167688] [controller_manager]: Initialize hardware 'MP3_arm_mock' 
[ros2_control_node-3] [INFO] [1763724274.481920492] [controller_manager]: Successful initialization of hardware 'MP3_arm_mock'
[ros2_control_node-3] [INFO] [1763724274.482055437] [controller_manager]: Loading hardware 'gripper' 
[ros2_control_node-3] [INFO] [1763724274.482076738] [controller_manager]: Loaded hardware 'gripper' from plugin 'mock_components/GenericSystem'
[ros2_control_node-3] [INFO] [1763724274.482125384] [controller_manager]: Initialize hardware 'gripper' 
[ros2_control_node-3] [INFO] [1763724274.483969182] [controller_manager]: Successful initialization of hardware 'gripper'
[ros2_control_node-3] [INFO] [1763724274.484090551] [resource_manager]: 'configure' hardware 'gripper' 
[ros2_control_node-3] [INFO] [1763724274.484095913] [resource_manager]: Successful 'configure' of hardware 'gripper'
[ros2_control_node-3] [INFO] [1763724274.484100049] [resource_manager]: 'activate' hardware 'gripper' 
[ros2_control_node-3] [INFO] [1763724274.484103822] [resource_manager]: Successful 'activate' of hardware 'gripper'
[ros2_control_node-3] [INFO] [1763724274.484125821] [resource_manager]: 'configure' hardware 'MP3_arm_mock' 
[ros2_control_node-3] [INFO] [1763724274.484127668] [resource_manager]: Successful 'configure' of hardware 'MP3_arm_mock'
[ros2_control_node-3] [INFO] [1763724274.484130796] [resource_manager]: 'activate' hardware 'MP3_arm_mock' 
[ros2_control_node-3] [INFO] [1763724274.484132809] [resource_manager]: Successful 'activate' of hardware 'MP3_arm_mock'
[ros2_control_node-3] [INFO] [1763724274.484145747] [controller_manager]: Registering statistics for : gripper
[ros2_control_node-3] [INFO] [1763724274.484186032] [controller_manager]: Registering statistics for : MP3_arm_mock
[ros2_control_node-3] [INFO] [1763724274.484217160] [controller_manager]: Resource Manager has been successfully initialized. Starting Controller Manager services...
[move_group-2] [INFO] [1763724274.522243452] [move_group.moveit.moveit.ros.planning_scene_monitor]: Publishing maintained planning scene on 'monitored_planning_scene'
[move_group-2] [INFO] [1763724274.522379579] [move_group.moveit.moveit.ros.moveit_cpp]: Listening to 'joint_states' for joint states
[move_group-2] [INFO] [1763724274.522696069] [move_group.moveit.moveit.ros.current_state_monitor]: Listening to joint states on topic 'joint_states'
[move_group-2] [INFO] [1763724274.522992144] [move_group.moveit.moveit.ros.planning_scene_monitor]: Listening to '/attached_collision_object' for attached collision objects
[move_group-2] [INFO] [1763724274.523002992] [move_group.moveit.moveit.ros.planning_scene_monitor]: Stopping existing planning scene publisher.
[move_group-2] [INFO] [1763724274.523181670] [move_group.moveit.moveit.ros.planning_scene_monitor]: Stopped publishing maintained planning scene.
[move_group-2] [INFO] [1763724274.523627543] [move_group.moveit.moveit.ros.planning_scene_monitor]: Publishing maintained planning scene on 'monitored_planning_scene'
[move_group-2] [INFO] [1763724274.523682770] [move_group.moveit.moveit.ros.planning_scene_monitor]: Starting planning scene monitor
[move_group-2] [INFO] [1763724274.524129509] [move_group.moveit.moveit.ros.planning_scene_monitor]: Listening to '/planning_scene'
[move_group-2] [INFO] [1763724274.524141510] [move_group.moveit.moveit.ros.planning_scene_monitor]: Starting world geometry update monitor for collision objects, attached objects, octomap updates.
[move_group-2] [INFO] [1763724274.524318339] [move_group.moveit.moveit.ros.planning_scene_monitor]: Listening to 'collision_object'
[move_group-2] [INFO] [1763724274.524520818] [move_group.moveit.moveit.ros.planning_scene_monitor]: Listening to 'planning_scene_world' for planning scene world geometry
[move_group-2] [WARN] [1763724274.524836712] [move_group.moveit.moveit.ros.occupancy_map_monitor]: Resolution not specified for Octomap. Assuming resolution = 0.1 instead
[move_group-2] [ERROR] [1763724274.524848210] [move_group.moveit.moveit.ros.occupancy_map_monitor]: No 3D sensor plugin(s) defined for octomap updates
[move_group-2] [INFO] [1763724274.536889633] [move_group.moveit.moveit.ros.planning_pipeline]: Successfully loaded planner 'OMPL'
[move_group-2] [INFO] [1763724274.538437262] [move_group]: Try loading adapter 'default_planning_request_adapters/ResolveConstraintFrames'
[move_group-2] [INFO] [1763724274.539347647] [move_group]: Loaded adapter 'default_planning_request_adapters/ResolveConstraintFrames'
[move_group-2] [INFO] [1763724274.539369067] [move_group]: Try loading adapter 'default_planning_request_adapters/ValidateWorkspaceBounds'
[move_group-2] [INFO] [1763724274.539559669] [move_group]: Loaded adapter 'default_planning_request_adapters/ValidateWorkspaceBounds'
[move_group-2] [INFO] [1763724274.539567896] [move_group]: Try loading adapter 'default_planning_request_adapters/CheckStartStateBounds'
[move_group-2] [INFO] [1763724274.539590647] [move_group]: Loaded adapter 'default_planning_request_adapters/CheckStartStateBounds'
[move_group-2] [INFO] [1763724274.539596583] [move_group]: Try loading adapter 'default_planning_request_adapters/CheckStartStateCollision'
[move_group-2] [INFO] [1763724274.539608494] [move_group]: Loaded adapter 'default_planning_request_adapters/CheckStartStateCollision'
[move_group-2] [INFO] [1763724274.540600502] [move_group]: Try loading adapter 'default_planning_response_adapters/AddTimeOptimalParameterization'
[move_group-2] [INFO] [1763724274.542082577] [move_group]: Loaded adapter 'default_planning_response_adapters/AddTimeOptimalParameterization'
[move_group-2] [INFO] [1763724274.542097652] [move_group]: Try loading adapter 'default_planning_response_adapters/ValidateSolution'
[move_group-2] [INFO] [1763724274.542865403] [move_group]: Loaded adapter 'default_planning_response_adapters/ValidateSolution'
[move_group-2] [INFO] [1763724274.542875294] [move_group]: Try loading adapter 'default_planning_response_adapters/DisplayMotionPath'
[move_group-2] [INFO] [1763724274.543267513] [move_group]: Loaded adapter 'default_planning_response_adapters/DisplayMotionPath'
[move_group-2] [INFO] [1763724274.559402665] [move_group.moveit.moveit.plugins.simple_controller_manager]: Added FollowJointTrajectory controller for arm_controller
[move_group-2] [INFO] [1763724274.559441371] [move_group.moveit.moveit.plugins.simple_controller_manager]: gripper_controller will command a max effort of: 0
[move_group-2] [INFO] [1763724274.560207622] [move_group.moveit.moveit.plugins.simple_controller_manager]: Added GripperCommand controller for gripper_controller
[move_group-2] [INFO] [1763724274.560330272] [move_group.moveit.moveit.plugins.simple_controller_manager]: Returned 2 controllers in list
[move_group-2] [INFO] [1763724274.560348718] [move_group.moveit.moveit.plugins.simple_controller_manager]: Returned 2 controllers in list
[move_group-2] [INFO] [1763724274.560599328] [move_group.moveit.moveit.ros.trajectory_execution_manager]: Trajectory execution is managing controllers
[move_group-2] [INFO] [1763724274.560614862] [move_group]: MoveGroup debug mode is ON
[move_group-2] [INFO] [1763724274.577691042] [move_group.moveit.moveit.ros.move_group.executable]: 
[move_group-2] 
[move_group-2] ********************************************************
[move_group-2] * MoveGroup using: 
[move_group-2] *     - apply_planning_scene_service
[move_group-2] *     - clear_octomap_service
[move_group-2] *     - ExecuteTaskSolution
[move_group-2] *     - get_group_urdf
[move_group-2] *     - load_geometry_from_file
[move_group-2] *     - CartesianPathService
[move_group-2] *     - execute_trajectory_action
[move_group-2] *     - get_planning_scene_service
[move_group-2] *     - kinematics_service
[move_group-2] *     - move_action
[move_group-2] *     - motion_plan_service
[move_group-2] *     - query_planners_service
[move_group-2] *     - state_validation_service
[move_group-2] *     - save_geometry_to_file
[move_group-2] ********************************************************
[move_group-2] 
[move_group-2] [INFO] [1763724274.577771813] [move_group.moveit.moveit.ros.move_group.context]: MoveGroup context using pipeline ompl
[move_group-2] [INFO] [1763724274.577794082] [move_group.moveit.moveit.ros.move_group.context]: MoveGroup context initialization complete
[move_group-2] Loading 'move_group/ApplyPlanningSceneService'...
[move_group-2] Loading 'move_group/ClearOctomapService'...
[move_group-2] Loading 'move_group/ExecuteTaskSolutionCapability'...
[move_group-2] Loading 'move_group/GetUrdfService'...
[move_group-2] Loading 'move_group/LoadGeometryFromFileService'...
[move_group-2] Loading 'move_group/MoveGroupCartesianPathService'...
[move_group-2] Loading 'move_group/MoveGroupExecuteTrajectoryAction'...
[move_group-2] Loading 'move_group/MoveGroupGetPlanningSceneService'...
[move_group-2] Loading 'move_group/MoveGroupKinematicsService'...
[move_group-2] Loading 'move_group/MoveGroupMoveAction'...
[move_group-2] Loading 'move_group/MoveGroupPlanService'...
[move_group-2] Loading 'move_group/MoveGroupQueryPlannersService'...
[move_group-2] Loading 'move_group/MoveGroupStateValidationService'...
[move_group-2] Loading 'move_group/SaveGeometryToFileService'...
[move_group-2] 
[move_group-2] You can start planning now!
[move_group-2] 
[ros2_control_node-3] [INFO] [1763724274.802350617] [controller_manager]: Loading controller : 'joint_state_broadcaster' of type 'joint_state_broadcaster/JointStateBroadcaster'
[ros2_control_node-3] [INFO] [1763724274.802375157] [controller_manager]: Loading controller 'joint_state_broadcaster'
[ros2_control_node-3] [INFO] [1763724274.804477839] [controller_manager]: Controller 'joint_state_broadcaster' node arguments: --ros-args --params-file /home/user/GITS/simulation_ros2_ws/ros2_ws/install/mp3_moveit_config/share/mp3_moveit_config/config/ros2_controllers_mock_sim.yaml --params-file /tmp/launch_params_mc75z4sp 
[spawner-5] [INFO] [1763724274.821928706] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-3] [INFO] [1763724274.822566776] [controller_manager]: Configuring controller: 'joint_state_broadcaster'
[ros2_control_node-3] [INFO] [1763724274.822653099] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[ros2_control_node-3] [INFO] [1763724274.834095975] [controller_manager]: Activating controllers: [ joint_state_broadcaster ]
[ros2_control_node-3] [INFO] [1763724274.843294875] [controller_manager]: Successfully switched controllers!
[spawner-5] [INFO] [1763724274.854204354] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[INFO] [spawner-5]: process has finished cleanly [pid 317964]
[rviz2-4] [INFO] [1763724275.086250976] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-4] [INFO] [1763724275.086310889] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[ros2_control_node-3] [INFO] [1763724275.137009951] [controller_manager]: Loading controller : 'gripper_controller' of type 'parallel_gripper_action_controller/GripperActionController'
[ros2_control_node-3] [INFO] [1763724275.137040143] [controller_manager]: Loading controller 'gripper_controller'
[ros2_control_node-3] [INFO] [1763724275.138316663] [controller_manager]: Controller 'gripper_controller' node arguments: --ros-args --params-file /home/user/GITS/simulation_ros2_ws/ros2_ws/install/mp3_moveit_config/share/mp3_moveit_config/config/ros2_controllers_mock_sim.yaml --params-file /tmp/launch_params_mc75z4sp 
[spawner-7] [INFO] [1763724275.163537403] [spawner_gripper_controller]: Loaded gripper_controller
[ros2_control_node-3] [INFO] [1763724275.164342347] [controller_manager]: Configuring controller: 'gripper_controller'
[ros2_control_node-3] [INFO] [1763724275.164402061] [gripper_controller]: Action status changes will be monitored at 20.000000 Hz.
[ros2_control_node-3] [INFO] [1763724275.164417326] [gripper_controller]: Joint name is : finger_joint
[rviz2-4] [INFO] [1763724275.173675380] [rviz2]: Stereo is NOT SUPPORTED
[ros2_control_node-3] [INFO] [1763724275.174533577] [controller_manager]: Activating controllers: [ gripper_controller ]
[ros2_control_node-3] [INFO] [1763724275.185314006] [controller_manager]: Successfully switched controllers!
[spawner-7] [INFO] [1763724275.194747909] [spawner_gripper_controller]: Configured and activated gripper_controller
[rviz2-4] Warning: class_loader.impl: SEVERE WARNING!!! A namespace collision has occurred with plugin factory for class rviz_default_plugins::displays::InteractiveMarkerDisplay. New factory will OVERWRITE existing one. This situation occurs when libraries containing plugins are directly linked against an executable (the one running right now generating this message). Please separate plugins out into their own library or just don't link against the library and use either class_loader::ClassLoader/MultiLibraryClassLoader to open.
[rviz2-4]          at line 321 in /opt/ros/jazzy/include/class_loader/class_loader/class_loader_core.hpp
[INFO] [spawner-7]: process has finished cleanly [pid 317966]
[ros2_control_node-3] [INFO] [1763724275.486819248] [controller_manager]: Loading controller : 'arm_controller' of type 'joint_trajectory_controller/JointTrajectoryController'
[ros2_control_node-3] [INFO] [1763724275.486862720] [controller_manager]: Loading controller 'arm_controller'
[ros2_control_node-3] [INFO] [1763724275.488673560] [controller_manager]: Controller 'arm_controller' node arguments: --ros-args --params-file /home/user/GITS/simulation_ros2_ws/ros2_ws/install/mp3_moveit_config/share/mp3_moveit_config/config/ros2_controllers_mock_sim.yaml --params-file /tmp/launch_params_mc75z4sp 
[spawner-6] [INFO] [1763724275.511619760] [spawner_arm_controller]: Loaded arm_controller
[ros2_control_node-3] [INFO] [1763724275.512214183] [controller_manager]: Configuring controller: 'arm_controller'
[ros2_control_node-3] [INFO] [1763724275.512380146] [arm_controller]: No specific joint names are used for command interfaces. Using 'joints' parameter.
[ros2_control_node-3] [INFO] [1763724275.512399099] [arm_controller]: Command interfaces are [position] and state interfaces are [position velocity].
[ros2_control_node-3] [INFO] [1763724275.512415204] [arm_controller]: Using 'splines' interpolation method.
[ros2_control_node-3] [INFO] [1763724275.513414167] [arm_controller]: Action status changes will be monitored at 20.00 Hz.
[ros2_control_node-3] [INFO] [1763724275.524099586] [controller_manager]: Activating controllers: [ arm_controller ]
[ros2_control_node-3] [INFO] [1763724275.533511730] [controller_manager]: Successfully switched controllers!
[spawner-6] [INFO] [1763724275.544557108] [spawner_arm_controller]: Configured and activated arm_controller
[INFO] [spawner-6]: process has finished cleanly [pid 317965]
[rviz2-4] [ERROR] [1763724278.261412029] [moveit_2191837037.moveit.ros.motion_planning_frame]: Action server: /recognize_objects not available
[rviz2-4] [INFO] [1763724278.271466393] [moveit_2191837037.moveit.ros.motion_planning_frame]: MoveGroup namespace changed: / -> . Reloading params.
[rviz2-4] [INFO] [1763724278.277517074] [rviz]: Subscribing to: /depth_pcl
[rviz2-4] 
[rviz2-4] [INFO] [1763724278.277784611] [rviz]: Subscribing to: /depth_pcl
[rviz2-4] 
[rviz2-4] [INFO] [1763724278.282130549] [moveit_2191837037.moveit.ros.rdf_loader]: Loaded robot model in 0.00303916 seconds
[rviz2-4] [INFO] [1763724278.282186580] [moveit_2191837037.moveit.core.robot_model]: Loading robot model 'mp3'...
[rviz2-4] [INFO] [1763724278.282198271] [moveit_2191837037.moveit.core.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[rviz2-4] [INFO] [1763724279.289234390] [rviz]: Subscribing to: /depth_pcl
[rviz2-4] 
[rviz2-4] [INFO] [1763724279.347142949] [moveit_2191837037.moveit.ros.rdf_loader]: Loaded robot model in 0.00185957 seconds
[rviz2-4] [INFO] [1763724279.347197220] [moveit_2191837037.moveit.core.robot_model]: Loading robot model 'mp3'...
[rviz2-4] [INFO] [1763724279.347206069] [moveit_2191837037.moveit.core.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[rviz2-4] [INFO] [1763724279.365626957] [moveit_2191837037.moveit.kinematics.kdl_kinematics_plugin]: Joint weights for group 'arm': 1 1 1 1 1 1 1
[rviz2-4] [INFO] [1763724279.408099481] [moveit_2191837037.moveit.ros.planning_scene_monitor]: Publishing maintained planning scene on 'monitored_planning_scene'
[simple_mover-8] [INFO] [1763724279.491332521] [moveit_3864290953.moveit.ros.rdf_loader]: Loaded robot model in 0.00292238 seconds
[simple_mover-8] [INFO] [1763724279.491393488] [moveit_3864290953.moveit.core.robot_model]: Loading robot model 'mp3'...
[simple_mover-8] [INFO] [1763724279.491404355] [moveit_3864290953.moveit.core.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[simple_mover-8] [INFO] [1763724279.507416169] [moveit_3864290953.moveit.kinematics.kdl_kinematics_plugin]: Joint weights for group 'arm': 1 1 1 1 1 1 1
[simple_mover-8] [INFO] [1763724279.540252792] [simple_mover]: Planning task...
[simple_mover-8] [INFO] [1763724279.542999783] [simple_mover]: Planning successful. Found 1 solutions.
[rviz2-4] [INFO] [1763724279.596364498] [moveit_2191837037.moveit.ros.planning_scene_monitor]: Starting planning scene monitor
[rviz2-4] [INFO] [1763724279.597012126] [moveit_2191837037.moveit.ros.planning_scene_monitor]: Listening to '/monitored_planning_scene'
[rviz2-4] [INFO] [1763724279.605612755] [interactive_marker_display_106736754076048]: Connected on namespace: /rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic
[rviz2-4] [INFO] [1763724279.616411572] [moveit_2191837037.moveit.ros.motion_planning_frame]: group arm
[rviz2-4] [INFO] [1763724279.616433144] [moveit_2191837037.moveit.ros.motion_planning_frame]: Constructing new MoveGroup connection for group 'arm' in namespace ''
[rviz2-4] [INFO] [1763724279.624550014] [moveit_2191837037.moveit.ros.move_group_interface]: Ready to take commands for planning group arm.
[rviz2-4] [INFO] [1763724279.684679055] [interactive_marker_display_106736754076048]: Sending request for interactive markers
[rviz2-4] [INFO] [1763724279.747463659] [interactive_marker_display_106736754076048]: Service response received for initialization
[simple_mover-8] [INFO] [1763724281.543527302] [simple_mover]: Executing the best solution...
[move_group-2] [WARN] [1763724281.548836318] [moveit_task_constructor_visualization.execute_task_solution]: The trajectory of stage '3' from task '' does not have any controllers specified for trajectory execution. This might lead to unexpected controller selection.
[move_group-2] [INFO] [1763724281.548862451] [moveit_task_constructor_visualization.execute_task_solution]: Executing TaskSolution
[move_group-2] [INFO] [1763724281.548912781] [move_group.moveit.moveit.plugins.simple_controller_manager]: Returned 2 controllers in list
[move_group-2] [INFO] [1763724281.548940052] [move_group.moveit.moveit.plugins.simple_controller_manager]: Returned 2 controllers in list
[move_group-2] [INFO] [1763724281.548985229] [move_group.moveit.moveit.ros.trajectory_execution_manager]: Validating trajectory with allowed_start_tolerance 0.01
[move_group-2] [INFO] [1763724281.553511913] [move_group.moveit.moveit.ros.trajectory_execution_manager]: Starting trajectory execution ...
[move_group-2] Stack trace (most recent call last) in thread 318363:
[move_group-2] [INFO] [1763724281.553574916] [move_group.moveit.moveit.plugins.simple_controller_manager]: Returned 2 controllers in list
[move_group-2] [INFO] [1763724281.553595780] [move_group.moveit.moveit.plugins.simple_controller_manager]: Returned 2 controllers in list
[move_group-2] [INFO] [1763724281.554189097] [move_group.moveit.moveit.plugins.simple_controller_manager]: Returned 2 controllers in list
[move_group-2] [INFO] [1763724281.554206520] [move_group.moveit.moveit.plugins.simple_controller_manager]: Returned 2 controllers in list
[move_group-2] [INFO] [1763724281.554319312] [moveit.simple_controller_manager.follow_joint_trajectory_controller_handle]: sending trajectory to arm_controller
[ros2_control_node-3] [INFO] [1763724281.554537787] [arm_controller]: Received new action goal
[ros2_control_node-3] [INFO] [1763724281.554587037] [arm_controller]: Accepted new action goal
[move_group-2] [INFO] [1763724281.554704800] [moveit.simple_controller_manager.follow_joint_trajectory_controller_handle]: arm_controller started execution
[move_group-2] [INFO] [1763724281.554720047] [moveit.simple_controller_manager.follow_joint_trajectory_controller_handle]: Goal request accepted!
[move_group-2] #10   Object "/usr/lib/x86_64-linux-gnu/ld-linux-x86-64.so.2", at 0xffffffffffffffff, in 
[move_group-2] #9    Source "../sysdeps/unix/sysv/linux/x86_64/clone3.S", line 78, in clone3 [0x7751aa729c6b]
[move_group-2] #8    Source "./nptl/pthread_create.c", line 447, in start_thread [0x7751aa69caa3]
[move_group-2] #7    Source "../../../../../src/libstdc++-v3/src/c++11/thread.cc", line 104, in execute_native_thread_routine [0x7751aaaecdb3]
[move_group-2] #6    Object "/home/user/GITS/simulation_ros2_ws/ros2_ws/install/moveit_task_constructor_capabilities/lib/libmoveit_task_constructor_capabilities.so", at 0x775195e2c720, in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<void (move_group::ExecuteTaskSolutionCapability::*)(std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_task_constructor_msgs::action::ExecuteTaskSolution> > const&), move_group::ExecuteTaskSolutionCapability*, std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_task_constructor_msgs::action::ExecuteTaskSolution> > > >, void>::_M_run()
[move_group-2] #5    Source "./nptl/pthread_once.c", line 116, in __pthread_once_slow [0x7751aa6a1ed2]
[move_group-2] #4  | Source "/usr/include/c++/13/future", line 589, in operator()
[move_group-2]     |   587:       _M_do_set(function<_Ptr_type()>* __f, bool* __did_set)
[move_group-2]     |   588:       {
[move_group-2]     | > 589:         _Ptr_type __res = (*__f)();
[move_group-2]     |   590:         // Notify the caller that we did try to set; if we do not throw an
[move_group-2]     |   591:         // exception, the caller will be aware that it did set (e.g., see
[move_group-2]       Source "/usr/include/c++/13/bits/std_function.h", line 591, in _M_do_set [0x7751ab1da7a1]
[move_group-2]         588:       {
[move_group-2]         589:     if (_M_empty())
[move_group-2]         590:       __throw_bad_function_call();
[move_group-2]       > 591:     return _M_invoker(_M_functor, std::forward<_ArgTypes>(__args)...);
[move_group-2]         592:       }
[move_group-2]         593: 
[move_group-2]         594: #if __cpp_rtti
[move_group-2] #3    Object "/home/user/GITS/simulation_ros2_ws/ros2_ws/install/moveit_task_constructor_capabilities/lib/libmoveit_task_constructor_capabilities.so", at 0x775195e2b21f, in std::_Function_handler<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> (), std::__future_base::_Task_setter<std::unique_ptr<std::__future_base::_Result<void>, std::__future_base::_Result_base::_Deleter>, std::thread::_Invoker<std::tuple<void (move_group::ExecuteTaskSolutionCapability::*)(std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_task_constructor_msgs::action::ExecuteTaskSolution> > const&), move_group::ExecuteTaskSolutionCapability*, std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_task_constructor_msgs::action::ExecuteTaskSolution> > > >, void> >::_M_invoke(std::_Any_data const&)
[move_group-2] #2    Object "/home/user/GITS/simulation_ros2_ws/ros2_ws/install/moveit_task_constructor_capabilities/lib/libmoveit_task_constructor_capabilities.so", at 0x775195e2a8c3, in move_group::ExecuteTaskSolutionCapability::execCallback(std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_task_constructor_msgs::action::ExecuteTaskSolution> > const&)
[move_group-2] #1    Source "/usr/src/ros-jazzy-moveit-ros-planning-2.12.3-1noble.20251008.071550/plan_execution/src/plan_execution.cpp", line 475, in executeAndMonitor [0x7751aace603c]
[move_group-2] #0  | Source "/usr/src/ros-jazzy-moveit-core-2.12.3-1noble.20251008.063839/robot_state/src/robot_state.cpp", line 1226, in begin
[move_group-2]     | Source "/usr/include/c++/13/bits/stl_map.h", line 378, in begin
[move_group-2]     |   376:       const_iterator
[move_group-2]     |   377:       begin() const _GLIBCXX_NOEXCEPT
[move_group-2]     | > 378:       { return _M_t.begin(); }
[move_group-2]     |   379: 
[move_group-2]     |   380:       /**
[move_group-2]       Source "/usr/include/c++/13/bits/stl_tree.h", line 1002, in getAttachedBodies [0x7751aa9c474b]
[move_group-2]        1000:       const_iterator
[move_group-2]        1001:       begin() const _GLIBCXX_NOEXCEPT
[move_group-2]       >1002:       { return const_iterator(this->_M_impl._M_header._M_left); }
[move_group-2]        1003: 
[move_group-2]        1004:       iterator
[move_group-2]        1005:       end() _GLIBCXX_NOEXCEPT
[move_group-2] Segmentation fault (Address not mapped to object [0xe8])
[ros2_control_node-3] [INFO] [1763724282.483160918] [arm_controller]: Goal reached, success!
[ERROR] [move_group-2]: process has died [pid 317961, exit code -11, cmd '/opt/ros/jazzy/lib/moveit_ros_move_group/move_group --ros-args --params-file /tmp/launch_params_m91ihx41 --params-file /tmp/launch_params_slbj1wic'].

Here is my simple .cpp file

#include <moveit/moveit_cpp/moveit_cpp.h>
#include <moveit/task_constructor/solvers/cartesian_path.h>
#include <moveit/task_constructor/solvers/joint_interpolation.h>
// #include <moveit/task_constructor/solvers/pipeline_planner.h>
#include <moveit/task_constructor/stages/connect.h>
#include <moveit/task_constructor/stages/current_state.h>
#include <moveit/task_constructor/stages/fixed_state.h>
#include <moveit/task_constructor/stages/move_relative.h>
#include <moveit/task_constructor/stages/move_to.h>
#include <moveit/task_constructor/task.h>

#include <moveit/planning_scene/planning_scene.hpp>
#include <rclcpp/rclcpp.hpp>
#include <string>

using namespace moveit::task_constructor;

Task createTask(const rclcpp::Node::SharedPtr& node) {
  Task t("task");
  t.stages()->setName("Cartesian Path");
  t.loadRobotModel(node);

  const std::string group = "arm";
  const std::string eef = "gripper";
  const std::string base_frame = "base_link";
  const std::string ik_frame = "tool0";

  auto cartesian_planner = std::make_shared<solvers::CartesianPath>();
  cartesian_planner->setMaxVelocityScalingFactor(0.5);
  cartesian_planner->setMaxAccelerationScalingFactor(0.5);
  cartesian_planner->setStepSize(.01);

  auto joint_interpolation = std::make_shared<solvers::JointInterpolationPlanner>();
  auto scene = std::make_shared<planning_scene::PlanningScene>(t.getRobotModel());

  {
    auto& state = scene->getCurrentStateNonConst();
    state.setToDefaultValues(state.getJointModelGroup(group), "home");
    auto fixed = std::make_unique<stages::FixedState>("initial state");
    fixed->setState(scene);
    t.add(std::move(fixed));
  }

  {
    auto stage = std::make_unique<stages::MoveRelative>("x +0.2", cartesian_planner);
    stage->setGroup(group);
    stage->setIKFrame(ik_frame);
    geometry_msgs::msg::Vector3Stamped direction;
    direction.header.frame_id = base_frame;
    direction.vector.x = 0.2;
    stage->setDirection(direction);
    t.add(std::move(stage));
  }

  return t;
}

int main(int argc, char** argv) {
  rclcpp::init(argc, argv);
  auto node = rclcpp::Node::make_shared("simple_mover");
  std::thread spinning_thread([node] { rclcpp::spin(node); });
  rclcpp::sleep_for(std::chrono::seconds(5));

  auto task = createTask(node);
  size_t max_solutions = 5;
  try {
    RCLCPP_INFO(node->get_logger(), "Planning task...");
    if (task.plan(max_solutions)) {
      RCLCPP_INFO(node->get_logger(), "Planning successful. Found %zu solutions.", task.solutions().size());
      task.introspection().publishSolution(*task.solutions().front());

      rclcpp::sleep_for(std::chrono::seconds(2));
      RCLCPP_INFO(node->get_logger(), "Executing the best solution...");
      auto result = task.execute(*task.solutions().front());

      if (result.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS) {
        RCLCPP_ERROR(node->get_logger(), "Task execution failed");
      } else {
        RCLCPP_INFO(node->get_logger(), "Task executed successfully!");
      }
    } else {
      RCLCPP_ERROR(node->get_logger(), "Planning failed");
    }
  } catch (const InitStageException& ex) {
    RCLCPP_ERROR_STREAM(node->get_logger(), "Task initialization failed: " << ex);
  }

  // keep alive for interactive inspection in rviz
  spinning_thread.join();
  return 0;
}

It is a custom manipulator on which a robotiq 2f140 gripper is attached. I can control the manipulator correctly with MoveIt plugin for RViz and the trajectories are successfully executed.

I don't know what could cause this as my example is based on the official example. Surprisingly, the trajectory starts to be executed but then the move_group node crashes

Setup:

Ubuntu 24.04
ROS2 Jazzy,
MoveIt binary install
MTC source install (jazzy branch)
Custom moveit config (made with setup assistant) for a yaskawa robot

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions