Public Types | Public Member Functions | Protected Attributes
octomap::ScanGraph Class Reference

#include <ScanGraph.h>

List of all members.

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

ScanEdgeaddEdge (ScanNode *first, ScanNode *second, pose6d constraint)
ScanEdgeaddEdge (unsigned int first_id, unsigned int second_id)
ScanNodeaddNode (Pointcloud *scan, pose6d pose)
iterator begin ()
const_iterator begin () const
void clear ()
 Clears all nodes and edges, and will delete the corresponding objects.
void connectPrevious ()
 Connect previously added ScanNode to the one before that.
void crop (point3d lowerBound, point3d upperBound)
 Cut graph (all containing Pointclouds) to given BBX in global coords.
void cropEachScan (point3d lowerBound, point3d upperBound)
 Cut Pointclouds to given BBX in local coords.
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)
ScanNodegetNodeByID (unsigned int id)
 will return NULL if node was not found
unsigned int 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 ()
unsigned int size () const
void transformScans ()
 Transform every scan according to its pose.
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

Detailed Description

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.


Member Typedef Documentation

Definition at line 184 of file ScanGraph.h.

Definition at line 174 of file ScanGraph.h.

Definition at line 183 of file ScanGraph.h.

Definition at line 173 of file ScanGraph.h.


Constructor & Destructor Documentation

Definition at line 118 of file ScanGraph.h.

Definition at line 159 of file ScanGraph.cpp.


Member Function Documentation

ScanEdge * octomap::ScanGraph::addEdge ( ScanNode first,
ScanNode second,
pose6d  constraint 
)

Creates an edge between two ScanNodes. ScanGraph will delete the object when it's no longer needed, don't delete it yourself.

Parameters:
firstScanNode
secondScanNode
constraint6D transform between the two nodes
Returns:

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.

Creates a new ScanNode in the graph from a Pointcloud.

Parameters:
scanPointer 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.
pose6D pose of the origin of the Pointcloud
Returns:
Pointer to the new node

Definition at line 175 of file ScanGraph.cpp.

Definition at line 175 of file ScanGraph.h.

Definition at line 177 of file ScanGraph.h.

Clears all nodes and edges, and will delete the corresponding objects.

Definition at line 163 of file ScanGraph.cpp.

Connect previously added ScanNode to the one before that.

Definition at line 222 of file ScanGraph.cpp.

void octomap::ScanGraph::crop ( point3d  lowerBound,
point3d  upperBound 
)

Cut graph (all containing Pointclouds) to given BBX in global coords.

Definition at line 591 of file ScanGraph.cpp.

void octomap::ScanGraph::cropEachScan ( point3d  lowerBound,
point3d  upperBound 
)

Cut Pointclouds to given BBX in local coords.

Definition at line 583 of file ScanGraph.cpp.

bool octomap::ScanGraph::edgeExists ( unsigned int  first_id,
unsigned int  second_id 
)
Returns:
true when an edge between first_id and second_id exists

Definition at line 255 of file ScanGraph.cpp.

Definition at line 185 of file ScanGraph.h.

Definition at line 187 of file ScanGraph.h.

Definition at line 186 of file ScanGraph.h.

Definition at line 188 of file ScanGraph.h.

Definition at line 176 of file ScanGraph.h.

Definition at line 178 of file ScanGraph.h.

void octomap::ScanGraph::exportDot ( std::string  filename)

Definition at line 232 of file ScanGraph.cpp.

std::vector< ScanEdge * > octomap::ScanGraph::getInEdges ( ScanNode node)

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.

unsigned int octomap::ScanGraph::getNumPoints ( unsigned int  max_id = -1) const

Definition at line 606 of file ScanGraph.cpp.

std::vector< ScanEdge * > octomap::ScanGraph::getOutEdges ( ScanNode node)

Definition at line 283 of file ScanGraph.cpp.

std::istream & octomap::ScanGraph::readBinary ( std::ifstream &  s)

Definition at line 364 of file ScanGraph.cpp.

bool octomap::ScanGraph::readBinary ( const std::string &  filename)

Definition at line 353 of file ScanGraph.cpp.

std::istream & octomap::ScanGraph::readEdgesASCII ( std::istream &  s)

Definition at line 505 of file ScanGraph.cpp.

std::istream & octomap::ScanGraph::readNodePosesASCII ( std::istream &  s)

Definition at line 551 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

Parameters:
sinput stream to read from
Returns:
read stream

Definition at line 431 of file ScanGraph.cpp.

void octomap::ScanGraph::readPlainASCII ( const std::string &  filename)

Definition at line 421 of file ScanGraph.cpp.

unsigned int octomap::ScanGraph::size ( ) const [inline]

Definition at line 180 of file ScanGraph.h.

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 486 of file ScanGraph.cpp.

std::ostream & octomap::ScanGraph::writeNodePosesASCII ( std::ostream &  s) const

Definition at line 538 of file ScanGraph.cpp.


Member Data Documentation

std::vector<ScanEdge*> octomap::ScanGraph::edges [protected]

Definition at line 225 of file ScanGraph.h.

std::vector<ScanNode*> octomap::ScanGraph::nodes [protected]

Definition at line 224 of file ScanGraph.h.


The documentation for this class was generated from the following files:


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Feb 11 2016 23:51:00