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

Coordinate frame transforms: /odom to /map? [closed]

asked 2012-08-17 07:23:54 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

I think I might just be having a difficult time understanding how the coordinate frames relate to each other. I'm working on a visualization (very small subset of rviz) that is shown in a browser.

Basically I'm running SLAM and building a map. Using rosbridge I'm able to get the map and draw it. The base frame is /map and the associated OccupancyGrid has an origin which I translate and rotate by. This seems to work just fine.

Now I want to put an overlay of a robot footprint so you can see where it is, or it thinks it is in the map. Ideally I'd like to display a few topics under /move_base_node which have a base frame of /odom:

  • /move_base_node/local_costmap/robot_footprint
  • /move_base_node/local_costmap/obstacles
  • /move_base_node/local_costmap/inflated_obstacles

* In the end this is what worked for me *

As suggested I look up the transform between map and odom and then publish that on a new topic that I can subscribe to on the client end of rosbridge. Whenever I receive an update I use the transformation between map and odom on any topics with a base frame of odom to bring them into the map frame.

You can check the frames easily with: rostopic echo 'your_topic_name' | grep frame

int main(int argc, char** argv){
  ros::init(argc, argv, "my_tf_listener");
  ros::NodeHandle node;
  ros::Rate rate(1.0);

  tf::TransformListener listener;
  tf::StampedTransform tfTransform;
  tf::Vector3 origin;
  tf::Quaternion rotation;
  tf::Vector3 axis;

  static ros::Publisher publisher = 
    node.advertise<geometry_msgs::TransformStamped>("/odom2map_transform",
                            10);

  geometry_msgs::TransformStamped geoTransform;

  int seq = 0;
  geoTransform.header.frame_id = "map";
  geoTransform.child_frame_id = "odom";

  while(node.ok()) {
    try { 
      listener.lookupTransform(geoTransform.header.frame_id,
                   geoTransform.child_frame_id,       
                   ros::Time(0), 
                   tfTransform);
    }
    catch(tf::TransformException &exception) { 
      ROS_ERROR("%s", exception.what());
    }

    origin = tfTransform.getOrigin();
    rotation = tfTransform.getRotation();
    axis = rotation.getAxis();

    geoTransform.header.seq = seq;
    geoTransform.header.stamp = tfTransform.stamp_;

    geoTransform.transform.translation.x = origin.x();
    geoTransform.transform.translation.y = origin.y();
    geoTransform.transform.translation.z = origin.z();

    geoTransform.transform.rotation.x = axis.x();
    geoTransform.transform.rotation.y = axis.y();
    geoTransform.transform.rotation.z = axis.z();
    geoTransform.transform.rotation.w = rotation.getW();

    seq++;
    publisher.publish(geoTransform);
    rate.sleep();
  }

  return 0;
}
edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by skiesel
close date 2013-10-11 04:41:18

Comments

I can't figure out where to respond to your comment? robot_footprint for example is in the /odom base frame. I want to figure out how to line up that coordinate frame with the /map frame. Basically I thought I was doing that above? The variables you reference are static, so they're only created once

skiesel gravatar image skiesel  ( 2012-08-18 06:00:13 -0500 )edit

Right. Sorry. I missed that... Still I don't see what the sleep is for. I'll update my answer to be more specific.

Lorenz gravatar image Lorenz  ( 2012-08-19 22:53:34 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
5

answered 2012-08-18 03:11:31 -0500

Lorenz gravatar image

updated 2012-08-19 23:00:39 -0500

If you just want to have the pose of the robot in map, all you need to do is look up the transform between /map and your base frame. There is no need to subscribe to the odom topic for that. The code for getting the pose of base_footprint in map would be:

tf::StampedTransform transform_in_map;
try {
  listener.lookupTransform("map", "base_footprint", ros::Time(0), transform_in_map);
} catch(tf::TransformException &exception) {
  ROS_ERROR("%s", exception.what());
}

Most tools, e.g. rviz, are using this mechanism to calculate the robot pose with respect to map instead of directly subscribing to odom. I think the only node that really uses the odom topic on the pr2 is the move_base node because it needs the current velocity. Everything else uses tf.

edit flag offensive delete link more

Comments

The odom topic is also used by mapping and localization algorithms. What can be confusing is that there can be an odometry topic (nav_msgs/Odometry) without the transform being published to tf (for instance if you use robot_pose_ekf that provides the link between /odom and /base)

pgorczak gravatar image pgorczak  ( 2012-08-23 22:02:12 -0500 )edit
1

According to the ros wiki, neither amcl nor gmapping or hector_mapping subscribe to the odom topic. I also checked the amcl source code, just in case the wiki is wrong. They all use tf, not the odom topic and that's why they work with robot_pose_ekf which publishes the odom->base_link transform.

Lorenz gravatar image Lorenz  ( 2012-08-23 22:14:02 -0500 )edit

Of course - my first sentence didn't make sense...

pgorczak gravatar image pgorczak  ( 2012-08-23 23:08:37 -0500 )edit
0

answered 2012-08-23 12:49:55 -0500

pgorczak gravatar image

updated 2012-08-23 21:47:31 -0500

In ROS, we have the odometry, giving us a continuous transform from /odom to /base_link. The mapping algorithm computes a possibly discontinuous (it can "jump") transform from /map to /base_link but publishes /map to /odom. The reason for that is, that algorithms like a Kalman Filter for pose estimation and trajectory planners don't deal with jumping coordinates so easily.

So if you display the map and you want to see the position of the robot in the map, you should look up /map -> /base_link or /base_footprint in tf.

More details of the coordinate frame specification are explained in REP 105

edit flag offensive delete link more

Comments

You're right - I fixed that mistake. What I was trying to explain was,if you display the map, the /odom frame will actually move around inside it (when the relative localization from odometry and the absolute localization from mapping drift apart). Or the map moves around /odom - whatever suits you.

pgorczak gravatar image pgorczak  ( 2012-08-23 21:53:24 -0500 )edit

I am looking up /map-> /base_link to see the position, but I am not getting desired result. I have posted a question, http://answers.ros.org/question/161326/rosrun-tf-tf_echo-map-base_link-vs-coding-implementation/

RB gravatar image RB  ( 2014-05-05 03:52:44 -0500 )edit

Question Tools

Stats

Asked: 2012-08-17 07:23:54 -0500

Seen: 10,690 times

Last updated: Aug 23 '12