log_recorder.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include <ros/ros.h>
33 
34 #include <laser_geometry/laser_geometry.h>
35 
36 #include <pcl/point_types.h>
37 #include <pcl/io/pcd_io.h>
38 #include <pcl/kdtree/kdtree_flann.h>
39 #include <pcl/surface/mls.h>
40 #include <pcl_conversions/pcl_conversions.h>
41 
42 #include <string>
43 #include <fstream>
44 
45 using namespace std;
46 using namespace ros;
47 
48 string outputFile="~/Desktop/temp.txt";
49 
50 void savePointCloud2(const sensor_msgs::PointCloud2& cloud)
51 {
52  pcl::PointCloud<pcl::PointXYZ> pclCloud;
53  pcl::PCLPointCloud2 pcl_pc;
54  pcl_conversions::toPCL(cloud, pcl_pc);
55  pcl::fromPCLPointCloud2(pcl_pc, pclCloud);
56 
57  ofstream file(outputFile.c_str(),ios::app);
58 
59  //get points into grid to reorder them
60  for(uint i=0;i<pclCloud.points.size();i++)
61  file<<pclCloud.points[i].x<<" "<<pclCloud.points[i].y<<" ";
62 
63  file<<cloud.header.stamp<<endl;
64 
65  return;
66 }
67 
68 void saveLaserScan(const sensor_msgs::LaserScan& scan)
69 {
70  ofstream file(outputFile.c_str(),ios::app);
71 
72  double min=0.1;//10 cm
73  double max=50.;//50 m
74  static bool init=false;
75 
76  if(init)
77  {
78  //write header
79  file<<"# ros-bag to log converter"<<endl;
80  file<<"# Jorge Almeida"<<endl;
81  file<<"# Formato do ficheiro:"<<endl;
82  file<<"# cada linha representa um scan diferente"<<endl;
83  file<<"# é assumido que todos os pontos num scan foram obtidos ao mesmo tempo"<<endl;
84  file<<"# o instante de tempo a que o scan corresponde aparece sempre na ultima coluna de uma linha"<<endl;
85  file<<"# todos os scans têm o mesmo número de pontos"<<endl;
86  file<<"# os valores aqui apresentados correspondem às distancias em metros"<<endl;
87  file<<"# os valores de distancia são sempre positivos, um valor negativo é uma medida falhada"<<endl;
88  file<<"# as distancias correspondem a ângulos de medição consecutivos começando em angle_min e terminando em angle_max"<<endl;
89  file<<"# os valores desses ângulos vêm em radianos"<<endl;
90  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;
91  file<<"# angle_min: "<<scan.angle_min<<endl;
92  file<<"# angle_max: "<<scan.angle_max<<endl;
93  file<<"# scan_time: "<<scan.scan_time<<endl;
94 
95  init=false;
96  }
97 
98  for(uint i=0;i<scan.ranges.size();i++)
99  {
100  if(scan.ranges[i]<min || scan.ranges[i]>max)
101  file<<-1<<" ";
102  else
103  file<<scan.ranges[i]<<" ";
104  }
105  file<<scan.header.stamp<<endl;
106 }
107 
108 int main(int argc,char**argv)
109 {
110  // Initialize ROS
111  init(argc,argv,"mht");
112 
113  NodeHandle nh("~");
114 
115  Subscriber laser_handler = nh.subscribe("/scan", 1000, saveLaserScan);
116  Subscriber point_handler = nh.subscribe("/points", 1000, savePointCloud2);
117 
118  nh.getParam("output", outputFile);
119 
120  if(remove(outputFile.c_str()) != 0 )
121  perror( "Error deleting file" );
122 
123  cout<<"Writing to "<<outputFile<<endl;
124  cout<<"Subscribed to "<<names::remap("/scan")<<endl;
125  cout<<"Subscribed to "<<names::remap("/points")<<endl;
126 
127  cout<<"Spinning"<<endl;
128  spin();
129  return 0;
130 }
string outputFile
void savePointCloud2(const sensor_msgs::PointCloud2 &cloud)
void saveLaserScan(const sensor_msgs::LaserScan &scan)
int main(int argc, char **argv)


mtt
Author(s): Jorge Almeida
autogenerated on Mon Mar 2 2015 01:32:18