Lightweight 3D point (float version).
Definition at line 315 of file lightweight_geom_data.h.
#include <mrpt/math/lightweight_geom_data.h>
Public Types | |
enum | { static_size = 3 } |
Public Member Functions | |
TPoint3Df () | |
constexpr | 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... | |
constexpr 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 317 of file lightweight_geom_data.h.
|
inline |
Definition at line 325 of file lightweight_geom_data.h.
Referenced by operator*().
|
inlineconstexpr |
Definition at line 326 of file lightweight_geom_data.h.
|
inline |
Definition at line 337 of file lightweight_geom_data.h.
References TPoint3Df().
Definition at line 330 of file lightweight_geom_data.h.
References x.
|
inline |
Coordinate access using operator[].
Order: x,y,z
Definition at line 342 of file lightweight_geom_data.h.
|
inlineconstexpr |
Coordinate access using operator[].
Order: x,y,z
Definition at line 358 of file lightweight_geom_data.h.
float mrpt::math::TPoint3Df::x |
Definition at line 321 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(), operator+=(), operator[](), 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::opengl::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 322 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(), operator[](), 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::opengl::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 323 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(), operator[](), 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::opengl::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.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST |