moveit / moveit_task_constructor

A hierarchical multi-stage manipulation planner
https://moveit.github.io/moveit_task_constructor
BSD 3-Clause "New" or "Revised" License
176 stars 150 forks source link

allowCollisions() is not working in ros2 iron #617

Open qboticslabs opened 4 days ago

qboticslabs commented 4 days ago

I am testing the following snippet before attaching the object1 to eef

    {
      auto stage = std::make_unique<stages::ModifyPlanningScene>("allow collision (object,support)");
      stage->allowCollisions("object1", true);
      c->insert(std::move(stage));

    }  

But it is still raising this error. The task planning works fine, but execution is raising this issue.

 Found a contact between 'object1' (type 'Object') and 'object1' (type 'Robot attached'), which constitutes a collision. Contact information is not stored.
[move_group-4] [INFO] [1727730076.878482284] [moveit_collision_detection_fcl.collision_common]: Collision checking is considered complete (collision was found and 0 contacts are stored)
[move_group-4] [INFO] [1727730076.878487975] [moveit_ros.plan_execution]: Trajectory component '9/59' is invalid after scene update
[move_group-4] [INFO] [1727730076.878541415] [moveit_ros.plan_execution]: Stopping execution because the path to execute became invalid(probably the environment changed)
[move_group-4] [INFO] [1727730076.878565020] [moveit.simple_controller_manager.follow_joint_trajectory_controller_handle]: Cancelling execution for tmr_arm_controller

Any support is appreciated.

I am testing in ROS 2 Iron using iron branch

tejasps28 commented 3 days ago

@rhaschke I am facing the similar issue while trying the demo

rhaschke commented 3 days ago

Can you please provide a minimal example illustrating the issue. So far, I cannot reproduce the problem. Rather, I'm running into issues with the time parameterization of trajectories: [panda_arm_controller]: Velocity of last trajectory point of joint panda_joint1 is not zero: 0.000669435750263

tejasps28 commented 3 days ago

Hello @rhaschke , i ran the following: ros2 launch moveit_task_constructor_demo demo.launch.py ros2 launch moveit_task_constructor_demo run.launch.py exe:=pick_place_demo

[pick_place_demo-1] [WARN] [1727800677.541984012] [moveit.ros_planning.planning_pipeline]: The planner plugin did not fill out the 'planner_id' field of the MotionPlanResponse. Setting it to the planner ID name of the MotionPlanRequest assuming that the planner plugin does warn you if it does not use the requested planner.
[pick_place_demo-1] [INFO] [1727800677.543467512] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'panda_arm' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[pick_place_demo-1] [WARN] [1727800677.590002228] [moveit.ros_planning.planning_pipeline]: The planner plugin did not fill out the 'planner_id' field of the MotionPlanResponse. Setting it to the planner ID name of the MotionPlanRequest assuming that the planner plugin does warn you if it does not use the requested planner.
[pick_place_demo-1] [INFO] [1727800677.641499349] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'hand' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[pick_place_demo-1] [WARN] [1727800677.686122887] [moveit.ros_planning.planning_pipeline]: The planner plugin did not fill out the 'planner_id' field of the MotionPlanResponse. Setting it to the planner ID name of the MotionPlanRequest assuming that the planner plugin does warn you if it does not use the requested planner.
[pick_place_demo-1] [INFO] [1727800677.736683650] [moveit_task_constructor_demo]: Planning succeded
[pick_place_demo-1] [INFO] [1727800677.736720149] [moveit_task_constructor_demo]: Executing solution trajectory
[pick_place_demo-1] [ERROR] [1727800679.564232672] [moveit_task_constructor_executor_101374747802880]: Goal was aborted or canceled
[pick_place_demo-1] [ERROR] [1727800679.570692870] [moveit_task_constructor_demo]: Task execution failed and returned: 99999
[pick_place_demo-1] [INFO] [1727800679.570841940] [moveit_task_constructor_demo]: Execution complete

this was the error that has popped up. In Rviz2, i can see the arm movement begins when i set flag "execute:true" in the yaml, but in a pre-grasp pose it gets stuck with the above mentioned error. I am using mtc from the 'iron' branch. image

rhaschke commented 2 days ago

@tejasps28, the more interesting error log is the one from the demo.launch.py console. There, I guess, you have the error reported in https://github.com/moveit/moveit_task_constructor/issues/617#issuecomment-2385747476.