Pointcloud.h
Go to the documentation of this file.
00001 /*
00002  * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
00003  * http://octomap.github.com/
00004  *
00005  * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg
00006  * All rights reserved.
00007  * License: New BSD
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions are met:
00011  *
00012  *     * Redistributions of source code must retain the above copyright
00013  *       notice, this list of conditions and the following disclaimer.
00014  *     * Redistributions in binary form must reproduce the above copyright
00015  *       notice, this list of conditions and the following disclaimer in the
00016  *       documentation and/or other materials provided with the distribution.
00017  *     * Neither the name of the University of Freiburg nor the names of its
00018  *       contributors may be used to endorse or promote products derived from
00019  *       this software without specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00023  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00024  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00025  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00026  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00027  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00028  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00029  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00030  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  * POSSIBILITY OF SUCH DAMAGE.
00032  */
00033 
00034 #ifndef OCTOMAP_POINTCLOUD_H
00035 #define OCTOMAP_POINTCLOUD_H
00036 
00037 #include <vector>
00038 #include <list>
00039 #include <octomap/octomap_types.h>
00040 
00041 namespace octomap {
00042 
00047   class Pointcloud {
00048 
00049   public:
00050 
00051     Pointcloud();
00052     ~Pointcloud();
00053 
00054     Pointcloud(const Pointcloud& other);
00055     Pointcloud(Pointcloud* other);
00056 
00057     size_t size() const {  return points.size(); }
00058     void clear();
00059     inline void reserve(size_t size) {points.reserve(size); }
00060 
00061     inline void push_back(float x, float y, float z) {
00062       points.push_back(point3d(x,y,z));
00063     }
00064     inline void push_back(const point3d& p) {
00065       points.push_back(p);
00066     }
00067     inline void push_back(point3d* p) {
00068        points.push_back(*p);
00069     }
00070 
00072     void push_back(const Pointcloud& other);
00073 
00075     void writeVrml(std::string filename);
00076 
00078     void transform(pose6d transform);
00079 
00081     void rotate(double roll, double pitch, double yaw);
00082 
00084     void transformAbsolute(pose6d transform);
00085 
00087     void calcBBX(point3d& lowerBound, point3d& upperBound) const;
00089     void crop(point3d lowerBound, point3d upperBound);
00090 
00091     // removes any points closer than [thres] to (0,0,0)
00092     void minDist(double thres);
00093 
00094     void subSampleRandom(unsigned int num_samples, Pointcloud& sample_cloud);
00095 
00096     // iterators ------------------
00097 
00098     typedef point3d_collection::iterator iterator;
00099     typedef point3d_collection::const_iterator const_iterator;
00100     iterator begin() { return points.begin(); }
00101     iterator end()   { return points.end(); }
00102     const_iterator begin() const { return points.begin(); }
00103     const_iterator end() const  { return points.end(); }
00104     point3d back()  { return points.back(); }
00107     point3d getPoint(unsigned int i) const;   // may return NULL
00108 
00109     inline const point3d& operator[] (size_t i) const { return points[i]; }
00110     inline point3d& operator[] (size_t i) { return points[i]; }
00111 
00112     // I/O methods
00113 
00114     std::istream& readBinary(std::istream &s);
00115     std::istream& read(std::istream &s);
00116     std::ostream& writeBinary(std::ostream &s) const;
00117 
00118   protected:
00119     pose6d               current_inv_transform;
00120     point3d_collection   points;
00121   };
00122 
00123 }
00124 
00125 
00126 #endif


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Feb 11 2016 23:50:59