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

MoveIt! Access the pose of a CollisionObject

asked 2014-06-13 13:09:25 -0500

courrier gravatar image

updated 2014-06-16 12:48:42 -0500

Hi all,

I need to perform transformations between all objects manipulated by the robot. So I intended to create a thread to publish a tf::Transform at the center of each CollisionObject at, say, 50Hz. But to do that I need to access the pose of the collision objects in real time with respect to some frame (base_link for instance). Is this pose published somewhere in a topic, accessible through a service or is present in some field?

I am the one defining the initial position of all CollisionObject and asking the robot to take/leave this object, so thanks to the position of the end effector I could update my own copy of the pose but:

1) This value is necessarily known by MoveIt! to display the objects 2) It's annoying to wonder when the pose has or has not changed 3) If I do it the pose would be duplicated with the internal value of MoveIt!

Another question: is the field frame_id of a CollisionObject used by MoveIt? I would like to anchor an object (e.g. a cup of tea) to another (e.g. a tray) and ask the robot to manipulate the tray (with moveit_msgs::AttachedCollisionObject.lik_name = end effector of the robot). The goal is obiously to keep the cup fastened to the tray. I wanted to set the frame_id of the cup to the tray like I would so with a regular RViz marker for that but apparently this field is not used, the two CollisionObjects are not linked. Any clue to achieve this goal?

Many thanks for your help

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2014-06-13 17:43:07 -0500

fergs gravatar image

You could subscribe to the "monitored_planning_scene" topic (which is what the RVIZ plugins do). This will publish the current planning scene, which includes changes to collision objects and attached objects. There is also a service call which you can you use to get the initial state of the planning scene since the published topic includes only diffs.

edit flag offensive delete link more

Comments

Thanks I that is what I do now it works. Also I added a new question related to these frames.

courrier gravatar image courrier  ( 2014-06-16 13:34:24 -0500 )edit

As for the frames, yes the frame is used, but I believe (unless it has been recently fixed) you can only use frames which are part of the robot as the RobotState class doesn't track the poses of non-robot frames. I think you will have to attach both objects to the end effector.

fergs gravatar image fergs  ( 2014-06-16 15:19:52 -0500 )edit

That's what I did in the end yes. Thanks

courrier gravatar image courrier  ( 2014-06-27 11:53:10 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2014-06-13 13:09:25 -0500

Seen: 1,173 times

Last updated: Jun 16 '14