34#ifndef OCTOMAP_POINTCLOUD_H
35#define OCTOMAP_POINTCLOUD_H
81 void rotate(
double roll,
double pitch,
double yaw);
115 std::istream&
read(std::istream &s);
A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan.
Definition: Pointcloud.h:47
std::istream & readBinary(std::istream &s)
Definition: Pointcloud.cpp:296
Pointcloud()
Definition: Pointcloud.cpp:57
const_iterator end() const
Definition: Pointcloud.h:103
iterator begin()
Definition: Pointcloud.h:100
void calcBBX(point3d &lowerBound, point3d &upperBound) const
Calculate bounding box of Pointcloud.
Definition: Pointcloud.cpp:134
void rotate(double roll, double pitch, double yaw)
Rotate each point in pointcloud.
Definition: Pointcloud.cpp:126
point3d_collection::const_iterator const_iterator
Definition: Pointcloud.h:99
size_t size() const
Definition: Pointcloud.h:57
const point3d & operator[](size_t i) const
Definition: Pointcloud.h:109
void transformAbsolute(pose6d transform)
Apply transform to each point, undo previous transforms.
Definition: Pointcloud.cpp:113
void reserve(size_t size)
Definition: Pointcloud.h:59
point3d_collection points
Definition: Pointcloud.h:120
void push_back(float x, float y, float z)
Definition: Pointcloud.h:61
point3d_collection::iterator iterator
Definition: Pointcloud.h:98
const_iterator begin() const
Definition: Pointcloud.h:102
void push_back(point3d *p)
Definition: Pointcloud.h:67
void subSampleRandom(unsigned int num_samples, Pointcloud &sample_cloud)
Definition: Pointcloud.cpp:210
void push_back(const point3d &p)
Definition: Pointcloud.h:64
void crop(point3d lowerBound, point3d upperBound)
Crop Pointcloud to given bounding box.
Definition: Pointcloud.cpp:162
iterator end()
Definition: Pointcloud.h:101
void writeVrml(std::string filename)
Export the Pointcloud to a VRML file.
Definition: Pointcloud.cpp:233
point3d back()
Definition: Pointcloud.h:104
pose6d current_inv_transform
Definition: Pointcloud.h:119
point3d getPoint(unsigned int i) const
Returns a copy of the ith point in point cloud. Use operator[] for direct access to point reference.
Definition: Pointcloud.cpp:93
void minDist(double thres)
Definition: Pointcloud.cpp:194
std::istream & read(std::istream &s)
Definition: Pointcloud.cpp:280
void clear()
Definition: Pointcloud.cpp:65
void transform(pose6d transform)
Apply transform to each point.
Definition: Pointcloud.cpp:102
~Pointcloud()
Definition: Pointcloud.cpp:61
std::ostream & writeBinary(std::ostream &s) const
Definition: Pointcloud.cpp:324
This class represents a tree-dimensional pose of an object.
Definition: Pose6D.h:49
This class represents a three-dimensional vector.
Definition: Vector3.h:50
Namespace the OctoMap library and visualization tools.
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
Definition: octomap_types.h:49
std::vector< octomath::Vector3 > point3d_collection
Definition: octomap_types.h:53