Obstacles Management in moveit

3,292 views
Skip to first unread message

ksat...@gmail.com

unread,
Apr 27, 2014, 1:31:02 AM4/27/14
to moveit...@googlegroups.com

Hello,

I would be delighted if someone can explain very clearly.

I have recently started working on a robot that has a Jaco Arm. (MetraLab Scitos G5).

I am using the ASUS xtion pro for the obstacle avoidance. Once this is done, I am able to view the Octree in the monitored_planning_scene topic (using rviz).

1. I also found that I could specify collision objects using the PlanningSceneInterface Class. What is the difference between the two approaches?

2. Also, what is the exact approach to using a PlanningSceneMonitor. In the planning scene tutorial, it is mentioned that the PlanninSceneMonitor is the elegant way to manage a Planning Scene. But, is there a tutorial for the PlanningSceneMonitor?

3. I saw that the PlanningSceneMonitor has a protected function called "excludeWorldObjectFromOctree()" .

Sometimes when I try to grasp an object (using xtion for obstacle avoidance), the plan fails since there is a potential collision between the fingers of the JACO arm and the object that I intend to pickup. I thought I could add it as a World object using the Planning Scene Interface (this I am able to do) and then use the "excludeWorldObjectFromOctree()" method to exclude the object from being considered for collision checking. Is there a more straight forward way of excluding a world object from collision checking?

4. I have somewhat understood how you could modify the AllowedCollisionMatrix. But then, how do I ensure that this ACM is updated to the current Planning Scene? I expect that there is a method in PlanningSceneInterface like "updateAllowedCollisionMatrix()" ? Am I guessing right? or is there a serious error in my understanding?

Please clarify!

Thank you so much!


Chittaranjan S Srinivas

Orebro University

Martin Günther

unread,
Apr 28, 2014, 7:38:44 AM4/28/14
to moveit...@googlegroups.com
Hi Chittaranjan,

On Sat, 26 Apr 2014 22:31:02 -0700 (PDT)
ksat...@gmail.com wrote:
>
>
> Hello,
>
> I would be delighted if someone can explain very clearly.
>
> I have recently started working on a robot that has a Jaco Arm.
> (MetraLab Scitos G5).
>
> I am using the ASUS xtion pro for the obstacle avoidance. Once this
> is done, I am able to view the Octree in the monitored_planning_scene
> topic (using rviz).
>
> *1.* I also found that I could specify collision objects using the
> PlanningSceneInterface Class. What is the difference between the two
> approaches?

The octomap is updated live from your Xtion sensor data. The collision
objects are added by you. They are used to add collision objects that
you know the position of; the most common way is to have some sort of
object recognition node that recognizes, for example, tabletop objects,
and adds these objects as collision objects to the PlanningSceneWorld.
(If you look at moveit_msgs/PlanningSceneWorld, you can see that it has
one octomap and a list of collision objects).

You can add objects by either publishing to the "/collision_object"
topic, or by using a convenience function from the move_group C++
interface.

