Lightweight 3D point (float version).
Definition at line 224 of file lightweight_geom_data.h.
#include <mrpt/math/lightweight_geom_data.h>
Public Types | |
enum | { static_size = 3 } |
Public Member Functions | |
TPoint3Df () | |
TPoint3Df (const float xx, const float yy, const float zz) | |
TPoint3Df & | operator+= (const TPoint3Df &p) |
TPoint3Df | operator* (const float s) |
float & | operator[] (size_t i) |
Coordinate access using operator[]. More... | |
const float & | operator[] (size_t i) const |
Coordinate access using operator[]. More... | |
Public Attributes | |
float | x |
float | y |
float | z |
anonymous enum |
Enumerator | |
---|---|
static_size |
Definition at line 226 of file lightweight_geom_data.h.
|
inline |
Definition at line 231 of file lightweight_geom_data.h.
|
inline |
Definition at line 232 of file lightweight_geom_data.h.
|
inline |
Definition at line 234 of file lightweight_geom_data.h.
Definition at line 233 of file lightweight_geom_data.h.
|
inline |
Coordinate access using operator[].
Order: x,y,z
Definition at line 236 of file lightweight_geom_data.h.
|
inline |
Coordinate access using operator[].
Order: x,y,z
Definition at line 239 of file lightweight_geom_data.h.
float mrpt::math::TPoint3Df::x |
Definition at line 227 of file lightweight_geom_data.h.
Referenced by mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::getCornerX(), mrpt::opengl::gl_utils::getCurrentRenderingInfo(), mrpt::maps::CPointsMap::insertAnotherMap(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::opengl::CPointCloud::PLY_export_get_vertex(), mrpt::opengl::CPointCloudColoured::PLY_export_get_vertex(), mrpt::maps::CColouredPointsMap::PLY_export_get_vertex(), mrpt::maps::CPointsMap::PLY_export_get_vertex(), mrpt::opengl::CPointCloud::PLY_import_set_vertex(), mrpt::opengl::CPointCloudColoured::PLY_import_set_vertex(), mrpt::maps::CColouredPointsMap::PLY_import_set_vertex(), mrpt::maps::CPointsMap::PLY_import_set_vertex(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), mrpt::utils::PLY_Exporter::saveToPlyFile(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::setBBFromOrderInParent(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), and velodyne_scan_to_pointcloud().
float mrpt::math::TPoint3Df::y |
Definition at line 228 of file lightweight_geom_data.h.
Referenced by mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::getCornerY(), mrpt::opengl::gl_utils::getCurrentRenderingInfo(), mrpt::maps::CPointsMap::insertAnotherMap(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::opengl::CPointCloud::PLY_export_get_vertex(), mrpt::opengl::CPointCloudColoured::PLY_export_get_vertex(), mrpt::maps::CColouredPointsMap::PLY_export_get_vertex(), mrpt::maps::CPointsMap::PLY_export_get_vertex(), mrpt::opengl::CPointCloud::PLY_import_set_vertex(), mrpt::opengl::CPointCloudColoured::PLY_import_set_vertex(), mrpt::maps::CColouredPointsMap::PLY_import_set_vertex(), mrpt::maps::CPointsMap::PLY_import_set_vertex(), mrpt::opengl::CFrustum::render_dl(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), mrpt::utils::PLY_Exporter::saveToPlyFile(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::setBBFromOrderInParent(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), and velodyne_scan_to_pointcloud().
float mrpt::math::TPoint3Df::z |
Definition at line 229 of file lightweight_geom_data.h.
Referenced by mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::getCornerZ(), mrpt::opengl::gl_utils::getCurrentRenderingInfo(), mrpt::maps::CPointsMap::insertAnotherMap(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::opengl::CPointCloud::PLY_export_get_vertex(), mrpt::opengl::CPointCloudColoured::PLY_export_get_vertex(), mrpt::maps::CColouredPointsMap::PLY_export_get_vertex(), mrpt::maps::CPointsMap::PLY_export_get_vertex(), mrpt::opengl::CPointCloud::PLY_import_set_vertex(), mrpt::opengl::CPointCloudColoured::PLY_import_set_vertex(), mrpt::maps::CColouredPointsMap::PLY_import_set_vertex(), mrpt::maps::CPointsMap::PLY_import_set_vertex(), mrpt::opengl::CFrustum::render_dl(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), mrpt::utils::PLY_Exporter::saveToPlyFile(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::setBBFromOrderInParent(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), and velodyne_scan_to_pointcloud().
Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019 |