Public Types | Public Member Functions | Protected Attributes | List of all members
octomap::ScanGraph Class Reference

#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

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. 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)
 
ScanNodegetNodeByID (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)
 
bool readBinary (const std::string &filename)
 
std::istream & readBinary (std::ifstream &s)
 
std::istream & readEdgesASCII (std::istream &s)
 
std::istream & readNodePosesASCII (std::istream &s)
 
void readPlainASCII (const std::string &filename)
 
std::istream & readPlainASCII (std::istream &s)
 
 ScanGraph ()
 
size_t size () const
 
void transformScans ()
 Transform every scan according to its pose. More...
 
bool writeBinary (const std::string &filename) const
 
std::ostream & writeBinary (std::ostream &s) 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

◆ const_edge_iterator

Definition at line 184 of file ScanGraph.h.

◆ const_iterator

Definition at line 174 of file ScanGraph.h.

◆ edge_iterator

Definition at line 183 of file ScanGraph.h.

◆ iterator

Definition at line 173 of file ScanGraph.h.

Constructor & Destructor Documentation

◆ ScanGraph()

octomap::ScanGraph::ScanGraph ( )
inline

Definition at line 118 of file ScanGraph.h.

◆ ~ScanGraph()

octomap::ScanGraph::~ScanGraph ( )

Definition at line 163 of file ScanGraph.cpp.

Member Function Documentation

◆ addEdge() [1/2]

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

◆ addEdge() [2/2]

ScanEdge * octomap::ScanGraph::addEdge ( unsigned int  first_id,
unsigned int  second_id 
)

Definition at line 205 of file ScanGraph.cpp.

◆ addNode()

ScanNode * octomap::ScanGraph::addNode ( Pointcloud scan,
pose6d  pose 
)

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

◆ begin() [1/2]

iterator octomap::ScanGraph::begin ( )
inline

Definition at line 175 of file ScanGraph.h.

◆ begin() [2/2]

const_iterator octomap::ScanGraph::begin ( ) const
inline

Definition at line 177 of file ScanGraph.h.

◆ clear()

void octomap::ScanGraph::clear ( )

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

Definition at line 167 of file ScanGraph.cpp.

◆ connectPrevious()

void octomap::ScanGraph::connectPrevious ( )

Connect previously added ScanNode to the one before that.

Definition at line 226 of file ScanGraph.cpp.

◆ crop()

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

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

Definition at line 596 of file ScanGraph.cpp.

◆ cropEachScan()

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

Cut Pointclouds to given BBX in local coords.

Definition at line 588 of file ScanGraph.cpp.

◆ edgeExists()

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

◆ edges_begin() [1/2]

edge_iterator octomap::ScanGraph::edges_begin ( )
inline

Definition at line 185 of file ScanGraph.h.

◆ edges_begin() [2/2]

const_edge_iterator octomap::ScanGraph::edges_begin ( ) const
inline

Definition at line 187 of file ScanGraph.h.

◆ edges_end() [1/2]

edge_iterator octomap::ScanGraph::edges_end ( )
inline

Definition at line 186 of file ScanGraph.h.

◆ edges_end() [2/2]

const_edge_iterator octomap::ScanGraph::edges_end ( ) const
inline

Definition at line 188 of file ScanGraph.h.

◆ end() [1/2]

iterator octomap::ScanGraph::end ( )
inline

Definition at line 176 of file ScanGraph.h.

◆ end() [2/2]

const_iterator octomap::ScanGraph::end ( ) const
inline

Definition at line 178 of file ScanGraph.h.

◆ exportDot()

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

Definition at line 236 of file ScanGraph.cpp.

◆ getInEdges()

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

Definition at line 299 of file ScanGraph.cpp.

◆ getNeighborIDs()

std::vector< unsigned int > octomap::ScanGraph::getNeighborIDs ( unsigned int  id)

Definition at line 272 of file ScanGraph.cpp.

◆ getNodeByID()

ScanNode * octomap::ScanGraph::getNodeByID ( unsigned int  id)

will return NULL if node was not found

Definition at line 252 of file ScanGraph.cpp.

◆ getNumPoints()

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

Definition at line 611 of file ScanGraph.cpp.

◆ getOutEdges()

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

Definition at line 287 of file ScanGraph.cpp.

◆ readBinary() [1/2]

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

Definition at line 358 of file ScanGraph.cpp.

◆ readBinary() [2/2]

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

Definition at line 369 of file ScanGraph.cpp.

◆ readEdgesASCII()

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

Definition at line 510 of file ScanGraph.cpp.

◆ readNodePosesASCII()

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

Definition at line 556 of file ScanGraph.cpp.

◆ readPlainASCII() [1/2]

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

Definition at line 426 of file ScanGraph.cpp.

◆ readPlainASCII() [2/2]

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

◆ size()

size_t octomap::ScanGraph::size ( ) const
inline

Definition at line 180 of file ScanGraph.h.

◆ transformScans()

void octomap::ScanGraph::transformScans ( )

Transform every scan according to its pose.

Definition at line 311 of file ScanGraph.cpp.

◆ writeBinary() [1/2]

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

Definition at line 317 of file ScanGraph.cpp.

◆ writeBinary() [2/2]

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

Definition at line 328 of file ScanGraph.cpp.

◆ writeEdgesASCII()

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

Definition at line 491 of file ScanGraph.cpp.

◆ writeNodePosesASCII()

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

Definition at line 543 of file ScanGraph.cpp.

Member Data Documentation

◆ edges

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

Definition at line 225 of file ScanGraph.h.

◆ nodes

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 Mar 21 2024 02:40:30