Getting accurate real-time x,y coordinates with gmapping?
Hello,
I have a Turtlebot 2 (Kobuki base) running in Ubuntu 12.04, ROS Groovy. I want to be able to print out a map of the robot's X,Y coordinates in real time.
Using information I've spliced together from various tutorials (still a newbie), I've come up with a node that uses a StampedTranform object to lookup the transform from "/map" to "base_link". It then takes the transform.getOrigin().x() and transform.getOrigin().y() and prints it to a text file.
My steps are this:
roslaunch turtlebot_bringup turtlebot.launch
roslaunch turtlebot_navigation gmapping_demo.launch
roslaunch turtlebot_teleop keyboard_teleop.launch
I then launch my application and manually drive the robot in a rectangular path around an office building (perhaps 50ft by 20ft). I load the resulting XY text file into MS Excel, and plot the points, but the path looks pretty awful.
I don't have enough karma to post pictures here, but suffice to say it looks like a squashed rhombus.
My question is, what am I doing wrong? Is there a different transform path I should be listening in on? Am I using the wrong function to extract X and Y? Or is it a bad idea in the first place to try and get the path coordinates in real time while the map is being built?
Thanks in advance! I've posted my code below, if anyone is interested.
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <tf/transform_listener.h>
#include <iostream>
#include <fstream>
int main(int argc, char **argv)
{
ros::init(argc, argv, "PoseUpdate");
ros::NodeHandle n;
ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
tf::TransformListener listener;
ros::Rate rate(1.0);
std::ofstream myfile;
myfile.open("/tmp/OUTPUTXY.txt");
while (n.ok())
{
tf::StampedTransform transform;
try
{
//ROS_INFO("Attempting to read pose...");
listener.lookupTransform("/map","/base_link",ros::Time(0), transform);
ROS_INFO("Got a transform! x = %f, y = %f",transform.getOrigin().x(),transform.getOrigin().y());
myfile << transform.getOrigin().x() << "," << transform.getOrigin().y() << "\n";
}
catch (tf::TransformException ex)
{
ROS_ERROR("Nope! %s", ex.what());
}
rate.sleep();
}
myfile.close();
ROS_ERROR("I DIED");
return 0;
}