46 cerr <<
"USAGE: " <<
self <<
" <InputFile.bt> <OutputFile.pcd>\n";
47 cerr <<
"This tool creates a point cloud of the occupied cells\n";
52 int main(
int argc,
char** argv) {
56 string inputFilename = argv[1];
57 string outputFilename = argv[2];
66 cout <<
"tree depth is " << maxDepth << endl;
69 vector<OcTreeNode*> collapsed_occ_nodes;
71 collapsed_occ_nodes.clear();
72 for (OcTree::iterator it = tree->
begin(); it != tree->
end(); ++it)
76 collapsed_occ_nodes.push_back(&(*it));
79 for (vector<OcTreeNode*>::iterator it = collapsed_occ_nodes.begin(); it != collapsed_occ_nodes.end(); ++it)
83 cout <<
"expanded " << collapsed_occ_nodes.size() <<
" nodes" << endl;
84 }
while(collapsed_occ_nodes.size() > 0);
87 for (OcTree::iterator it = tree->
begin(); it != tree->
end(); ++it)
91 pcl.push_back(it.getCoordinate());
97 ofstream f(outputFilename.c_str(), ofstream::out);
98 f <<
"# .PCD v0.7" << endl
99 <<
"VERSION 0.7" << endl
100 <<
"FIELDS x y z" << endl
101 <<
"SIZE 4 4 4" << endl
102 <<
"TYPE F F F" << endl
103 <<
"COUNT 1 1 1" << endl
104 <<
"WIDTH " << pcl.size() << endl
105 <<
"HEIGHT 1" << endl
106 <<
"VIEWPOINT 0 0 0 0 0 0 1" << endl
107 <<
"POINTS " << pcl.size() << endl
108 <<
"DATA ascii" << endl;
109 for (
size_t i = 0; i < pcl.size(); i++)
110 f << pcl[i].x() <<
" " << pcl[i].y() <<
" " << pcl[i].z() << endl;