Once a collision object is added to the PlanningScene, the voxels that
overlap with it are automatically filtered out of the octomap. You do
not need to call excludeWorldObjectFromOctree() yourself (that's
probably why it's protected).

By default, collision checking is done between all robot links and the
octomap, and between all robot links and each collision object.
However, you can disable collision checks between certain robot links
and certain collision objects, and that's exactly what you should do:
disable collision checking between the fingers and the object you're
trying to pick up. There are basically two ways to do it:

1. Disable the collision checks before calling the move_group action.
All calls to the move_group action after that will ignore those
collisions. You'll have to remember to re-enable the collisions
afterwards.

2. Specify the allowed collisions for that specific move_group call
only, as a parameter of that action call. This is somewhat nicer in
my opinion.

For (1), there are a couple of options:

1a. Using the PlanningSceneMonitor. From C++, I think this is better
than the solution (1b) below. It should go something like this
(warning, completely untested!):

#include <moveit/planning_scene_monitor/planning_scene_monitor.h>

planning_scene_monitor::PlanningSceneMonitorPtr psm = planning_scene_monitor::PlanningSceneMonitorPtr(
new planning_scene_monitor::PlanningSceneMonitor("robot_description", tf, "name"));

planning_scene_monitor::LockedPlanningSceneRW planning_scene = planning_scene_monitor::LockedPlanningSceneRW(psm);

collision_detection::AllowedCollisionMatrix acm = planning_scene->getAllowedCollisionMatrix();

// TODO: modify acm here as explained in the PlanningScene tutorial: http://docs.ros.org/api/pr2_moveit_tutorials/html/planning/src/doc/planning_scene_tutorial.html

As an inspiration, I found digging through this code helpful: https://github.com/ros-planning/moveit_ros/tree/hydro-devel/visualization/planning_scene_rviz_plugin


1b. Publishing to the "/planning_scene" topic. From Python, it looks
like this:

self._pubPlanningScene = rospy.Publisher('planning_scene', PlanningScene)
rospy.wait_for_service('/get_planning_scene', 10.0)
get_planning_scene = rospy.ServiceProxy('/get_planning_scene', GetPlanningScene)
request = PlanningSceneComponents(components=PlanningSceneComponents.ALLOWED_COLLISION_MATRIX)
response = get_planning_scene(request)

acm = response.scene.allowed_collision_matrix
if not 'button' in acm.default_entry_names:
# add button to allowed collision matrix
acm.default_entry_names += ['button']
acm.default_entry_values += [True]

planning_scene_diff = PlanningScene(
is_diff=True,
allowed_collision_matrix=acm)

self._pubPlanningScene.publish(planning_scene_diff)
rospy.sleep(1.0)


For (2), you can use the same planning_scene_diff that I computed above
by putting it into your MoveGroupGoal.planning_options.planning_scene_diff.
It's important that you really get the current allowed collision matrix first
and then modify it, as shown above.

Note that I added the collision object to the default_entry_names,
which means that collisions between that object and *all* robot links are
allowed, not just the fingers. That's bad, but I couldn't make it work
otherwise.


Another option for you is to use the `pick` action instead of implementing
it yourself with move_group calls. It wraps the move_group action, and it
automatically handles the allowed collision matrix etc. for you. One small
example of using it is here:

https://github.com/uos/calvin_robot/blob/hydro/calvin_pick_n_place/src/calvin_pick_n_place.cpp

> *2.* Also, what is the exact approach to using a
> PlanningSceneMonitor. In the planning scene tutorial, it is mentioned
> that the PlanninSceneMonitor is the elegant way to manage a Planning
> Scene. But, is there a tutorial for the PlanningSceneMonitor?

Not that I know of. The Planning Scene tutorial says that it's
"discussed in detail in the next tutorial", but that never got written
if I'm correct. (Please, everyone, correct me if I'm wrong!)

> *3.* I saw that the PlanningSceneMonitor has a protected function
> called "excludeWorldObjectFromOctree()" .
>
> Sometimes when I try to grasp an object (using xtion for obstacle
> avoidance), the plan fails since there is a potential collision
> between the fingers of the JACO arm and the object that I intend to
> pickup. I thought I could add it as a World object using the Planning
> Scene Interface (this I am able to do) and then use the
> "excludeWorldObjectFromOctree()" method to exclude the object from
> being considered for collision checking. Is there a more straight
> forward way of excluding a world object from collision checking?

See above. Once you add a CollisionObject, it is automatically excluded
from the octomap, but of course not from collision checking.

> *4.* I have somewhat understood how you could modify the
> AllowedCollisionMatrix. But then, how do I ensure that this ACM is
> updated to the current Planning Scene? I expect that there is a
> method in PlanningSceneInterface like
> "updateAllowedCollisionMatrix()" ? Am I guessing right? or is there a
> serious error in my understanding?

See above.

> Please clarify!
>
> Thank you so much!
>
>
> Chittaranjan S Srinivas
>
> Orebro University

Cheers,
Martin


--
Dipl.-Inf. Martin Günther
Universität Osnabrück
Institut für Informatik
Albrechtstr. 28 (Raum 31/503)
D-49076 Osnabrück

Fon: 0541 969 2434
http://www.inf.uos.de/mguenthe/

Carlos Maestre

