ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to attach an object for collision check in motion planning

asked 2020-10-15 02:49:34 -0500

furushchev gravatar image

Hi, I'm trying to use MoveIt! for planning motion avoiding collisions between robot links and collision object attached to the end effector of the robot manually and finding usages by simply calling several ROS services instead of using any interface (e.g. MoveGroupInterface) for the simplicity of codes.

It looks there are at least two ways to tell a planner about attached objects to robot links. My question is which API is better to use, from the perspective of function, difficulty and support.

  1. Use of /apply_planning_scene service, then /plan_kinematic_path service

    Firstly, call /apply_planning_scene which takes moveit_msgs/ApplyPlanningScene, where we can define attached collision objects by setting them in ApplyPlanningSceneRequest.scene.robot_state.attached_collision_objects. After receiving its result with a boolean success set to true, then call /plan_kinematic_path for getting the result of motion planning.

    I tried this method, but I doubt a planner actually consider attached collision objects on motion planning, because it sometimes produces trajectory which contains collision in the middle of it.

  2. Use of /plan_kinematic_path service only

    The service /plan_kinematic_path takes moveit_msgs/GetMotionPlan service, which also has a field for describing collision objects at GetMotionPlanRequest.motion_plan_request.start_state.attached_collision_objects. Is it enough to set the field with initial robot joint state and the target one?

    I tried the method too and also got trajectory which contains points in collision.

Or is there any other proper way to use planning service for getting planned motion avoiding collisions between attached objects and robots?

Any suggestion or comment are very welcome! Thank you very much in advance!

edit retag flag offensive close merge delete

Comments

You do need to attach collision objects to the robot for it to be considered in collision checking, but the /plan_kinematic_path service uses the attached_collision_objects provided in the message (including if you don't supply any). Could you provide examples of trajectories that contain collisions?

fvd gravatar image fvd  ( 2020-10-15 08:40:40 -0500 )edit

@fvd Thank you for the comment and sorry for the late reply. Unfortunately, I cannot make the test case public right now, but found how to use planning with attached collision objects correctly (which I "answered"). Anyway, thank you for your advice!

furushchev gravatar image furushchev  ( 2020-11-30 05:02:23 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-11-30 05:00:08 -0500

furushchev gravatar image

After several months, we found the cause of this issue.

As for No.2 in my question, we got trajectory which contains points in collision because the collision objects which is set in GetMotionPlanRequest.motion_plan_request.start_state.attached_collision_objects accidentally have the same name as robot link names. Since, we guess, MoveIt! assumes there is only one name space on collision objects including robot links and attached collision objects, they are just ignored and it generated plan including collision.

After renaming the attached collision objects by adding unique prefix, we confirmed that there is no more collision in planned path.

edit flag offensive delete link more

Comments

Thanks for following up! I made a MoveIt issue to avoid this edge case in the future.

fvd gravatar image fvd  ( 2020-11-30 12:41:06 -0500 )edit

@fvd Thank you very much!!

furushchev gravatar image furushchev  ( 2020-11-30 18:46:19 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-10-15 02:49:34 -0500

Seen: 952 times

Last updated: Nov 30 '20