Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00046
00047 #include <ros/ros.h>
00048
00049 #include <tf/transform_listener.h>
00050
00051 #include <fstream>
00052 #include <iostream>
00053
00054 using namespace std;
00055
00056 class PoseLogger
00057 {
00058 protected:
00059 ros::NodeHandle nh_;
00060
00061 public:
00062
00063 ros::Subscriber sub_;
00064 ros::Publisher pub_;
00065 tf::TransformListener tf_;
00066
00068 PoseLogger (ros::NodeHandle &n) : nh_(n)
00069 {
00070
00071 }
00072
00074
00075 void spin (double rate)
00076 {
00077 ros::Rate loop_rate(rate);
00078 std::ofstream a_file ( "poses.txt" );
00079 a_file<< "time" << " " << "x" << " " << "y" << std::endl;
00080
00081
00082
00083
00084 while (ros::ok())
00085 {
00086 ros::Time time;
00087 time = ros::Time::now();
00088 bool found_transform = tf_.waitForTransform("map", "/base_link",
00089 time, ros::Duration(1.0));
00090 if (found_transform)
00091 {
00092
00093 tf::StampedTransform transform;
00094 tf_.lookupTransform("map", "base_link", time, transform);
00095 std::cerr << time << " " << transform.getOrigin().x() << " " << transform.getOrigin().y() << std::endl;
00096 a_file<< time << " " << transform.getOrigin().x() << " " << transform.getOrigin().y() << std::endl;
00097 }
00098 ros::spinOnce();
00099 loop_rate.sleep();
00100 }
00101 a_file.close();
00102 }
00103 };
00104
00105 int main (int argc, char** argv)
00106 {
00107 ros::init (argc, argv, "pose_logger_node");
00108 if (argc != 2)
00109 {
00110 ROS_ERROR("Usage %s <logging rate>", argv[0]);
00111 exit (0);
00112 }
00113 ros::NodeHandle n("~");
00114 PoseLogger tp(n);
00115 tp.spin(atof(argv[1]));
00116
00117 return (0);
00118 }
00119
00120