Go to the documentation of this file.
59 uint32_t uintId =
static_cast<uint32_t
>(
id);
60 s.write((
char*)&uintId,
sizeof(uintId));
73 s.read((
char*)&uintId,
sizeof(uintId));
93 if (read_id != this->
id)
94 OCTOMAP_ERROR(
"ERROR while reading ScanNode pose from ASCII. id %d does not match real id %d.\n", read_id, this->
id);
118 unsigned int first_id, second_id;
119 s.read((
char*)&first_id,
sizeof(first_id));
120 s.read((
char*)&second_id,
sizeof(second_id));
123 if (this->
first == NULL)
OCTOMAP_ERROR(
"ERROR while reading ScanEdge. first node not found.\n");
125 if (this->
second == NULL)
OCTOMAP_ERROR(
"ERROR while reading ScanEdge. second node not found.\n");
148 unsigned int first_id, second_id;
153 if (this->
first == NULL)
OCTOMAP_ERROR(
"ERROR while reading ScanEdge. first node %d not found.\n", first_id);
155 if (this->
second == NULL)
OCTOMAP_ERROR(
"ERROR while reading ScanEdge. second node %d not found.\n", second_id);
168 for (
unsigned int i=0; i<
nodes.size(); i++) {
172 for (
unsigned int i=0; i<
edges.size(); i++) {
193 if ((first != 0) && (second != 0)) {
215 if ((first != 0) && (second != 0)) {
217 return this->
addEdge(first, second, constr);
227 if (
nodes.size() >= 2) {
231 this->
addEdge(first, second, c);
237 std::ofstream outfile (filename.c_str());
238 outfile <<
"graph ScanGraph" << std::endl;
239 outfile <<
"{" << std::endl;
240 for (
unsigned int i=0; i<
edges.size(); i++) {
241 outfile << (
edges[i]->first)->
id
243 << (
edges[i]->second)->id
245 << std::fixed << std::setprecision(2) <<
edges[i]->constraint.transLength()
248 outfile <<
"}" << std::endl;
253 for (
unsigned int i = 0; i <
nodes.size(); i++) {
261 for (
unsigned int i=0; i<
edges.size(); i++) {
263 (((
edges[i]->first)->
id == first_id) && ((
edges[i]->second)->
id == second_id))
265 (((
edges[i]->first)->
id == second_id) && ((
edges[i]->second)->
id == first_id))) {
273 std::vector<unsigned int> res;
277 for (
unsigned int i = 0; i <
nodes.size(); i++) {
278 if (node->
id ==
nodes[i]->id)
continue;
280 res.push_back(
nodes[i]->
id);
288 std::vector<ScanEdge*> res;
290 for (std::vector<ScanEdge*>::iterator it =
edges.begin(); it !=
edges.end(); it++) {
291 if ((*it)->first == node) {
300 std::vector<ScanEdge*> res;
302 for (std::vector<ScanEdge*>::iterator it =
edges.begin(); it !=
edges.end(); it++) {
303 if ((*it)->second == node) {
313 ((*it)->scan)->transformAbsolute((*it)->pose);
318 std::ofstream binary_outfile( filename.c_str(), std::ios_base::binary);
319 if (!binary_outfile.is_open()){
324 binary_outfile.close();
334 unsigned int graph_size = (
unsigned int) this->
size();
335 if (graph_size)
OCTOMAP_DEBUG(
"writing %u nodes to binary file...\n", graph_size);
336 s.write((
char*)&graph_size,
sizeof(graph_size));
339 (*it)->writeBinary(s);
345 unsigned int num_edges = (
unsigned int) this->
edges.size();
346 if (num_edges)
OCTOMAP_DEBUG(
"writing %u edges to binary file...\n", num_edges);
347 s.write((
char*)&num_edges,
sizeof(num_edges));
350 (*it)->writeBinary(s);
359 std::ifstream binary_infile(filename.c_str(), std::ios_base::binary);
360 if (!binary_infile.is_open()){
365 binary_infile.close();
371 OCTOMAP_ERROR_STR(
"Could not read from input filestream in ScanGraph::readBinary");
373 }
else if (!s.good()){
379 unsigned int graph_size = 0;
380 s.read((
char*)&graph_size,
sizeof(graph_size));
381 if (graph_size)
OCTOMAP_DEBUG(
"reading %d nodes from binary file...\n", graph_size);
383 if (graph_size > 0) {
384 this->
nodes.reserve(graph_size);
386 for (
unsigned int i=0; i<graph_size; i++) {
391 this->
nodes.push_back(node);
402 unsigned int num_edges = 0;
403 s.read((
char*)&num_edges,
sizeof(num_edges));
404 if (num_edges)
OCTOMAP_DEBUG(
"reading %d edges from binary file...\n", num_edges);
407 this->
edges.reserve(num_edges);
409 for (
unsigned int i=0; i<num_edges; i++) {
414 this->
edges.push_back(edge);
427 std::ifstream infile(filename.c_str());
428 if (!infile.is_open()){
437 std::string currentLine;
440 getline(s, currentLine);
441 if (s.good() && !s.eof()){
442 std::stringstream ss;
445 if (currentLine.size() == 0
446 || (currentLine.compare(0,1,
"#") == 0)
447 || (currentLine.compare(0,1,
" ") == 0)){
450 }
else if(currentLine.compare(0,4,
"NODE")==0){
452 this->
nodes.push_back(currentNode);
460 float x, y, z, roll, pitch, yaw;
462 ss >> tmp >> x >> y >> z >> roll >> pitch >> yaw;
463 pose6d pose(x, y, z, roll, pitch, yaw);
465 currentNode->
pose = pose;
467 if (currentNode == NULL){
480 this->
nodes.push_back(currentNode);
497 s <<
" " << this->
edges.size();
501 (*it)->writeASCII(s);
512 unsigned int num_edges = 0;
514 OCTOMAP_DEBUG(
"Reading %d edges from ASCII file...\n", num_edges);
518 for (
unsigned int i=0; i<this->
edges.size(); i++)
delete edges[i];
521 this->
edges.reserve(num_edges);
523 for (
unsigned int i=0; i<num_edges; i++) {
528 this->
edges.push_back(edge);
545 OCTOMAP_DEBUG(
"Writing %lu node poses to ASCII file...\n", (
unsigned long) this->
size());
548 (*it)->writePoseASCII(s);
559 (*it)->readPoseASCII(s);
565 (*it)->constraint = (first->
pose).inv() * second->
pose;
591 ((*it)->scan)->
crop(lowerBound, upperBound);
601 pose6d scan_pose = (*it)->pose;
604 pc->
crop(lowerBound, upperBound);
615 retval += (*it)->scan->size();
616 if ((max_id > 0) && ((*it)->id == max_id))
break;
void clear()
Clears all nodes and edges, and will delete the corresponding objects.
std::istream & readBinary(std::istream &s)
#define OCTOMAP_WARNING_STR(args)
pose6d pose
6D pose from which the scan was performed
Vector3 toEuler() const
Conversion to Euler angles.
void crop(point3d lowerBound, point3d upperBound)
Crop Pointcloud to given bounding box.
std::istream & readPoseASCII(std::istream &s)
void push_back(float x, float y, float z)
edge_iterator edges_begin()
std::istream & readEdgesASCII(std::istream &s)
std::ostream & writePoseASCII(std::ostream &s) const
std::ostream & writeBinary(std::ostream &s) const
std::vector< ScanEdge * > getOutEdges(ScanNode *node)
#define OCTOMAP_DEBUG(...)
bool edgeExists(unsigned int first_id, unsigned int second_id)
std::ostream & writeEdgesASCII(std::ostream &s) const
std::vector< ScanNode * >::const_iterator const_iterator
std::istream & readPlainASCII(std::istream &s)
#define OCTOMAP_DEBUG_STR(args)
This class represents a three-dimensional vector.
std::vector< ScanNode * > nodes
std::ostream & writeBinary(std::ostream &s) const
size_t getNumPoints(unsigned int max_id=-1) const
std::ostream & writeNodePosesASCII(std::ostream &s) const
void exportDot(std::string filename)
std::istream & read(std::istream &s)
void connectPrevious()
Connect previously added ScanNode to the one before that.
ScanNode * getNodeByID(unsigned int id)
will return NULL if node was not found
#define OCTOMAP_ERROR(...)
std::istream & readBinary(std::istream &s)
void transform(pose6d transform)
Apply transform to each point.
std::ostream & writeBinary(std::ostream &s) const
Binary output operator.
std::istream & readBinary(std::istream &s)
Binary input operator.
std::istream & readBinary(std::istream &s, ScanGraph &graph)
edge_iterator edges_end()
std::istream & readASCII(std::istream &s, ScanGraph &graph)
std::vector< ScanEdge * > getInEdges(ScanNode *node)
#define OCTOMAP_ERROR_STR(args)
std::ostream & write(std::ostream &s) const
std::ostream & write(std::ostream &s) const
Output operator.
std::vector< ScanEdge * >::const_iterator const_edge_iterator
ScanNode * addNode(Pointcloud *scan, pose6d pose)
ScanEdge * addEdge(ScanNode *first, ScanNode *second, pose6d constraint)
Quaternion & rot()
Rotational component.
std::ostream & writeBinary(std::ostream &s) const
std::ostream & writeBinary(std::ostream &s) const
void transformScans()
Transform every scan according to its pose.
std::istream & readNodePosesASCII(std::istream &s)
std::vector< ScanEdge * > edges
std::ostream & writeASCII(std::ostream &s) const
This class represents a tree-dimensional pose of an object.
void transformAbsolute(pose6d transform)
Apply transform to each point, undo previous transforms.
void cropEachScan(point3d lowerBound, point3d upperBound)
Cut Pointclouds to given BBX in local coords.
std::vector< ScanNode * >::iterator iterator
std::istream & read(std::istream &s)
Input operator.
This class represents a Quaternion.
std::vector< unsigned int > getNeighborIDs(unsigned int id)
Pose6D inv() const
Inversion.
void crop(point3d lowerBound, point3d upperBound)
Cut graph (all containing Pointclouds) to given BBX in global coords.
Vector3 & trans()
Translational component.
std::istream & readBinary(std::ifstream &s)
std::vector< ScanEdge * >::iterator edge_iterator
octomap
Author(s): Kai M. Wurm
, Armin Hornung
autogenerated on Tue Dec 12 2023 03:39:40