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

Moveit PlanningSceneInterface addBox not showing in Rviz

asked 2015-05-11 21:51:23 -0500

Arowana gravatar image

updated 2015-05-11 21:58:31 -0500

My goal is to be able to add and remove object dynamically then do path planning. Even moving objects should be nice but I don't know if it's possible

I want to add box or meshes to my Planning scene to do path planning avoiding some object. The problem is that after adding object to the scene interface I don't have any visual feedback in RViz. Later I would like to spawn this object in gazebo as well to be able to have physics.

This is what I do.

rospy.init_node('scene_test', anonymous=True)

scene = moveit_commander.PlanningSceneInterface()

p = PoseStamped()
p.pose.position.x = 0.
p.pose.position.y = 0.
p.pose.position.z = 0.
scene.add_box("table", p, (1, 1, 1))

rospy.sleep(10)

I don't know how to check the scene because the interface doesn't provide any method to do so, but nothing appear in RViz. I suspect something is missing to notice Rviz a new object is here but I can't find anything related to this issue.

Thank you for reading, any help will be much appreciated

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
11

answered 2015-05-13 00:16:20 -0500

Arowana gravatar image

I finally find out why, the pose header was missing and the node need a sleep before adding box to scene otherwise it will skip it.

scene = moveit_commander.PlanningSceneInterface()
robot = moveit_commander.RobotCommander()

rospy.sleep(2)

p = PoseStamped()
p.header.frame_id = robot.get_planning_frame()
p.pose.position.x = 0.
p.pose.position.y = 0.
p.pose.position.z = 0.
scene.add_box("table", p, (0.5, 1.5, 0.6))
edit flag offensive delete link more

Comments

thanks for posting this!

alexpad gravatar image alexpad  ( 2016-04-22 09:14:41 -0500 )edit

Darn. I was struggling one week to solve this issue!!. My objects were simply not added. Is this somewhere in the tutorial? How did you find out about this little hack? Thnx for posting.

Markus Eich gravatar image Markus Eich  ( 2016-12-12 18:44:58 -0500 )edit

Only thing missing is: How can I visualise the added scene in RVIZ? The objects are there (I can see the collision when moving the arm) but the scene in rviz is not updated. Any ideas?

Markus Eich gravatar image Markus Eich  ( 2016-12-12 18:48:17 -0500 )edit

To visualize the scene in rviz add the PlanningScene display with the 'add' button

urielo gravatar image urielo  ( 2017-01-10 22:17:19 -0500 )edit

I don't understand this... so confusing, but ok

buckley.toby gravatar image buckley.toby  ( 2017-05-18 19:51:38 -0500 )edit

The frame has to be specified. Otherwise MoveIt wouldn't know how to interpret the pose w.r.t. the rest of the setup.

The sleep might be necessary to ensure the scene interface is connected to the move_group. As always in ROS, the connection is created in the background.

v4hn gravatar image v4hn  ( 2017-05-19 05:17:45 -0500 )edit
2

Currently, we don't export the applyCollisionObject methods of the C++ PlanningSceneInterface to the Python class. This would add the box synchronously to the move_group and does not need the additional sleep.

Patches are welcome.

v4hn gravatar image v4hn  ( 2017-05-19 05:21:33 -0500 )edit

That's true, when using applyCollisionObject method in c++, the object appears in the scene immediately, I guess the addCollisionObject method add the object asynchronously so that the RViz is not notified.

boooooosh gravatar image boooooosh  ( 2017-07-24 16:41:54 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2015-05-11 21:51:23 -0500

Seen: 6,758 times

Last updated: May 13 '15