octomap 1.5.0
|
00001 // $Id: ScanGraph.h 245 2011-08-09 10:00:53Z kai_wurm $ 00002 00011 /* 00012 * Copyright (c) 2009, K. M. Wurm, A. Hornung, University of Freiburg 00013 * All rights reserved. 00014 * 00015 * Redistribution and use in source and binary forms, with or without 00016 * modification, are permitted provided that the following conditions are met: 00017 * 00018 * * Redistributions of source code must retain the above copyright 00019 * notice, this list of conditions and the following disclaimer. 00020 * * Redistributions in binary form must reproduce the above copyright 00021 * notice, this list of conditions and the following disclaimer in the 00022 * documentation and/or other materials provided with the distribution. 00023 * * Neither the name of the University of Freiburg nor the names of its 00024 * contributors may be used to endorse or promote products derived from 00025 * this software without specific prior written permission. 00026 * 00027 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00028 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00029 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00030 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00031 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00032 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00033 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00034 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00035 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00036 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00037 * POSSIBILITY OF SUCH DAMAGE. 00038 */ 00039 00040 #ifndef OCTOMAP_SCANGRAPH_H 00041 #define OCTOMAP_SCANGRAPH_H 00042 00043 00044 #include <string> 00045 #include <math.h> 00046 00047 #include "Pointcloud.h" 00048 #include "octomap_types.h" 00049 00050 namespace octomap { 00051 00052 class ScanGraph; 00053 00054 00058 class ScanNode { 00059 00060 public: 00061 00062 ScanNode (Pointcloud* _scan, pose6d _pose, unsigned int _id) 00063 : scan(_scan), pose(_pose), id(_id) {} 00064 ScanNode () 00065 : scan(NULL) {} 00066 00067 ~ScanNode(); 00068 00069 bool operator == (const ScanNode& other) { 00070 return (id == other.id); 00071 } 00072 00073 std::ostream& writeBinary(std::ostream &s) const; 00074 std::istream& readBinary(std::istream &s); 00075 00076 std::ostream& writePoseASCII(std::ostream &s) const; 00077 std::istream& readPoseASCII(std::istream &s); 00078 00079 Pointcloud* scan; 00080 pose6d pose; 00081 unsigned int id; 00082 00083 }; 00084 00088 class ScanEdge { 00089 00090 public: 00091 00092 ScanEdge(ScanNode* _first, ScanNode* _second, pose6d _constraint) 00093 : first(_first), second(_second), constraint(_constraint), weight(1.0) { } 00094 ScanEdge() {} 00095 00096 bool operator == (const ScanEdge& other) { 00097 return ( (*first == *(other.first) ) && ( *second == *(other.second) ) ); 00098 } 00099 00100 std::ostream& writeBinary(std::ostream &s) const; 00101 // a graph has to be given to recover ScanNode pointers 00102 std::istream& readBinary(std::istream &s, ScanGraph& graph); 00103 00104 std::ostream& writeASCII(std::ostream &s) const; 00105 std::istream& readASCII(std::istream &s, ScanGraph& graph); 00106 00107 ScanNode* first; 00108 ScanNode* second; 00109 00110 pose6d constraint; 00111 double weight; 00112 }; 00113 00114 00120 class ScanGraph { 00121 00122 public: 00123 00124 ScanGraph() {}; 00125 ~ScanGraph(); 00126 00128 void clear(); 00129 00138 ScanNode* addNode(Pointcloud* scan, pose6d pose); 00139 00149 ScanEdge* addEdge(ScanNode* first, ScanNode* second, pose6d constraint); 00150 00151 ScanEdge* addEdge(unsigned int first_id, unsigned int second_id); 00152 00154 ScanNode* getNodeByID(unsigned int id); 00155 00157 bool edgeExists(unsigned int first_id, unsigned int second_id); 00158 00160 void connectPrevious(); 00161 00162 std::vector<unsigned int> getNeighborIDs(unsigned int id); 00163 std::vector<ScanEdge*> getOutEdges(ScanNode* node); 00164 // warning: constraints are reversed 00165 std::vector<ScanEdge*> getInEdges(ScanNode* node); 00166 00167 void exportDot(std::string filename); 00168 00170 void transformScans(); 00171 00173 void crop(point3d lowerBound, point3d upperBound); 00174 00176 void cropEachScan(point3d lowerBound, point3d upperBound); 00177 00178 00179 typedef std::vector<ScanNode*>::iterator iterator; 00180 typedef std::vector<ScanNode*>::const_iterator const_iterator; 00181 iterator begin() { return nodes.begin(); } 00182 iterator end() { return nodes.end(); } 00183 const_iterator begin() const { return nodes.begin(); } 00184 const_iterator end() const { return nodes.end(); } 00185 00186 unsigned int size() const { return nodes.size(); } 00187 unsigned int getNumPoints(unsigned int max_id = -1) const; 00188 00189 typedef std::vector<ScanEdge*>::iterator edge_iterator; 00190 typedef std::vector<ScanEdge*>::const_iterator const_edge_iterator; 00191 edge_iterator edges_begin() { return edges.begin(); } 00192 edge_iterator edges_end() { return edges.end(); } 00193 const_edge_iterator edges_begin() const { return edges.begin(); } 00194 const_edge_iterator edges_end() const { return edges.end(); } 00195 00196 00197 std::ostream& writeBinary(std::ostream &s) const; 00198 std::istream& readBinary(std::ifstream &s); 00199 bool writeBinary(const std::string& filename) const; 00200 bool readBinary(const std::string& filename); 00201 00202 00203 std::ostream& writeEdgesASCII(std::ostream &s) const; 00204 std::istream& readEdgesASCII(std::istream &s); 00205 00206 std::ostream& writeNodePosesASCII(std::ostream &s) const; 00207 std::istream& readNodePosesASCII(std::istream &s); 00208 00225 std::istream& readPlainASCII(std::istream& s); 00226 void readPlainASCII(const std::string& filename); 00227 00228 protected: 00229 00230 std::vector<ScanNode*> nodes; 00231 std::vector<ScanEdge*> edges; 00232 }; 00233 00234 } 00235 00236 00237 #endif