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

How to disable collision between a link and a newly added collision object?

asked 2020-12-16 19:44:46 -0500

srujan gravatar image

I have a scene with UR10 arm mounted on wall. I also have a table. I have this entire scene configured using moveit setup assistant.

I launch the scene. I then run a node(part_spawner) which spawns a mesh on the table(I am doing this by loading a mesh and adding this mesh as a collision object to planning_scene_interface). My rviz screen properly loads it and spawns it, as expected rviz also shows that there is a collision between the table and the mesh. But when I check for the collisions in the same node(part_spawner) using planning_scene.CheckCollision(collision_request, collision_result, copied_state, allowed_collision_matrix), the collision_result does not return any contact between table and mesh. I'm guessing this should ideally return a pair of contact (table, mesh)

My goal is to manually disable this specific collision by adding the pair (table, mesh) to the Allowed Collision Matrix using allowedCollisionMatrix.setEntry('table', 'mesh', true). But the collision is not being detected in the first place.

Is this the right way of doing it?

Is there a better way to do it?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-12-16 21:02:37 -0500

fvd gravatar image

updated 2020-12-17 03:44:15 -0500

gvdhoorn gravatar image

Yes, you describe the correct way of disabling collision checking between two bodies.

But this post contains the unspoken question "Why are collisions not detected for my newly added collision object?", which needs to be answered: I suspect that the PlanningScene object that you are calling checkCollision on is not the same as the one that RViz displays, and that is why you are not seeing the collision. You can use a PlanningSceneMonitor to get the newest scene, or use the /get_planning_scene service (this is probably easier). Here is some boilerplate code for the latter, which you can copy from:

bool SkillServer::updatePlanningScene()
{
  moveit_msgs::GetPlanningScene srv;
  // Request only the collision matrix
  srv.request.components.components = moveit_msgs::PlanningSceneComponents::ALLOWED_COLLISION_MATRIX;
  get_planning_scene_client.call(srv);
  if (get_planning_scene_client.call(srv))
  {
    ROS_INFO("Got planning scene from move group.");
    planning_scene_ = srv.response.scene;
    return true;
  }
  else
  {
    ROS_ERROR("Failed to get planning scene from move group.");
    return false;
  }
}

Regarding a better way to enable/disable collisions: Internally I am using this extension of the planning_scene_interface that defines the functions allowCollisions and disallowCollisions and connects them to the Python interface as well, but we did not merge this upstream because the updating method is not strictly safe. If you are confident that it does not affect your application, you can use those changes as well.

Related question: https://answers.ros.org/question/3598...

edit flag offensive delete link more

Comments

Thanks for the answer @fvd . I used this post as a reference to get this working

srujan gravatar image srujan  ( 2020-12-18 15:15:05 -0500 )edit

Thanks for adding the reference. Don't forget to accept the answer to take the question out of the queue, too.

fvd gravatar image fvd  ( 2020-12-18 22:35:00 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-12-16 19:44:46 -0500

Seen: 1,636 times

Last updated: Dec 17 '20