octomap 1.5.0
|
00001 // $Id: Pointcloud.h 205 2011-06-10 11:58:40Z ahornung $ 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_POINTCLOUD_H 00041 #define OCTOMAP_POINTCLOUD_H 00042 00043 #include <vector> 00044 #include <list> 00045 #include <octomap/octomap_types.h> 00046 00047 namespace octomap { 00048 00053 class Pointcloud { 00054 00055 public: 00056 00057 Pointcloud(); 00058 ~Pointcloud(); 00059 00060 Pointcloud(const Pointcloud& other); 00061 Pointcloud(Pointcloud* other); 00062 00063 size_t size() const { return points.size(); } 00064 void clear(); 00065 inline void reserve(size_t size) {points.reserve(size); } 00066 00067 inline void push_back(float x, float y, float z) { 00068 points.push_back(point3d(x,y,z)); 00069 } 00070 inline void push_back(const point3d& p) { 00071 points.push_back(p); 00072 } 00073 inline void push_back(point3d* p) { 00074 points.push_back(*p); 00075 } 00076 00078 void push_back(const Pointcloud& other); 00079 00081 void writeVrml(std::string filename); 00082 00084 void transform(pose6d transform); 00085 00087 void rotate(double roll, double pitch, double yaw); 00088 00090 void transformAbsolute(pose6d transform); 00091 00093 void calcBBX(point3d& lowerBound, point3d& upperBound) const; 00095 void crop(point3d lowerBound, point3d upperBound); 00096 00097 // removes any points closer than [thres] to (0,0,0) 00098 void minDist(double thres); 00099 00100 void subSampleRandom(unsigned int num_samples, Pointcloud& sample_cloud); 00101 00102 // iterators ------------------ 00103 00104 typedef point3d_collection::iterator iterator; 00105 typedef point3d_collection::const_iterator const_iterator; 00106 iterator begin() { return points.begin(); } 00107 iterator end() { return points.end(); } 00108 const_iterator begin() const { return points.begin(); } 00109 const_iterator end() const { return points.end(); } 00110 point3d back() { return points.back(); } 00111 point3d getPoint(unsigned int i); // may return NULL 00112 00113 // I/O methods 00114 00115 std::istream& readBinary(std::istream &s); 00116 std::istream& read(std::istream &s); 00117 std::ostream& writeBinary(std::ostream &s) const; 00118 00119 protected: 00120 pose6d current_inv_transform; 00121 point3d_collection points; 00122 }; 00123 00124 } 00125 00126 00127 #endif