Pointcloud.h
Go to the documentation of this file.
1 /*
2  * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
3  * https://octomap.github.io/
4  *
5  * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg
6  * All rights reserved.
7  * License: New BSD
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above copyright
15  * notice, this list of conditions and the following disclaimer in the
16  * documentation and/or other materials provided with the distribution.
17  * * Neither the name of the University of Freiburg nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #ifndef OCTOMAP_POINTCLOUD_H
35 #define OCTOMAP_POINTCLOUD_H
36 
37 #include <vector>
38 #include <list>
39 #include <octomap/octomap_types.h>
40 
41 namespace octomap {
42 
47  class Pointcloud {
48 
49  public:
50 
51  Pointcloud();
52  ~Pointcloud();
53 
54  Pointcloud(const Pointcloud& other);
55  Pointcloud(Pointcloud* other);
56 
57  size_t size() const { return points.size(); }
58  void clear();
59  inline void reserve(size_t size) {points.reserve(size); }
60 
61  inline void push_back(float x, float y, float z) {
62  points.push_back(point3d(x,y,z));
63  }
64  inline void push_back(const point3d& p) {
65  points.push_back(p);
66  }
67  inline void push_back(point3d* p) {
68  points.push_back(*p);
69  }
70 
72  void push_back(const Pointcloud& other);
73 
75  void writeVrml(std::string filename);
76 
79 
81  void rotate(double roll, double pitch, double yaw);
82 
85 
87  void calcBBX(point3d& lowerBound, point3d& upperBound) const;
89  void crop(point3d lowerBound, point3d upperBound);
90 
91  // removes any points closer than [thres] to (0,0,0)
92  void minDist(double thres);
93 
94  void subSampleRandom(unsigned int num_samples, Pointcloud& sample_cloud);
95 
96  // iterators ------------------
97 
98  typedef point3d_collection::iterator iterator;
99  typedef point3d_collection::const_iterator const_iterator;
100  iterator begin() { return points.begin(); }
101  iterator end() { return points.end(); }
102  const_iterator begin() const { return points.begin(); }
103  const_iterator end() const { return points.end(); }
104  point3d back() { return points.back(); }
107  point3d getPoint(unsigned int i) const; // may return NULL
108 
109  inline const point3d& operator[] (size_t i) const { return points[i]; }
110  inline point3d& operator[] (size_t i) { return points[i]; }
111 
112  // I/O methods
113 
114  std::istream& readBinary(std::istream &s);
115  std::istream& read(std::istream &s);
116  std::ostream& writeBinary(std::ostream &s) const;
117 
118  protected:
121  };
122 
123 }
124 
125 
126 #endif
octomap::Pointcloud::push_back
void push_back(const point3d &p)
Definition: Pointcloud.h:64
octomap::Pointcloud::points
point3d_collection points
Definition: Pointcloud.h:120
octomap::Pointcloud::readBinary
std::istream & readBinary(std::istream &s)
Definition: Pointcloud.cpp:296
octomap::Pointcloud
Definition: Pointcloud.h:47
octomap::Pointcloud::calcBBX
void calcBBX(point3d &lowerBound, point3d &upperBound) const
Calculate bounding box of Pointcloud.
Definition: Pointcloud.cpp:134
octomap::Pointcloud::crop
void crop(point3d lowerBound, point3d upperBound)
Crop Pointcloud to given bounding box.
Definition: Pointcloud.cpp:162
octomap::Pointcloud::push_back
void push_back(float x, float y, float z)
Definition: Pointcloud.h:61
octomap::Pointcloud::reserve
void reserve(size_t size)
Definition: Pointcloud.h:59
octomap::Pointcloud::getPoint
point3d getPoint(unsigned int i) const
Definition: Pointcloud.cpp:93
octomap::Pointcloud::clear
void clear()
Definition: Pointcloud.cpp:65
octomap::Pointcloud::back
point3d back()
Definition: Pointcloud.h:104
octomap::Pointcloud::~Pointcloud
~Pointcloud()
Definition: Pointcloud.cpp:61
octomath::Vector3
This class represents a three-dimensional vector.
Definition: Vector3.h:50
octomap::Pointcloud::subSampleRandom
void subSampleRandom(unsigned int num_samples, Pointcloud &sample_cloud)
Definition: Pointcloud.cpp:210
octomap::Pointcloud::writeBinary
std::ostream & writeBinary(std::ostream &s) const
Definition: Pointcloud.cpp:324
octomap::Pointcloud::begin
const_iterator begin() const
Definition: Pointcloud.h:102
octomap::Pointcloud::writeVrml
void writeVrml(std::string filename)
Export the Pointcloud to a VRML file.
Definition: Pointcloud.cpp:233
octomap::Pointcloud::push_back
void push_back(point3d *p)
Definition: Pointcloud.h:67
octomap::Pointcloud::operator[]
const point3d & operator[](size_t i) const
Definition: Pointcloud.h:109
octomap::Pointcloud::rotate
void rotate(double roll, double pitch, double yaw)
Rotate each point in pointcloud.
Definition: Pointcloud.cpp:126
octomap::Pointcloud::current_inv_transform
pose6d current_inv_transform
Definition: Pointcloud.h:119
octomap::Pointcloud::read
std::istream & read(std::istream &s)
Definition: Pointcloud.cpp:280
octomap::Pointcloud::transform
void transform(pose6d transform)
Apply transform to each point.
Definition: Pointcloud.cpp:102
octomap_types.h
octomap::point3d_collection
std::vector< octomath::Vector3 > point3d_collection
Definition: octomap_types.h:53
octomap::Pointcloud::minDist
void minDist(double thres)
Definition: Pointcloud.cpp:194
octomap::Pointcloud::Pointcloud
Pointcloud()
Definition: Pointcloud.cpp:57
octomap::Pointcloud::begin
iterator begin()
Definition: Pointcloud.h:100
octomap::Pointcloud::end
const_iterator end() const
Definition: Pointcloud.h:103
octomap::Pointcloud::const_iterator
point3d_collection::const_iterator const_iterator
Definition: Pointcloud.h:99
octomap
octomath::Pose6D
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
octomap::Pointcloud::transformAbsolute
void transformAbsolute(pose6d transform)
Apply transform to each point, undo previous transforms.
Definition: Pointcloud.cpp:113
octomap::point3d
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
Definition: octomap_types.h:49
octomap::Pointcloud::iterator
point3d_collection::iterator iterator
Definition: Pointcloud.h:98
octomap::Pointcloud::size
size_t size() const
Definition: Pointcloud.h:57
octomap::Pointcloud::end
iterator end()
Definition: Pointcloud.h:101


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Tue Dec 12 2023 03:39:40