-
Notifications
You must be signed in to change notification settings - Fork 12
/
Copy pathpcd_to_ssa.cpp
140 lines (123 loc) · 3.57 KB
/
pcd_to_ssa.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
#include <iostream>
#include <stdlib.h>
#include <string.h>
#include <istream>
#include <fstream>
#include <sstream>
#include <list>
#include <cstring>
#include <limits>
// #include <cmath>
#include <QApplication>
#include "Eigen/Core"
#include "pcl/io/pcd_io.h"
#include "pcl/point_types.h"
#include "pcl/point_cloud.h"
#include "pcl/common/transforms.h"
#include "pcl/filters/filter.h"
#include "pcl/filters/voxel_grid.h"
#include "g2o/stuff/timeutil.h"
#include "pcl_ssa_hierarchical.h"
using namespace std;
using namespace ssa;
const char *message[]={
"pcd_to_ssa: converts a set of pcd files into a ssa 3d graph file",
"usage pcd_to_ssa [options] <ssa3d_file>",
"options:",
"-e [int] take every e.th scan.",
"-n [int] number of scans.",
"-p [string] prefix of the pcd file list.",
"-lms use lms sensor model instead of kinect.",
"-r [double] resolution of the resulting model (default resolution 0.01m)",
"example:",
"pcd_to_ssa -p alufr_black_mug_raw -n 60 -r 0.001 alufr_black_mug_raw.ssa3d",
0
};
int main(int argc, char **argv)
{
//Debuging stuff
//OptimizableGraph::printRegisteredTypes(cout, true);
string pcPrefix = "pcloud";
if (argc<2){
const char**v=message;
while (*v){
cout << *v << endl;
v++;
}
return 0;
}
const char* outputFile=0;
int numOfScans = 100;
int every = 1;
double voxelSize = 0.01;
bool useLMS = false;
int c=1;
while (c<argc){
if (!strcmp(argv[c],"-e")){
c++;
every=atoi(argv[c]);
c++;
} else
if (!strcmp(argv[c],"-n")){
c++;
numOfScans=atoi(argv[c]);
c++;
} else
if (!strcmp(argv[c],"-p")){
c++;
pcPrefix=argv[c];
c++;
} else
if (!strcmp(argv[c],"-r")){
c++;
voxelSize=atof(argv[c]);
c++;
} else
if (!strcmp(argv[c],"-lms")){
useLMS = true;
c++;
} else
if (! outputFile){
outputFile=argv[c];
c++;
break;
}
}
//Create ssa 3d graph
SparseSurfaceAdjustmentGraph3D ssaGraph;
vector< pcl::PointCloud<pcl::PointXYZRGBA>::Ptr > clouds;
cerr << "Building ssa graph with resolution " << voxelSize << "m."<< endl;
PCLSSAHierarchicalT<pcl::PointCloud<pcl::PointXYZRGBA> > pclToSSA;
//pclToSSA.setInput(&clouds);
if(useLMS){
pclToSSA.setSensor(PCLSSAHierarchicalT<pcl::PointCloud<pcl::PointXYZRGBA> >::LMS);
pclToSSA.setLevels(4);
pclToSSA.setResolution(0, 0.001);
pclToSSA.setResolution(1, 0.01);
pclToSSA.setResolution(2, 0.1);
pclToSSA.setResolution(3, 0.2);
pclToSSA.params().normalExtractionMaxNeighborDistance = 1.0;
} else {
pclToSSA.setSensor(PCLSSAHierarchicalT<pcl::PointCloud<pcl::PointXYZRGBA> >::KINECT);
pclToSSA.setLevels(3);
pclToSSA.setResolution(0, 0.001);
pclToSSA.setResolution(1, 0.005);
pclToSSA.setResolution(2, 0.01);
pclToSSA.setResolution(3, 0.02);
pclToSSA.setResolution(4, 0.05);
pclToSSA.params().normalExtractionMaxNeighborDistance = 0.5;
}
pclToSSA.params().normalExtractionMinNeighbors = 9;
for(int i = 0; i < numOfScans; i=i+every)
{
double timing = get_time();
pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGBA>);
char cloudFileName[2048];
sprintf(cloudFileName, "%s%05d.pcd", pcPrefix.c_str(), i);
pcl::io::loadPCDFile(cloudFileName , *cloud);
cerr << "loading from disk took " << (get_time() - timing) * 1000 << "ms." << endl;
pclToSSA.addCloudToGraph(ssaGraph, cloud);
}
cout << "Writing ssa3d file to " << outputFile << endl;
ssaGraph.save(outputFile);
}