Coordinate frame transforms: /odom to /map? [closed]
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;
}
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
Right. Sorry. I missed that... Still I don't see what the sleep is for. I'll update my answer to be more specific.