46 std::cerr <<
"USAGE: " <<
self <<
" <InputFile.graph>\n";
47 std::cerr <<
"This tool is part of OctoMap and evaluates the statistical accuracy\n" 48 "of an octree map from scan graph data (point clouds with poses).\n";
50 std::cerr <<
"OPTIONS:\n" 51 " -res <resolution> (default: 0.1 m)\n" 52 " -m <maxrange> (optional) \n" 53 " -n <max scan no.> (optional) \n" 60 int main(
int argc,
char** argv) {
67 string graphFilename = std::string(argv[1]);
71 int skip_scan_eval = 5;
74 while (++arg < argc) {
75 if (! strcmp(argv[arg],
"-i"))
76 graphFilename = std::string(argv[++arg]);
77 else if (! strcmp(argv[arg],
"-res"))
78 res = atof(argv[++arg]);
79 else if (! strcmp(argv[arg],
"-m"))
80 maxrange = atof(argv[++arg]);
81 else if (! strcmp(argv[arg],
"-n"))
82 max_scan_no = atoi(argv[++arg]);
88 cout <<
"\nReading Graph file\n===========================\n";
93 size_t num_points_in_graph = 0;
94 if (max_scan_no > 0) {
95 num_points_in_graph = graph->
getNumPoints(max_scan_no-1);
96 cout <<
"\n Data points in graph up to scan " << max_scan_no <<
": " << num_points_in_graph << endl;
100 cout <<
"\n Data points in graph: " << num_points_in_graph << endl;
103 cout <<
"\nCreating tree\n===========================\n";
106 size_t numScans = graph->
size();
107 unsigned int currentScan = 1;
110 if (currentScan % skip_scan_eval != 0){
111 if (max_scan_no > 0) cout <<
"("<<currentScan <<
"/" << max_scan_no <<
") " << flush;
112 else cout <<
"("<<currentScan <<
"/" << numScans <<
") " << flush;
115 cout <<
"(SKIP) " << flush;
117 if ((max_scan_no > 0) && (currentScan == (
unsigned int) max_scan_no))
126 cout <<
"\nEvaluating scans\n===========================\n";
128 size_t num_points = 0;
129 size_t num_voxels_correct = 0;
130 size_t num_voxels_wrong = 0;
131 size_t num_voxels_unknown = 0;
136 if (currentScan % skip_scan_eval == 0){
137 if (max_scan_no > 0) cout <<
"("<<currentScan <<
"/" << max_scan_no <<
") " << flush;
138 else cout <<
"("<<currentScan <<
"/" << numScans <<
") " << flush;
141 pose6d frame_origin = (*scan_it)->pose;
149 KeySet free_cells, occupied_cells;
150 tree->
computeUpdate(scan, origin, free_cells, occupied_cells, maxrange);
152 num_points += scan.
size();
155 for (KeySet::iterator it = free_cells.begin(); it != free_cells.end(); ++it) {
161 num_voxels_correct++;
163 num_voxels_unknown++;
165 for (KeySet::iterator it = occupied_cells.begin(); it != occupied_cells.end(); ++it) {
169 num_voxels_correct++;
173 num_voxels_unknown++;
179 if ((max_scan_no > 0) && (currentScan == (
unsigned int) max_scan_no))
187 cout <<
"\nFinished evaluating " << num_points <<
"/"<< num_points_in_graph <<
" points.\n" 188 <<
"Voxels correct: "<<num_voxels_correct<<
" #wrong: " <<num_voxels_wrong <<
" #unknown: " <<num_voxels_unknown
189 <<
". % correct: "<< num_voxels_correct/double(num_voxels_correct+num_voxels_wrong)<<
"\n\n";
Vector3 transform(const Vector3 &v) const
Transformation of a vector.
std::istream & readBinary(std::ifstream &s)
void transform(pose6d transform)
Apply transform to each point.
virtual void insertPointCloud(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
std::vector< ScanNode * >::iterator iterator
NODE * search(double x, double y, double z, unsigned int depth=0) const
size_t getNumPoints(unsigned int max_id=-1) const
void printUsage(char *self)
int main(int argc, char **argv)
unordered_ns::unordered_set< OcTreeKey, OcTreeKey::KeyHash > KeySet
This class represents a tree-dimensional pose of an object.
This class represents a three-dimensional vector.
void computeUpdate(const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
bool isNodeOccupied(const OcTreeNode *occupancyNode) const
queries whether a node is occupied according to the tree's parameter for "occupancy" ...
Pose6D inv() const
Inversion.