Go to the documentation of this file.
34 #ifndef OCTOMAP_SCANGRAPH_H
35 #define OCTOMAP_SCANGRAPH_H
64 return (
id == other.
id);
98 std::ostream&
writeASCII(std::ostream &s)
const;
151 bool edgeExists(
unsigned int first_id,
unsigned int second_id);
193 bool writeBinary(
const std::string& filename)
const;
void clear()
Clears all nodes and edges, and will delete the corresponding objects.
Definition: ScanGraph.cpp:167
pose6d pose
6D pose from which the scan was performed
Definition: ScanGraph.h:74
A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan.
Definition: Pointcloud.h:47
pose6d constraint
Definition: ScanGraph.h:104
ScanNode(Pointcloud *_scan, pose6d _pose, unsigned int _id)
Definition: ScanGraph.h:56
std::istream & readPoseASCII(std::istream &s)
Definition: ScanGraph.cpp:90
edge_iterator edges_begin()
Definition: ScanGraph.h:185
std::istream & readEdgesASCII(std::istream &s)
Definition: ScanGraph.cpp:510
std::ostream & writePoseASCII(std::ostream &s) const
Definition: ScanGraph.cpp:80
std::ostream & writeBinary(std::ostream &s) const
Definition: ScanGraph.cpp:52
const_edge_iterator edges_begin() const
Definition: ScanGraph.h:187
std::vector< ScanEdge * > getOutEdges(ScanNode *node)
Definition: ScanGraph.cpp:287
bool edgeExists(unsigned int first_id, unsigned int second_id)
Definition: ScanGraph.cpp:259
std::ostream & writeEdgesASCII(std::ostream &s) const
Definition: ScanGraph.cpp:491
std::vector< ScanNode * >::const_iterator const_iterator
Definition: ScanGraph.h:174
ScanNode * second
Definition: ScanGraph.h:102
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 ...
Definition: ScanGraph.cpp:436
This class represents a three-dimensional vector.
Definition: Vector3.h:50
std::vector< ScanNode * > nodes
Definition: ScanGraph.h:224
A ScanGraph is a collection of ScanNodes, connected by ScanEdges.
Definition: ScanGraph.h:114
~ScanGraph()
Definition: ScanGraph.cpp:163
iterator end()
Definition: ScanGraph.h:176
~ScanNode()
Definition: ScanGraph.cpp:45
ScanGraph()
Definition: ScanGraph.h:118
size_t getNumPoints(unsigned int max_id=-1) const
Definition: ScanGraph.cpp:611
std::ostream & writeNodePosesASCII(std::ostream &s) const
Definition: ScanGraph.cpp:543
ScanNode * first
Definition: ScanGraph.h:101
const_iterator end() const
Definition: ScanGraph.h:178
A 3D scan as Pointcloud, performed from a Pose6D.
Definition: ScanGraph.h:52
void exportDot(std::string filename)
Definition: ScanGraph.cpp:236
ScanNode()
Definition: ScanGraph.h:58
iterator begin()
Definition: ScanGraph.h:175
void connectPrevious()
Connect previously added ScanNode to the one before that.
Definition: ScanGraph.cpp:226
bool operator==(const ScanEdge &other)
Definition: ScanGraph.h:90
size_t size() const
Definition: ScanGraph.h:180
const_iterator begin() const
Definition: ScanGraph.h:177
ScanNode * getNodeByID(unsigned int id)
will return NULL if node was not found
Definition: ScanGraph.cpp:252
std::istream & readBinary(std::istream &s)
Definition: ScanGraph.cpp:65
ScanEdge(ScanNode *_first, ScanNode *_second, pose6d _constraint)
Definition: ScanGraph.h:86
unsigned int id
Definition: ScanGraph.h:75
bool operator==(const ScanNode &other)
Definition: ScanGraph.h:63
std::istream & readBinary(std::istream &s, ScanGraph &graph)
Definition: ScanGraph.cpp:117
edge_iterator edges_end()
Definition: ScanGraph.h:186
std::istream & readASCII(std::istream &s, ScanGraph &graph)
Definition: ScanGraph.cpp:146
std::vector< ScanEdge * > getInEdges(ScanNode *node)
Definition: ScanGraph.cpp:299
A connection between two ScanNodes.
Definition: ScanGraph.h:82
const_edge_iterator edges_end() const
Definition: ScanGraph.h:188
std::vector< ScanEdge * >::const_iterator const_edge_iterator
Definition: ScanGraph.h:184
ScanNode * addNode(Pointcloud *scan, pose6d pose)
Creates a new ScanNode in the graph from a Pointcloud.
Definition: ScanGraph.cpp:179
ScanEdge * addEdge(ScanNode *first, ScanNode *second, pose6d constraint)
Creates an edge between two ScanNodes.
Definition: ScanGraph.cpp:191
std::ostream & writeBinary(std::ostream &s) const
Definition: ScanGraph.cpp:106
std::ostream & writeBinary(std::ostream &s) const
Definition: ScanGraph.cpp:328
void transformScans()
Transform every scan according to its pose.
Definition: ScanGraph.cpp:311
std::istream & readNodePosesASCII(std::istream &s)
Definition: ScanGraph.cpp:556
std::vector< ScanEdge * > edges
Definition: ScanGraph.h:225
std::ostream & writeASCII(std::ostream &s) const
Definition: ScanGraph.cpp:134
double weight
Definition: ScanGraph.h:105
Tables used by the Marching Cubes Algorithm The tables are from Paul Bourke's web page http://paulbou...
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
Pointcloud * scan
Definition: ScanGraph.h:73
void cropEachScan(point3d lowerBound, point3d upperBound)
Cut Pointclouds to given BBX in local coords.
Definition: ScanGraph.cpp:588
std::vector< ScanNode * >::iterator iterator
Definition: ScanGraph.h:173
std::vector< unsigned int > getNeighborIDs(unsigned int id)
Definition: ScanGraph.cpp:272
void crop(point3d lowerBound, point3d upperBound)
Cut graph (all containing Pointclouds) to given BBX in global coords.
Definition: ScanGraph.cpp:596
ScanEdge()
Definition: ScanGraph.h:88
std::istream & readBinary(std::ifstream &s)
Definition: ScanGraph.cpp:369
std::vector< ScanEdge * >::iterator edge_iterator
Definition: ScanGraph.h:183