A collection of 3D coordinates (point3d), which are regarded as endpoints of a 3D laser scan.
Definition at line 63 of file Pointcloud.h.
#include <mrpt/otherlibs/octomap/Pointcloud.h>
Public Types | |
| typedef point3d_collection::iterator | iterator |
| typedef point3d_collection::const_iterator | const_iterator |
Public Member Functions | |
| Pointcloud () | |
| ~Pointcloud () | |
| Pointcloud (const Pointcloud &other) | |
| Pointcloud (Pointcloud *other) | |
| size_t | size () const |
| void | clear () |
| void | reserve (size_t size) |
| void | push_back (float x, float y, float z) |
| void | push_back (const point3d &p) |
| void | push_back (point3d *p) |
| void | push_back (const Pointcloud &other) |
| Add points from other Pointcloud. More... | |
| void | writeVrml (std::string filename) |
| Export the Pointcloud to a VRML file. More... | |
| void | transform (pose6d transform) |
| Apply transform to each point. More... | |
| void | rotate (double roll, double pitch, double yaw) |
| Rotate each point in pointcloud. More... | |
| void | transformAbsolute (pose6d transform) |
| Apply transform to each point, undo previous transforms. More... | |
| void | calcBBX (point3d &lowerBound, point3d &upperBound) const |
| Calculate bounding box of Pointcloud. More... | |
| void | crop (point3d lowerBound, point3d upperBound) |
| Crop Pointcloud to given bounding box. More... | |
| void | minDist (double thres) |
| void | subSampleRandom (unsigned int num_samples, Pointcloud &sample_cloud) |
| iterator | begin () |
| iterator | end () |
| const_iterator | begin () const |
| const_iterator | end () const |
| point3d | back () |
| point3d | getPoint (unsigned int i) |
| std::istream & | readBinary (std::istream &s) |
| std::istream & | read (std::istream &s) |
| std::ostream & | writeBinary (std::ostream &s) const |
Protected Attributes | |
| pose6d | current_inv_transform |
| point3d_collection | points |
| typedef point3d_collection::const_iterator octomap::Pointcloud::const_iterator |
Definition at line 115 of file Pointcloud.h.
| typedef point3d_collection::iterator octomap::Pointcloud::iterator |
Definition at line 114 of file Pointcloud.h.
| octomap::Pointcloud::Pointcloud | ( | ) |
| octomap::Pointcloud::~Pointcloud | ( | ) |
| octomap::Pointcloud::Pointcloud | ( | const Pointcloud & | other | ) |
| octomap::Pointcloud::Pointcloud | ( | Pointcloud * | other | ) |
|
inline |
Definition at line 120 of file Pointcloud.h.
References points.
|
inline |
Definition at line 116 of file Pointcloud.h.
References points.
|
inline |
Definition at line 118 of file Pointcloud.h.
References points.
Calculate bounding box of Pointcloud.
| void octomap::Pointcloud::clear | ( | ) |
Crop Pointcloud to given bounding box.
|
inline |
Definition at line 117 of file Pointcloud.h.
References points.
|
inline |
Definition at line 119 of file Pointcloud.h.
References points.
| point3d octomap::Pointcloud::getPoint | ( | unsigned int | i | ) |
| void octomap::Pointcloud::minDist | ( | double | thres | ) |
|
inline |
Definition at line 77 of file Pointcloud.h.
References points.
Referenced by mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::internal_build_PointCloud_for_observation().
|
inline |
Definition at line 80 of file Pointcloud.h.
References points.
|
inline |
Definition at line 83 of file Pointcloud.h.
References points.
| void octomap::Pointcloud::push_back | ( | const Pointcloud & | other | ) |
Add points from other Pointcloud.
| std::istream& octomap::Pointcloud::read | ( | std::istream & | s | ) |
| std::istream& octomap::Pointcloud::readBinary | ( | std::istream & | s | ) |
|
inline |
Definition at line 75 of file Pointcloud.h.
References points.
Referenced by mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::internal_build_PointCloud_for_observation().
| void octomap::Pointcloud::rotate | ( | double | roll, |
| double | pitch, | ||
| double | yaw | ||
| ) |
Rotate each point in pointcloud.
|
inline |
Definition at line 73 of file Pointcloud.h.
References points.
Referenced by mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::internal_computeObservationLikelihood().
| void octomap::Pointcloud::subSampleRandom | ( | unsigned int | num_samples, |
| Pointcloud & | sample_cloud | ||
| ) |
| void octomap::Pointcloud::transform | ( | pose6d | transform | ) |
Apply transform to each point.
| void octomap::Pointcloud::transformAbsolute | ( | pose6d | transform | ) |
Apply transform to each point, undo previous transforms.
| std::ostream& octomap::Pointcloud::writeBinary | ( | std::ostream & | s | ) | const |
| void octomap::Pointcloud::writeVrml | ( | std::string | filename | ) |
Export the Pointcloud to a VRML file.
|
protected |
Definition at line 130 of file Pointcloud.h.
|
protected |
Definition at line 131 of file Pointcloud.h.
Referenced by back(), begin(), end(), push_back(), reserve(), and size().
| Page generated by Doxygen 1.8.9.1 for MRPT 1.3.2 SVN:Unversioned directory at Thu Dec 10 00:07:55 UTC 2015 |