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
00032 #include <ros/ros.h>
00033
00034 #include <laser_geometry/laser_geometry.h>
00035
00036 #include <pcl/point_types.h>
00037 #include <pcl/io/pcd_io.h>
00038 #include <pcl/kdtree/kdtree_flann.h>
00039 #include <pcl/surface/mls.h>
00040
00041 #include <string>
00042 #include <fstream>
00043
00044 using namespace std;
00045 using namespace ros;
00046
00047 string outputFile="~/Desktop/temp.txt";
00048
00049 void savePointCloud2(const sensor_msgs::PointCloud2& cloud)
00050 {
00051 pcl::PointCloud<pcl::PointXYZ> pclCloud;
00052 pcl::fromROSMsg(cloud,pclCloud);
00053
00054 ofstream file(outputFile.c_str(),ios::app);
00055
00056
00057 for(uint i=0;i<pclCloud.points.size();i++)
00058 file<<pclCloud.points[i].x<<" "<<pclCloud.points[i].y<<" ";
00059
00060 file<<cloud.header.stamp<<endl;
00061
00062 return;
00063 }
00064
00065 void saveLaserScan(const sensor_msgs::LaserScan& scan)
00066 {
00067 ofstream file(outputFile.c_str(),ios::app);
00068
00069 double min=0.1;
00070 double max=50.;
00071 static bool init=false;
00072
00073 if(init)
00074 {
00075
00076 file<<"# ros-bag to log converter"<<endl;
00077 file<<"# Jorge Almeida"<<endl;
00078 file<<"# Formato do ficheiro:"<<endl;
00079 file<<"# cada linha representa um scan diferente"<<endl;
00080 file<<"# é assumido que todos os pontos num scan foram obtidos ao mesmo tempo"<<endl;
00081 file<<"# o instante de tempo a que o scan corresponde aparece sempre na ultima coluna de uma linha"<<endl;
00082 file<<"# todos os scans têm o mesmo número de pontos"<<endl;
00083 file<<"# os valores aqui apresentados correspondem às distancias em metros"<<endl;
00084 file<<"# os valores de distancia são sempre positivos, um valor negativo é uma medida falhada"<<endl;
00085 file<<"# as distancias correspondem a ângulos de medição consecutivos começando em angle_min e terminando em angle_max"<<endl;
00086 file<<"# os valores desses ângulos vêm em radianos"<<endl;
00087 file<<"# podes calcular a frequência dos scans usando o tempo de cada um, o valor de scan_time é o valor médio/ótimo (tempo entre scans)"<<endl;
00088 file<<"# angle_min: "<<scan.angle_min<<endl;
00089 file<<"# angle_max: "<<scan.angle_max<<endl;
00090 file<<"# scan_time: "<<scan.scan_time<<endl;
00091
00092 init=false;
00093 }
00094
00095 for(uint i=0;i<scan.ranges.size();i++)
00096 {
00097 if(scan.ranges[i]<min || scan.ranges[i]>max)
00098 file<<-1<<" ";
00099 else
00100 file<<scan.ranges[i]<<" ";
00101 }
00102 file<<scan.header.stamp<<endl;
00103 }
00104
00105 int main(int argc,char**argv)
00106 {
00107
00108 init(argc,argv,"mht");
00109
00110 NodeHandle nh("~");
00111
00112 Subscriber laser_handler = nh.subscribe("/scan", 1000, saveLaserScan);
00113 Subscriber point_handler = nh.subscribe("/points", 1000, savePointCloud2);
00114
00115 nh.getParam("output", outputFile);
00116
00117 if(remove(outputFile.c_str()) != 0 )
00118 perror( "Error deleting file" );
00119
00120 cout<<"Writing to "<<outputFile<<endl;
00121 cout<<"Subscribed to "<<names::remap("/scan")<<endl;
00122 cout<<"Subscribed to "<<names::remap("/points")<<endl;
00123
00124 cout<<"Spinning"<<endl;
00125 spin();
00126 return 0;
00127 }