Lightweight 3D point.
Allows coordinate access using [] operator.
Definition at line 381 of file lightweight_geom_data.h.
#include <mrpt/math/lightweight_geom_data.h>
Public Types | |
enum | { static_size = 3 } |
Public Member Functions | |
TPoint3D (double xx, double yy, double zz) | |
Constructor from coordinates. More... | |
TPoint3D () | |
Default fast constructor. More... | |
TPoint3D (const TPoint3Df &p) | |
Explicit constructor from coordinates. More... | |
TPoint3D (const TPoint2D &p) | |
Implicit constructor from TPoint2D. More... | |
TPoint3D (const TPose2D &p) | |
Constructor from TPose2D, losing information. More... | |
TPoint3D (const TPose3D &p) | |
Constructor from TPose3D, losing information. More... | |
TPoint3D (const mrpt::poses::CPoint3D &p) | |
Implicit constructor from heavyweight type. More... | |
TPoint3D (const mrpt::poses::CPose3D &p) | |
Constructor from heavyweight 3D pose. More... | |
double & | operator[] (size_t i) |
Coordinate access using operator[]. More... | |
const double & | operator[] (size_t i) const |
Coordinate access using operator[]. More... | |
double | distanceTo (const TPoint3D &p) const |
Point-to-point distance. More... | |
double | sqrDistanceTo (const TPoint3D &p) const |
Point-to-point distance, squared. More... | |
double | norm () const |
Point norm. More... | |
TPoint3D & | operator*= (const double f) |
Point scale. More... | |
template<class VECTORLIKE > | |
void | getAsVector (VECTORLIKE &v) const |
Transformation into vector. More... | |
TPoint3D & | operator+= (const TPoint3D &p) |
Translation. More... | |
TPoint3D & | operator-= (const TPoint3D &p) |
Difference between points. More... | |
TPoint3D | operator+ (const TPoint3D &p) const |
Points addition. More... | |
TPoint3D | operator- (const TPoint3D &p) const |
Points substraction. More... | |
TPoint3D | operator* (double d) const |
TPoint3D | operator/ (double d) const |
bool | operator< (const TPoint3D &p) const |
void | asString (std::string &s) const |
Returns a human-readable textual representation of the object (eg: "[0.02 1.04 -0.8]" ) More... | |
std::string | asString () const |
void | fromString (const std::string &s) |
Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -0.8]" ) More... | |
Static Public Member Functions | |
static size_t | size () |
Public Attributes | |
double | x |
X,Y,Z coordinates. More... | |
double | y |
double | z |
anonymous enum |
Enumerator | |
---|---|
static_size |
Definition at line 383 of file lightweight_geom_data.h.
|
inline |
Constructor from coordinates.
Definition at line 391 of file lightweight_geom_data.h.
|
inline |
Default fast constructor.
Initializes to garbage.
Definition at line 393 of file lightweight_geom_data.h.
Referenced by operator*(), operator+(), operator-(), and operator/().
|
inlineexplicit |
Explicit constructor from coordinates.
Definition at line 395 of file lightweight_geom_data.h.
mrpt::math::TPoint3D::TPoint3D | ( | const TPoint2D & | p | ) |
Implicit constructor from TPoint2D.
Zeroes the z.
Definition at line 197 of file lightweight_geom_data.cpp.
|
explicit |
Constructor from TPose2D, losing information.
Zeroes the z.
Definition at line 198 of file lightweight_geom_data.cpp.
|
explicit |
Constructor from TPose3D, losing information.
Definition at line 199 of file lightweight_geom_data.cpp.
mrpt::math::TPoint3D::TPoint3D | ( | const mrpt::poses::CPoint3D & | p | ) |
Implicit constructor from heavyweight type.
Definition at line 200 of file lightweight_geom_data.cpp.
|
explicit |
Constructor from heavyweight 3D pose.
Definition at line 204 of file lightweight_geom_data.cpp.
|
inline |
Returns a human-readable textual representation of the object (eg: "[0.02 1.04 -0.8]" )
Definition at line 543 of file lightweight_geom_data.h.
References mrpt::mrpt::format().
|
inline |
Definition at line 547 of file lightweight_geom_data.h.
|
inline |
Point-to-point distance.
Definition at line 453 of file lightweight_geom_data.h.
References mrpt::math::square().
Referenced by mrpt::detectors::CFaceDetection::checkIfDiagonalSurface(), mrpt::detectors::CFaceDetection::checkIfDiagonalSurface2(), mrpt::detectors::CFaceDetection::checkIfFaceRegions(), and mrpt::topography::path_from_rtk_gps().
void mrpt::math::TPoint3D::fromString | ( | const std::string & | s | ) |
Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -0.8]" )
std::exception | On invalid format |
Definition at line 220 of file lightweight_geom_data.cpp.
References ASSERTMSG_, mrpt::mrpt::math::size(), and THROW_EXCEPTION.
|
inline |
Transformation into vector.
Definition at line 485 of file lightweight_geom_data.h.
Referenced by mrpt::math::TSegment3D::distance().
|
inline |
Point norm.
Definition at line 467 of file lightweight_geom_data.h.
References mrpt::math::square().
Referenced by mrpt::vision::computeMsd(), mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), and mrpt::vision::projectMatchedFeatures().
|
inline |
Definition at line 527 of file lightweight_geom_data.h.
References TPoint3D().
|
inline |
Point scale.
Definition at line 474 of file lightweight_geom_data.h.
Points addition.
Definition at line 515 of file lightweight_geom_data.h.
References TPoint3D().
Points substraction.
Definition at line 522 of file lightweight_geom_data.h.
References TPoint3D().
|
inline |
Definition at line 532 of file lightweight_geom_data.h.
References TPoint3D().
bool mrpt::math::TPoint3D::operator< | ( | const TPoint3D & | p | ) | const |
Definition at line 207 of file lightweight_geom_data.cpp.
|
inline |
Coordinate access using operator[].
Order: x,y,z
Definition at line 421 of file lightweight_geom_data.h.
|
inline |
Coordinate access using operator[].
Order: x,y,z
Definition at line 436 of file lightweight_geom_data.h.
|
inlinestatic |
Definition at line 560 of file lightweight_geom_data.h.
Referenced by mrpt::math::TPolygon3D::TPolygon3D().
|
inline |
Point-to-point distance, squared.
Definition at line 460 of file lightweight_geom_data.h.
References mrpt::math::square().
Referenced by mrpt::topography::path_from_rtk_gps().
double mrpt::math::TPoint3D::x |
X,Y,Z coordinates.
Definition at line 388 of file lightweight_geom_data.h.
Referenced by mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::castRay(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::detectors::CFaceDetection::checkIfFaceRegions(), mrpt::detectors::CFaceDetection::checkRelativePosition(), mrpt::poses::CPose2D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::maps::CLandmarksMap::computeLikelihood_RSLC_2007(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::math::conformAPlane(), mrpt::math::TLine3D::contains(), mrpt::math::TPolygon3D::contains(), mrpt::obs::detail::cost_func(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::distance(), mrpt::math::TLine3D::distance(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::vision::frameJac(), mrpt::maps::CPointsMap::fuseWith(), mrpt::topography::geocentricToENU_WGS84(), mrpt::topography::geocentricToGeodetic(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::geodeticToUTM(), mrpt::topography::GeodeticToUTM(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::maps::COctoMap::getAsOctoMapVoxels(), mrpt::maps::CColouredOctoMap::getAsOctoMapVoxels(), getAsVector(), mrpt::opengl::COpenGLStandardObject::getBoundingBox(), mrpt::opengl::CText::getBoundingBox(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::opengl::CDisk::getBoundingBox(), mrpt::opengl::CAxis::getBoundingBox(), mrpt::opengl::CColorBar::getBoundingBox(), mrpt::opengl::CSphere::getBoundingBox(), mrpt::opengl::CSimpleLine::getBoundingBox(), mrpt::opengl::CTexturedPlane::getBoundingBox(), mrpt::opengl::CArrow::getBoundingBox(), mrpt::opengl::CGridPlaneXY::getBoundingBox(), mrpt::opengl::CText3D::getBoundingBox(), mrpt::opengl::CGridPlaneXZ::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CPolyhedron::getBoundingBox(), mrpt::opengl::CCylinder::getBoundingBox(), mrpt::opengl::CMesh3D::getBoundingBox(), mrpt::opengl::CMeshFast::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CMesh::getBoundingBox(), mrpt::opengl::CVectorField2D::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::opengl::CVectorField3D::getBoundingBox(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CLandmark::getPose(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), IMPLEMENTS_SERIALIZABLE(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), insertRotunda(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::poses::CPose3D::inverseComposePoint(), jacob_dh_db_and_dh_dc(), mrpt::vision::CCamModel::jacobian_project_with_distortion(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::math::operator!=(), operator+=(), mrpt::math::operator-(), operator-=(), mrpt::math::operator<<(), mrpt::math::operator==(), mrpt::math::operator>>(), operator[](), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pointJac(), mrpt::math::project3D(), mrpt::vision::CCamModel::project_3D_point(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoint_with_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::push_back(), mrpt::opengl::CBox::readFromStream(), mrpt::vision::recompute_errors_and_Jacobians(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CColorBar::render_dl(), mrpt::opengl::CBox::render_dl(), mrpt::opengl::COctoMapVoxels::render_dl(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), se3_l2_internal(), mrpt::opengl::CBox::setBoxCorners(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CLandmark::setPose(), mrpt::poses::CPose3DRotVec::sphericalCoordinates(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), TEST(), Pose3DQuatTests::test_composeAndInvComposePoint(), Pose3DQuatTests::test_composePoint_vs_CPose3D(), Pose3DQuatTests::test_composePointJacob(), Pose3DTests::test_composePointJacob(), Pose3DTests::test_composePointJacob_se3(), Pose3DQuatTests::test_invComposePoint_vs_CPose3D(), Pose3DQuatTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob_se3(), mrpt::math::TLine2D::TLine2D(), mrpt::math::TLine3D::TLine3D(), mrpt::math::TPlane::TPlane(), mrpt::opengl::CCylinder::traceRay(), mrpt::topography::transfInterpolation(), mrpt::topography::transform10params(), mrpt::topography::transform1D(), mrpt::topography::transform7params(), mrpt::topography::transform7params_TOPCON(), mrpt::topography::transformHelmert3D_TOPCON(), mrpt::slam::COccupancyGridMapFeatureExtractor::uncached_extractFeatures(), mrpt::vision::CCamModel::unproject_3D_point(), unsafeProjectPoint(), mrpt::topography::UTMToGeodetic(), and mrpt::opengl::CBox::writeToStream().
double mrpt::math::TPoint3D::y |
Definition at line 388 of file lightweight_geom_data.h.
Referenced by mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::castRay(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::detectors::CFaceDetection::checkRelativePosition(), mrpt::poses::CPose2D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::maps::CLandmarksMap::computeLikelihood_RSLC_2007(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::math::conformAPlane(), mrpt::math::TLine3D::contains(), mrpt::math::TPolygon3D::contains(), mrpt::obs::detail::cost_func(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::distance(), mrpt::math::TLine3D::distance(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::vision::frameJac(), mrpt::topography::geocentricToENU_WGS84(), mrpt::topography::geocentricToGeodetic(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::geodeticToUTM(), mrpt::topography::GeodeticToUTM(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::maps::COctoMap::getAsOctoMapVoxels(), mrpt::maps::CColouredOctoMap::getAsOctoMapVoxels(), getAsVector(), mrpt::opengl::COpenGLStandardObject::getBoundingBox(), mrpt::opengl::CText::getBoundingBox(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::opengl::CDisk::getBoundingBox(), mrpt::opengl::CAxis::getBoundingBox(), mrpt::opengl::CColorBar::getBoundingBox(), mrpt::opengl::CSphere::getBoundingBox(), mrpt::opengl::CSimpleLine::getBoundingBox(), mrpt::opengl::CTexturedPlane::getBoundingBox(), mrpt::opengl::CArrow::getBoundingBox(), mrpt::opengl::CGridPlaneXY::getBoundingBox(), mrpt::opengl::CText3D::getBoundingBox(), mrpt::opengl::CGridPlaneXZ::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CPolyhedron::getBoundingBox(), mrpt::opengl::CCylinder::getBoundingBox(), mrpt::opengl::CMesh3D::getBoundingBox(), mrpt::opengl::CMeshFast::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CMesh::getBoundingBox(), mrpt::opengl::CVectorField2D::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::opengl::CVectorField3D::getBoundingBox(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CLandmark::getPose(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), IMPLEMENTS_SERIALIZABLE(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), insertRotunda(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::poses::CPose3D::inverseComposePoint(), jacob_dh_db_and_dh_dc(), mrpt::vision::CCamModel::jacobian_project_with_distortion(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::math::operator!=(), mrpt::math::operator-(), mrpt::math::operator<<(), mrpt::math::operator==(), mrpt::math::operator>>(), operator[](), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pointJac(), mrpt::math::project3D(), mrpt::vision::CCamModel::project_3D_point(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoint_with_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::push_back(), mrpt::opengl::CBox::readFromStream(), mrpt::vision::recompute_errors_and_Jacobians(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CColorBar::render_dl(), mrpt::opengl::CBox::render_dl(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), se3_l2_internal(), mrpt::opengl::CBox::setBoxCorners(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CLandmark::setPose(), mrpt::poses::CPose3DRotVec::sphericalCoordinates(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), TEST(), Pose3DQuatTests::test_composeAndInvComposePoint(), Pose3DQuatTests::test_composePoint_vs_CPose3D(), Pose3DQuatTests::test_composePointJacob(), Pose3DTests::test_composePointJacob(), Pose3DTests::test_composePointJacob_se3(), Pose3DQuatTests::test_invComposePoint_vs_CPose3D(), Pose3DQuatTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob_se3(), mrpt::math::TLine2D::TLine2D(), mrpt::math::TLine3D::TLine3D(), mrpt::math::TPlane::TPlane(), mrpt::opengl::CCylinder::traceRay(), mrpt::topography::transfInterpolation(), mrpt::topography::transform10params(), mrpt::topography::transform1D(), mrpt::topography::transform7params(), mrpt::topography::transform7params_TOPCON(), mrpt::topography::transformHelmert3D_TOPCON(), mrpt::slam::COccupancyGridMapFeatureExtractor::uncached_extractFeatures(), mrpt::vision::CCamModel::unproject_3D_point(), unsafeProjectPoint(), mrpt::topography::UTMToGeodetic(), and mrpt::opengl::CBox::writeToStream().
double mrpt::math::TPoint3D::z |
Definition at line 388 of file lightweight_geom_data.h.
Referenced by mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::castRay(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::poses::CPose2D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::math::conformAPlane(), mrpt::math::TLine3D::contains(), mrpt::math::TPolygon3D::contains(), mrpt::obs::detail::cost_func(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::distance(), mrpt::math::TLine3D::distance(), mrpt::math::TPolygon3D::distance(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::vision::frameJac(), mrpt::topography::geocentricToENU_WGS84(), mrpt::topography::geocentricToGeodetic(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::geodeticToUTM(), mrpt::topography::GeodeticToUTM(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::maps::COctoMap::getAsOctoMapVoxels(), mrpt::maps::CColouredOctoMap::getAsOctoMapVoxels(), getAsVector(), mrpt::opengl::COpenGLStandardObject::getBoundingBox(), mrpt::opengl::CText::getBoundingBox(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::opengl::CDisk::getBoundingBox(), mrpt::opengl::CAxis::getBoundingBox(), mrpt::opengl::CColorBar::getBoundingBox(), mrpt::opengl::CSphere::getBoundingBox(), mrpt::opengl::CSimpleLine::getBoundingBox(), mrpt::opengl::CTexturedPlane::getBoundingBox(), mrpt::opengl::CArrow::getBoundingBox(), mrpt::opengl::CGridPlaneXY::getBoundingBox(), mrpt::opengl::CText3D::getBoundingBox(), mrpt::opengl::CGridPlaneXZ::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CPolyhedron::getBoundingBox(), mrpt::opengl::CCylinder::getBoundingBox(), mrpt::opengl::CMesh3D::getBoundingBox(), mrpt::opengl::CMeshFast::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CMesh::getBoundingBox(), mrpt::opengl::CVectorField2D::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::opengl::CVectorField3D::getBoundingBox(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CLandmark::getPose(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), IMPLEMENTS_SERIALIZABLE(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), insertRotunda(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::poses::CPose3D::inverseComposePoint(), jacob_dh_db_and_dh_dc(), mrpt::vision::CCamModel::jacobian_project_with_distortion(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::math::operator!=(), mrpt::math::operator-(), mrpt::math::operator<<(), mrpt::math::operator==(), mrpt::math::operator>>(), operator[](), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pointJac(), mrpt::math::project3D(), mrpt::vision::CCamModel::project_3D_point(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoint_with_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::opengl::CBox::readFromStream(), mrpt::vision::recompute_errors_and_Jacobians(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CColorBar::render_dl(), mrpt::opengl::CBox::render_dl(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), se3_l2_internal(), mrpt::opengl::CBox::setBoxCorners(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CLandmark::setPose(), mrpt::poses::CPose3DRotVec::sphericalCoordinates(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), TEST(), Pose3DQuatTests::test_composeAndInvComposePoint(), Pose3DQuatTests::test_composePoint_vs_CPose3D(), Pose3DQuatTests::test_composePointJacob(), Pose3DTests::test_composePointJacob(), Pose3DTests::test_composePointJacob_se3(), Pose3DQuatTests::test_invComposePoint_vs_CPose3D(), Pose3DQuatTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob_se3(), mrpt::math::TLine3D::TLine3D(), mrpt::math::TPlane::TPlane(), mrpt::opengl::CCylinder::traceRay(), mrpt::topography::transfInterpolation(), mrpt::topography::transform10params(), mrpt::topography::transform1D(), mrpt::topography::transform7params(), mrpt::topography::transform7params_TOPCON(), mrpt::topography::transformHelmert3D_TOPCON(), mrpt::slam::COccupancyGridMapFeatureExtractor::uncached_extractFeatures(), mrpt::vision::CCamModel::unproject_3D_point(), unsafeProjectPoint(), mrpt::topography::UTMToGeodetic(), and mrpt::opengl::CBox::writeToStream().
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019 |