#include <ScanGraph.h>
Public Types | |
typedef std::vector< ScanEdge * >::const_iterator | const_edge_iterator |
typedef std::vector< ScanNode * >::const_iterator | const_iterator |
typedef std::vector< ScanEdge * >::iterator | edge_iterator |
typedef std::vector< ScanNode * >::iterator | iterator |
Public Member Functions | |
ScanEdge * | addEdge (ScanNode *first, ScanNode *second, pose6d constraint) |
ScanEdge * | addEdge (unsigned int first_id, unsigned int second_id) |
ScanNode * | addNode (Pointcloud *scan, pose6d pose) |
iterator | begin () |
const_iterator | begin () const |
void | clear () |
Clears all nodes and edges, and will delete the corresponding objects. More... | |
void | connectPrevious () |
Connect previously added ScanNode to the one before that. More... | |
void | crop (point3d lowerBound, point3d upperBound) |
Cut graph (all containing Pointclouds) to given BBX in global coords. More... | |
void | cropEachScan (point3d lowerBound, point3d upperBound) |
Cut Pointclouds to given BBX in local coords. More... | |
bool | edgeExists (unsigned int first_id, unsigned int second_id) |
edge_iterator | edges_begin () |
const_edge_iterator | edges_begin () const |
edge_iterator | edges_end () |
const_edge_iterator | edges_end () const |
iterator | end () |
const_iterator | end () const |
void | exportDot (std::string filename) |
std::vector< ScanEdge * > | getInEdges (ScanNode *node) |
std::vector< unsigned int > | getNeighborIDs (unsigned int id) |
ScanNode * | getNodeByID (unsigned int id) |
will return NULL if node was not found More... | |
size_t | getNumPoints (unsigned int max_id=-1) const |
std::vector< ScanEdge * > | getOutEdges (ScanNode *node) |
std::istream & | readBinary (std::ifstream &s) |
bool | readBinary (const std::string &filename) |
std::istream & | readEdgesASCII (std::istream &s) |
std::istream & | readNodePosesASCII (std::istream &s) |
std::istream & | readPlainASCII (std::istream &s) |
void | readPlainASCII (const std::string &filename) |
ScanGraph () | |
size_t | size () const |
void | transformScans () |
Transform every scan according to its pose. More... | |
std::ostream & | writeBinary (std::ostream &s) const |
bool | writeBinary (const std::string &filename) const |
std::ostream & | writeEdgesASCII (std::ostream &s) const |
std::ostream & | writeNodePosesASCII (std::ostream &s) const |
~ScanGraph () | |
Protected Attributes | |
std::vector< ScanEdge * > | edges |
std::vector< ScanNode * > | nodes |
A ScanGraph is a collection of ScanNodes, connected by ScanEdges. Each ScanNode contains a 3D scan performed from a pose.
Definition at line 114 of file ScanGraph.h.
typedef std::vector<ScanEdge*>::const_iterator octomap::ScanGraph::const_edge_iterator |
Definition at line 184 of file ScanGraph.h.
typedef std::vector<ScanNode*>::const_iterator octomap::ScanGraph::const_iterator |
Definition at line 174 of file ScanGraph.h.
typedef std::vector<ScanEdge*>::iterator octomap::ScanGraph::edge_iterator |
Definition at line 183 of file ScanGraph.h.
typedef std::vector<ScanNode*>::iterator octomap::ScanGraph::iterator |
Definition at line 173 of file ScanGraph.h.
|
inline |
Definition at line 118 of file ScanGraph.h.
octomap::ScanGraph::~ScanGraph | ( | ) |
Definition at line 159 of file ScanGraph.cpp.
Creates an edge between two ScanNodes. ScanGraph will delete the object when it's no longer needed, don't delete it yourself.
Definition at line 187 of file ScanGraph.cpp.
ScanEdge * octomap::ScanGraph::addEdge | ( | unsigned int | first_id, |
unsigned int | second_id | ||
) |
Definition at line 201 of file ScanGraph.cpp.
ScanNode * octomap::ScanGraph::addNode | ( | Pointcloud * | scan, |
pose6d | pose | ||
) |
Creates a new ScanNode in the graph from a Pointcloud.
scan | Pointer to a pointcloud to be added to the ScanGraph. ScanGraph will delete the object when it's no longer needed, don't delete it yourself. |
pose | 6D pose of the origin of the Pointcloud |
Definition at line 175 of file ScanGraph.cpp.
|
inline |
Definition at line 175 of file ScanGraph.h.
|
inline |
Definition at line 177 of file ScanGraph.h.
void octomap::ScanGraph::clear | ( | ) |
Clears all nodes and edges, and will delete the corresponding objects.
Definition at line 163 of file ScanGraph.cpp.
void octomap::ScanGraph::connectPrevious | ( | ) |
Connect previously added ScanNode to the one before that.
Definition at line 222 of file ScanGraph.cpp.
Cut graph (all containing Pointclouds) to given BBX in global coords.
Definition at line 592 of file ScanGraph.cpp.
Cut Pointclouds to given BBX in local coords.
Definition at line 584 of file ScanGraph.cpp.
bool octomap::ScanGraph::edgeExists | ( | unsigned int | first_id, |
unsigned int | second_id | ||
) |
Definition at line 255 of file ScanGraph.cpp.
|
inline |
Definition at line 185 of file ScanGraph.h.
|
inline |
Definition at line 187 of file ScanGraph.h.
|
inline |
Definition at line 186 of file ScanGraph.h.
|
inline |
Definition at line 188 of file ScanGraph.h.
|
inline |
Definition at line 176 of file ScanGraph.h.
|
inline |
Definition at line 178 of file ScanGraph.h.
void octomap::ScanGraph::exportDot | ( | std::string | filename | ) |
Definition at line 232 of file ScanGraph.cpp.
Definition at line 295 of file ScanGraph.cpp.
std::vector< unsigned int > octomap::ScanGraph::getNeighborIDs | ( | unsigned int | id | ) |
Definition at line 268 of file ScanGraph.cpp.
ScanNode * octomap::ScanGraph::getNodeByID | ( | unsigned int | id | ) |
will return NULL if node was not found
Definition at line 248 of file ScanGraph.cpp.
size_t octomap::ScanGraph::getNumPoints | ( | unsigned int | max_id = -1 | ) | const |
Definition at line 607 of file ScanGraph.cpp.
Definition at line 283 of file ScanGraph.cpp.
std::istream & octomap::ScanGraph::readBinary | ( | std::ifstream & | s | ) |
Definition at line 365 of file ScanGraph.cpp.
bool octomap::ScanGraph::readBinary | ( | const std::string & | filename | ) |
Definition at line 354 of file ScanGraph.cpp.
std::istream & octomap::ScanGraph::readEdgesASCII | ( | std::istream & | s | ) |
Definition at line 506 of file ScanGraph.cpp.
std::istream & octomap::ScanGraph::readNodePosesASCII | ( | std::istream & | s | ) |
Definition at line 552 of file ScanGraph.cpp.
std::istream & octomap::ScanGraph::readPlainASCII | ( | std::istream & | s | ) |
Reads in a ScanGraph from a "plain" ASCII file of the form NODE x y z R P Y x y z x y z x y z NODE x y z R P Y x y z
Lines starting with the NODE keyword contain the 6D pose of a scan node, all 3D point following until the next NODE keyword (or end of file) are inserted into that scan node as pointcloud in its local coordinate frame
s | input stream to read from |
Definition at line 432 of file ScanGraph.cpp.
void octomap::ScanGraph::readPlainASCII | ( | const std::string & | filename | ) |
Definition at line 422 of file ScanGraph.cpp.
|
inline |
Definition at line 180 of file ScanGraph.h.
void octomap::ScanGraph::transformScans | ( | ) |
Transform every scan according to its pose.
Definition at line 307 of file ScanGraph.cpp.
std::ostream & octomap::ScanGraph::writeBinary | ( | std::ostream & | s | ) | const |
Definition at line 324 of file ScanGraph.cpp.
bool octomap::ScanGraph::writeBinary | ( | const std::string & | filename | ) | const |
Definition at line 313 of file ScanGraph.cpp.
std::ostream & octomap::ScanGraph::writeEdgesASCII | ( | std::ostream & | s | ) | const |
Definition at line 487 of file ScanGraph.cpp.
std::ostream & octomap::ScanGraph::writeNodePosesASCII | ( | std::ostream & | s | ) | const |
Definition at line 539 of file ScanGraph.cpp.
|
protected |
Definition at line 225 of file ScanGraph.h.
|
protected |
Definition at line 224 of file ScanGraph.h.