unread,
Aug 14, 2014, 11:01:40 AM8/14/14
to moveit...@googlegroups.com
Hi! I have a similar need, and following your comments I created the following code: I created a collision object in the same space that an object on the table. and I want to add it to the allowed collision matrix. I am able to get the collision matrix, update it, and publish it (in 2 different ways) but nothing happens. If I try to touch the objects a collision with the collision object is found.

I guess my problem comes from the point that ' rosrun info /planning_scene ' returns nothing, RViz does not publish on it. I also realize that the MoveIt's RViz plug-in is properly receiving information from the move_group node. Is this right? If I select in the MoveIt's RViz plug-in /move_group/monitor_planning_scene and I execute some (e.g. random) movement with the robot I will see it in RViz. But If I select the topic /planning_scene nothing changes on RViz. Which is the main difference about these 2 topics?

I hope at least the code is correct:

#include <moveit/move_group_interface/move_group.h>
#include <iostream>
#include <geometry_msgs/PoseStamped.h>
#include <ros/ros.h>
#include <string>

// MoveIt!
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit_msgs/PlanningScene.h>
#include <moveit_msgs/AllowedCollisionMatrix.h>
#include <moveit_msgs/GetPlanningScene.h>
#include <moveit/kinematic_constraints/utils.h>

int main(int argc, char **argv)
{
  ros::init (argc, argv, "right_arm_kinematics");
  ros::AsyncSpinner spinner(1);
  spinner.start();
    
  ros::NodeHandle nh;
  
  moveit_msgs::PlanningScene currentScene;
  moveit_msgs::PlanningScene newSceneDiff;
    
  ros::ServiceClient client_get_scene = nh.serviceClient<moveit_msgs::GetPlanningScene>("/get_planning_scene");
  moveit_msgs::GetPlanningScene scene_srv;
  scene_srv.request.components.components = scene_srv.request.components.ALLOWED_COLLISION_MATRIX;  
  
  if(!client_get_scene.call(scene_srv))
    {
ROS_WARN("Failed to call service /get_planning_scene");
    }
    else
    {
      ROS_INFO_STREAM("Initial scene!");
      currentScene = scene_srv.response.scene;
      moveit_msgs::AllowedCollisionMatrix currentACM = currentScene.allowed_collision_matrix;
      
      ROS_INFO_STREAM(currentACM.default_entry_values.size()); // Originally 0
      
      currentACM.entry_names.push_back("objects_collision_box");
      currentACM.entry_values[0].enabled.push_back(true);
      currentACM.default_entry_names.push_back("objects_collision_box");
      currentACM.default_entry_values.push_back(true);      
      
      newSceneDiff.is_diff = true;
      newSceneDiff.allowed_collision_matrix = currentACM;

// Publish using /planning_scene topic directly

      ros::Publisher planning_scene_diff_publisher = nh.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);      
      planning_scene_diff_publisher.publish(newSceneDiff);

      sleep(2);

// Publish using the ROS API
      
      robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
      robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
      planning_scene::PlanningScene planning_scene(kinematic_model);      
      planning_scene.setPlanningSceneDiffMsg(newSceneDiff);
      
      sleep(2);
    }  

// To check that the matrix was properly updated

  if(!client_get_scene.call(scene_srv))
    {
ROS_WARN("Failed to call service /get_planning_scene");
    }
    else
    {
      ROS_INFO_STREAM("Modified scene!");
      currentScene = scene_srv.response.scene;
      moveit_msgs::AllowedCollisionMatrix currentACM = currentScene.allowed_collision_matrix;    
      
      ROS_INFO_STREAM(currentACM.default_entry_values.size()); // It should be 1, but returns 0
    }
     
  ros::shutdown(); 
  return 0;
}



Julia Nitsch

unread,
Aug 23, 2014, 7:48:56 AM8/23/14
to moveit...@googlegroups.com
Hi!


Am Donnerstag, 14. August 2014 17:01:40 UTC+2 schrieb Carlos Maestre:
Hi! I have a similar need, and following your comments I created the following code: I created a collision object in the same space that an object on the table. and I want to add it to the allowed collision matrix. I am able to get the collision matrix, update it, and publish it (in 2 different ways) but nothing happens. If I try to touch the objects a collision with the collision object is found.

