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

Is it possible to get a list of all the current collision objects using the MoveIt API?

asked 2020-02-12 20:22:49 -0500

sdfryc gravatar image

Hi, I would like to get a list of all the collision object currently in the planning scene using the C++ MoveIt API.

My main goal is to be able to clear all collision objects in the environment. My approach will be to obtain a list of all the current collision objects which I can then iteratively delete using the object list.

System: Ubuntu 16.04 & ROS Kinetic

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-02-13 08:52:24 -0500

Use planning scene interface class to manipulate collision objects. You can directly remove all existing collision objects with removeCOllisionObejects() or get a list of current objects with getCollisionObejcts()

Refer to the related API interface here

edit flag offensive delete link more

Comments

Thanks, atas.

I'm now able to get a list of the collision objects in the scene using getCollisionObjects(). However, for some reason I'm unable to remove collision objects using removeCollisionObjects().

For example I tried:

int main(int argc, char **argv) 
{
    ros::init(argc, argv, "remove_collision");
    ros::NodeHandle node_handle("~");

    ros::AsyncSpinner spinner(1);
    spinner.start();

    moveit::planning_interface::PlanningSceneInterface current_scene;
    sleep(1.0);

    std::vector<std::string> object_ids;
    object_ids.push_back("box1");
    current_scene.removeCollisionObjects(object_ids);
    ROS_INFO("remove an object from the world");

    ros::shutdown();
}

Perhaps that is a question for a new thread. For now I'm able to remove the objects using the planning scene diffs via a rosservice call to '/apply_planning_scene'.

sdfryc gravatar image sdfryc  ( 2020-02-13 20:31:53 -0500 )edit

get a list of current objects with getCollisionObjects()

That's unavailable

abhishek47 gravatar image abhishek47  ( 2021-10-11 07:25:58 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-02-12 20:22:49 -0500

Seen: 785 times

Last updated: Feb 13 '20