0
$\begingroup$

Rosanswers logo

I'm aware of the possibility of quickly setting up MoveIt! to use point cloud sensors and generate octomap data from their clouds, but what I'd like to do is retrieving a area of interest from another node providing a octomap and using that inside MoveIt!. I have a custom MoveGroup plugin that listens to requests for planning. If one comes in, it should retrieve the relevant octomap via a service call and then plan. Apart from the collision avoidance step the plugin already works as intended. Any ideas/suggestions are much appreciated.

/edit: So the first idea I have is instantiating a planning scene, keeping track of it manually and using the planning scene monitor constructor taking a planning scene as argument (for getting the planning scene monitor benefits like tf monitoring etc.). I'll then try updating the planning scene with a octomap manually, locking the planning scene monitor afterwards and then starting planning.

/edit2: After taking a close look I noted that I can indeed retrieve the planning_scene from the planning_scene_monitor and add the octomap data. Normally, my octomap data are in a frame not belonging to the robot ("/map"), thus when trying to add the octomap message to the scene I get:

[ERROR] [1367584563.653419864, 80.883000000]: Transform from frame 'map' to frame 'pelvis' is not known ('map' should be a link name or an attached body id).

Is there any way for working around this? Transforming octomap data between frames isn't possible right now, so from what I'm seeing my options are:

  1. Changing internals of MoveIt! so it also can use transforms outside of those belonging to the robot
  2. Providing a octomap already in the "pelvis" frame

Originally posted by Stefan Kohlbrecher on ROS Answers with karma: 24361 on 2013-05-01

Post score: 4


Original comments

Comment by Danfoa on 2019-05-24:
Did you get an answer?

Do you have the code for publishing the octomap?

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Hi Stefan,

Could you please ask future MoveIt! related questions on the moveit-users mailing list: [email protected]. Its easier for us to track MoveIt! specific questions there.

Regarding your questions: you can have MoveIt! plan and maintain everything in a different frame: e.g. odom_combined for the PR2 or map. To do this right, you need to have a virtual joint in your SRDF (which can be added through the Setup Assistant) that connects the frame to the root link on your robot: e.g. for the PR2, the corresponding line in the SRDF looks like this:

<virtual_joint name="world_joint" type="planar" parent_frame="odom_combined" child_link="base_footprint" />

This forces MoveIt! to do everything in the odom_combined frame. It uses TF information to figure out this particular transform. MoveIt! does use transforms outside of those belonging to the robot, it just needs to know about them through the SRDF.


Originally posted by Sachin Chitta with karma: 1304 on 2013-05-15

This answer was ACCEPTED on the original site

Post score: 3

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.