I guess my problem comes from the point that ' rosrun info /planning_scene ' returns nothing, RViz does not publish on it. I also realize that the MoveIt's RViz plug-in is properly receiving information from the move_group node. Is this right? If I select in the MoveIt's RViz plug-in /move_group/monitor_planning_scene and I execute some (e.g. random) movement with the robot I will see it in RViz. But If I select the topic /planning_scene nothing changes on RViz. Which is the main difference about these 2 topics?

I had the same problem. I am also publishing a collsision object (on topic /planning_scene) and want to grasp this object. I used your code as starting point. In my opinion the update of the AllowCollisionMatrix is not correct. As far as I understood this message, it represents a NxN symetric matrix of boolean values more or less. It tells which links/collsision objects are allowed to be in collision. So if you have three links it should look like:
    
            | link_1 | link_2 | link_3
 -------------------------------------------------
  link_1 |  true    | false  | true
  -------------------------------------------------
  link_2 |  false  |  true   | false  
  -------------------------------------------------
  link_3 |  true    | false  | true

So link_1 is allowed to be in collision with link_3 but not with link_2. Link_2 and link_3 are also not allowed to be in collision with each other. If you would add a collsion object 'box' to this matrix, which is allowed to be touched by all links, it would look like this:


           | link_1 | link_2 | link_3 | box
 -------------------------------------------------
  link_1 |  true  | false   | true    | true
  -------------------------------------------------
  link_2 |  false |  true   | false   | true 
  -------------------------------------------------
  link_3 |  true  | false   | true    | true
  -------------------------------------------------
  box    |  true  |   true   | true    | true

I think the rows of the matrix are represented by the vector of AllowedCollisionEntry[] entry_values (moveit_msgs/AllowedCollisionMatrix) and the columns are represented by the boolean vector enabled[] (moveit_msgs/AllowedCollisionEntry) of each of the entry_values . If I am wrong, please anyone should correct me! 

This code works in my case:

    planning_scene_diff_publisher_ = nh_.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
    [ ... ]
    void VisualTools::publishBox(geometry_msgs::PoseStamped handle_pose)
  {
        //publish collision object
        moveit_msgs::CollisionObject object;
    object.header = handle_pose.header;
    object.id = "transport_box";

    shape_msgs::SolidPrimitive primitive;
    primitive.type = primitive.BOX;
    primitive.dimensions.resize(3);
    primitive.dimensions[0] = box_height_*2.0;
    primitive.dimensions[1] = box_width_;
    primitive.dimensions[2] = box_length_;

    object.primitives.push_back(primitive);
    object.primitive_poses.push_back(handle_pose.pose);
    object.operation = attached_object.object.ADD;

    moveit_msgs::PlanningScene planning_scene_add;
    planning_scene_add.world.collision_objects.push_back(object);
    planning_scene_add.is_diff = true;
    planning_scene_diff_publisher_.publish(planning_scene_add);


    moveit_msgs::GetPlanningScene srv;
    srv.request.components.components =  moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_NAMES;

    //wait until box is published (I don't think that this is really needed)
    bool object_in_world = false;
    while(!object_in_world)
    {
        ROS_ERROR("waiting for box to appear");
        if (client_get_scene_.call(srv))
        {
            for (int i = 0; i < (int)srv.response.scene.world.collision_objects.size(); ++i)
            {
                if (srv.response.scene.world.collision_objects[i].id == "transport_box")
                    object_in_world = true;
            }
        }
    }

    moveit_msgs::PlanningScene currentScene;
    moveit_msgs::PlanningScene newSceneDiff;


    moveit_msgs::GetPlanningScene scene_srv;
    scene_srv.request.components.components = scene_srv.request.components.ALLOWED_COLLISION_MATRIX;

    if(!client_get_scene_.call(scene_srv))
    {
        ROS_WARN("Failed to call service /get_planning_scene");
    }
    else
    {
        ROS_INFO_STREAM("Initial scene!");
        currentScene = scene_srv.response.scene;
        moveit_msgs::AllowedCollisionMatrix currentACM = currentScene.allowed_collision_matrix;

        ROS_ERROR_STREAM("size of acm_entry_names before " << currentACM.entry_names.size());
        ROS_ERROR_STREAM("size of acm_entry_values before " << currentACM.entry_values.size());
        ROS_ERROR_STREAM("size of acm_entry_values[0].entries before " << currentACM.entry_values[0].enabled.size());



        currentACM.entry_names.push_back("transport_box");
        moveit_msgs::AllowedCollisionEntry entry;
        entry.enabled.resize(currentACM.entry_names.size());

        for(int i = 0; i < entry.enabled.size(); i++)
            entry.enabled[i] = true;
        
        //add new row to allowed collsion matrix
        currentACM.entry_values.push_back(entry);

        for(int i = 0; i < currentACM.entry_values.size(); i++)
        {
            //extend the last column of the matrix
            currentACM.entry_values[i].enabled.push_back(true);
        }

        newSceneDiff.is_diff = true;
        newSceneDiff.allowed_collision_matrix = currentACM;

        planning_scene_diff_publisher_.publish(newSceneDiff);


     }
     
      if(!client_get_scene_.call(scene_srv))
     {
       ROS_WARN("Failed to call service /get_planning_scene");
     }
     else
     {
         ROS_INFO_STREAM("Modified scene!");
         currentScene = scene_srv.response.scene;
         moveit_msgs::AllowedCollisionMatrix currentACM = currentScene.allowed_collision_matrix;

         ROS_ERROR_STREAM("size of acm_entry_names after " << currentACM.entry_names.size());
         ROS_ERROR_STREAM("size of acm_entry_values after " << currentACM.entry_values.size());
         ROS_ERROR_STREAM("size of acm_entry_values[0].entries after " << currentACM.entry_values[0].enabled.size());
     }
   }


