Class ScanGraph

Class Documentation

class ScanGraph

A ScanGraph is a collection of ScanNodes, connected by ScanEdges. Each ScanNode contains a 3D scan performed from a pose.

Public Types

typedef std::vector<ScanNode*>::iterator iterator
typedef std::vector<ScanNode*>::const_iterator const_iterator
typedef std::vector<ScanEdge*>::iterator edge_iterator
typedef std::vector<ScanEdge*>::const_iterator const_edge_iterator

Public Functions

inline ScanGraph()
~ScanGraph()
void clear()

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

ScanNode *addNode(Pointcloud *scan, pose6d pose)

Creates a new ScanNode in the graph from a Pointcloud.

Parameters:
  • 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

Returns:

Pointer to the new node

ScanEdge *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

  • constraint – 6D transform between the two nodes

Returns:

ScanEdge *addEdge(unsigned int first_id, unsigned int second_id)
ScanNode *getNodeByID(unsigned int id)

will return NULL if node was not found

bool edgeExists(unsigned int first_id, unsigned int second_id)
Returns:

true when an edge between first_id and second_id exists

void connectPrevious()

Connect previously added ScanNode to the one before that.

std::vector<unsigned int> getNeighborIDs(unsigned int id)
std::vector<ScanEdge*> getOutEdges(ScanNode *node)
std::vector<ScanEdge*> getInEdges(ScanNode *node)
void exportDot(std::string filename)
void transformScans()

Transform every scan according to its pose.

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.

inline iterator begin()
inline iterator end()
inline const_iterator begin() const
inline const_iterator end() const
inline size_t size() const
size_t getNumPoints(unsigned int max_id = -1) const
inline edge_iterator edges_begin()
inline edge_iterator edges_end()
inline const_edge_iterator edges_begin() const
inline const_edge_iterator edges_end() const
std::ostream &writeBinary(std::ostream &s) const
std::istream &readBinary(std::ifstream &s)
bool writeBinary(const std::string &filename) const
bool readBinary(const std::string &filename)
std::ostream &writeEdgesASCII(std::ostream &s) const
std::istream &readEdgesASCII(std::istream &s)
std::ostream &writeNodePosesASCII(std::ostream &s) const
std::istream &readNodePosesASCII(std::istream &s)
std::istream &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:

s – input stream to read from

Returns:

read stream

void readPlainASCII(const std::string &filename)

Protected Attributes

std::vector<ScanNode*> nodes
std::vector<ScanEdge*> edges