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

Moveit planning scene collision padding

asked 2017-05-13 10:23:57 -0600

BrettHemes gravatar image

updated 2017-05-13 10:29:05 -0600

Moveit's planning scene has collision checking functions, some with and some without padding. Is the padding configurable and how big is it by default?

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
2

answered 2017-05-13 14:08:15 -0600

v4hn gravatar image

updated 2017-05-13 14:09:12 -0600

For PlanningScenes maintained by the PlanningSceneMonitor, the parameters can be configured by ROS parameters. The code that parses the parameters can be found here: https://github.com/ros-planning/movei...

However, greping further through the code suggests that default_object_padd_ and default_attached_padd_ are not implemented though. They can be queried through getDefault*Padding, but are never used anywhere.

So you can set the default robot padding, scale, and their corresponding link versions through the parameters and these should be supported.

To set the parameters for a scene that is not maintained by the PSM, you have to set them for its RobotState directly: https://github.com/ros-planning/movei...

By default the padding seems to be 0.0 everywhere.

edit flag offensive delete link more

Comments

Thanks v4hn!

BrettHemes gravatar image BrettHemes  ( 2017-05-16 21:50:58 -0600 )edit

I'm still not 100% sure what is the best way to add this parameters. I created a paddings.yaml file and loaded it through rosparam in my launch file, and make sure it's sitting in the correct namespace like /<my own="" robot="" namespace="">/robot_description_planning/default_attached_padding ?

johnyang gravatar image johnyang  ( 2017-09-11 23:54:39 -0600 )edit
2

answered 2021-03-25 02:23:54 -0600

FSund gravatar image

Since this is the top result on Google for "moveit default_robot_padding", I though having a working example might be good. Here's how I have set the default_robot_padding parameter:

Add a file padding.yaml, for example in <robot>_moveit_config/config, with the following content

# parameters for padded robot (not used for self collision checks)
default_robot_padding: 0.05
default_robot_scale: 1.0

and load the parameters from padding.yaml into the correct namespace in a launch file somewhere, for example in planning_context.launch

<!-- Load padding -->
<group ns="move_group">
  <group ns="$(arg robot_description)_planning">
    <rosparam command="load" file="$(find <robot>_moveit_config)/config/padding.yaml" />
  </group>
</group>
edit flag offensive delete link more

Comments

Thank you for providing this example. However, we could not get it to work the way you describe it. We made sure that the padding settings are indeed in the correct namespace and that they get loaded. But we do not see the desired behavior, i.e. detection collisions at the distance of the padding.

Would you be prepared to share something like an example how you tested and made sure that your settings work?

In our scenario, we are interested to use padding around either the robot or scene to avoid collisions that could arise due to discrepancies between the real system and the model of the cell.

tgaspar gravatar image tgaspar  ( 2021-05-25 05:29:37 -0600 )edit
1

What I did was to add a collision object to my scene (a box or something else), and tried moving the robot near the object. When I got around 5 cm from the box (the size of the padding I used), the part of the robot close to the box was marked in red/in collision. Make sure your collision tags are set up properly as well as the visual tags.

FSund gravatar image FSund  ( 2021-05-25 06:30:09 -0600 )edit

Thanks! I followed the steps you described here and was finally able to see the padding parameters having some effect!

Now I have to figure out how to achieve the same behavior between my robot arm and the structure of the robot cell as they are part of the same URDF. Any pointers in or advice in this regard?

p.s. if anyone ever finds themselves in the similar situation and is looking for answers I tried the following parameters separately and they all worked: default_robot_padding, default_robot_scale, default_robot_link_padding: {}.

tgaspar gravatar image tgaspar  ( 2021-05-25 07:53:09 -0600 )edit

No, sorry. We're having the same problem here, trying to tackle the posibility of unreliable motor positions. If the robot cell is static (as in, not moving) you could load it separately by publishing a model on the /collision_object topic instead of loading it as part of the robot. Or importing it via PlanningSceneInterface (Python) add_object or add_mesh. http://docs.ros.org/en/noetic/api/mov....

FSund gravatar image FSund  ( 2021-05-25 08:25:28 -0600 )edit
0

answered 2021-05-26 11:01:51 -0600

tgaspar gravatar image

updated 2021-05-26 11:04:11 -0600

After the fruitful discussion with FSound I came to a partial solution to add padding to the peripheral elements of the robot cell.

The first assumption is that the whole model of the cell is available in the parameter server under /robot_description. This should anyhow be the case. Next, I prepared the padding values as described by FSound and loaded them into their appropriate namespace.

I then created a Python script that goes through the URDF and adds the objects to the Scene with the add_mesh() method.

Here are a few slices of the code.

First the imports that help you parse the URDF and the path to the mesh:

from urdf_parser_py.urdf import URDF
import rospkg 

I then created a helper function that returns the full path of the mesh from the path available in the URDF:

get_full_mesh_path(mesh_path_from_urdf):
    relative_path = mesh_path_from_urdf.replace("package://","")    
    package_name = relative_path.split('/')[0]
    package_path = rospkg.RosPack().get_path(package_name)
    file_path = package_path + relative_path.replace(package_name, "") 

Finally, I loop through the list of objects to add and add them to the scene:

urdf = URDF.from_parameter_server('/robot_description')
scene = moveit_commander.PlanningSceneInterface()
for object in objects_to_add:
    link = urdf.link_map[object]
    mesh_path = get_full_mesh_path(link.visual.geometry.filename)
    link_pose = PoseStamped()
    link_pose.pose.orientation.w = 1
    link_pose.header.frame_id = link.name
    scene.add_mesh(link.name, link_pose, mesh_path) 
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2017-05-13 10:23:57 -0600

Seen: 2,623 times

Last updated: May 26 '21