Best regards,
Julia


José

unread,
Apr 5, 2018, 8:38:23 PM4/5/18
to MoveIt! Users
Hi Julia Nitsch,

I tried to implement your code in my specific aplication. Right now I am using Ubuntu 16.04 LTS and ROS Kinetic and simulating in Gazebo a Robotis Manipulator-H on top of a Husky robot. I intend to perform path planning with the manipulator using MoveIt! and my main goal is to be able to perform path planning to a specific goal which, in some cases, may also be collision objetcs. Right now I am using the laser Hokuyo UST-10LX integrated with the "occupancy_map_monitor/PointCloudOctoMapUpdater" MoveIt! plugin to map my environment and, since some of my goals poses are in the collision map, I used your approach of updating the AllowedCollisionMatrix to be able to update my collision octomap and make some space around my desired point free in order to perform path planning onto it.

In the image "mappedTree.png" you can see an example of a mapped tree using the laser. The squares represent my collision octomap and the planners take that into account when performing path plans so that the manipulator doesn't collide with objects represented by the octomap.

In the image "goalPointNotR.png" you see an example of one of my goal points inside the octomap, so the planners can't actually perform path planning to that point.

Finally, after applying your code, you see in image "goalPointReachable.png" that after I added a very small box to my environment (dimensions are in milimeters, that's why you don't see the cube, it is smaller that the axis plotted), the octomap is updated and now there is a free path for the manipulator to go through in order to perform path planning. I see that everything works fine but I have the following error when I run your code:

[ERROR] [1522974455.189631640, 33.323000000]: Number of entries is incorrect for link 'transport_box' in AllowedCollisionMatrix message

And I see that the size of "entry_names" and "entry_values" remains the same before and after updating the AllowedCollisionMatrix (which is 19 in my case). In fact, this doesn't affect my simulation but since I get this error and the size of this variables from the updated AllowedCollisionMatrix don't change, I am concerned that this may be a problem, what do you think?

I also get this error after a few second:

[ERROR] [1522945517.882926418, 54.358000000]: Internal error. Shape filter handle 22 not found 
[ERROR] [1522945518.668399924, 54.874000000]: Internal error. Shape filter handle 22 not found

Do you think that I also should be concerned about this?
I posted something similar to this in this link from ROS answers.

Thanks in advance!
mappedTree.png
goalPointReachable.png
goalPointNotR.png
Reply all
Reply to author
Forward
0 new messages