MRPT  2.0.2
Macros | Functions
Funtions in #include <mrpt/core/bits_math.h>

Detailed Description

Collaboration diagram for Funtions in #include <mrpt/core/bits_math.h>:

Macros

#define M_PI   3.14159265358979323846
 
#define M_PIl   3.14159265358979323846264338327950288L
 
#define M_2PIl   (2.0L * 3.14159265358979323846264338327950288L)
 
#define DEG2RAD   DEG2RAD
 
#define RAD2DEG   RAD2DEG
 

Functions

template<typename num_t , typename return_t = num_t>
return_t mrpt::square (const num_t x)
 Inline function for the square of a number. More...
 
template<class T >
mrpt::hypot_fast (const T x, const T y)
 Faster version of std::hypot(), to use when overflow is not an issue and we prefer fast code. More...
 
constexpr double mrpt::DEG2RAD (const double x)
 Degrees to radians. More...
 
constexpr float mrpt::DEG2RAD (const float x)
 Degrees to radians. More...
 
constexpr double mrpt::DEG2RAD (const int x)
 Degrees to radians. More...
 
constexpr double mrpt::RAD2DEG (const double x)
 Radians to degrees. More...
 
constexpr float mrpt::RAD2DEG (const float x)
 Radians to degrees. More...
 
constexpr long double mrpt::DEG2RAD (const long double x)
 Degrees to radians. More...
 
constexpr long double mrpt::RAD2DEG (const long double x)
 Radians to degrees. More...
 
constexpr double mrpt::operator"" _deg (long double v)
 degrees to radian literal operator (e.g. More...
 
template<typename T >
int mrpt::sign (T x)
 Returns the sign of X as "1" or "-1". More...
 
template<typename T >
int mrpt::signWithZero (T x)
 Returns the sign of X as "0", "1" or "-1". More...
 
template<typename T >
mrpt::lowestPositive (const T a, const T b)
 Returns the smallest positive number among a and b. More...
 
template<typename T >
mrpt::abs_diff (const T a, const T b)
 Efficient and portable evaluation of the absolute difference of two unsigned integer values (but will also work for signed and floating point types) More...
 
template<typename T >
const T mrpt::min3 (const T &A, const T &B, const T &C)
 
template<typename T >
const T mrpt::max3 (const T &A, const T &B, const T &C)
 
template<typename T >
int mrpt::fix (T x)
 Rounds toward zero. More...
 
template<typename T , typename K >
void mrpt::keep_min (T &var, const K test_val)
 If the second argument is below the first one, set the first argument to this lower value. More...
 
template<typename T , typename K >
void mrpt::keep_max (T &var, const K test_val)
 If the second argument is above the first one, set the first argument to this higher value. More...
 
template<typename T >
void mrpt::saturate (T &var, const T sat_min, const T sat_max)
 Saturate the value of var (the variable gets modified) so it does not get out of [min,max]. More...
 
template<typename T >
mrpt::saturate_val (const T &value, const T sat_min, const T sat_max)
 Like saturate() but it returns the value instead of modifying the variable. More...
 
template<class T >
mrpt::round2up (T val)
 Round up to the nearest power of two of a given number. More...
 
float mrpt::d2f (const double d)
 shortcut for static_cast<float>(double) More...
 
uint8_t mrpt::f2u8 (const float f)
 converts a float [0,1] into an uint8_t [0,255] (without checking for out of bounds) More...
 
float mrpt::u8tof (const uint8_t v)
 converts a uint8_t [0,255] into a float [0,1] More...
 

Macro Definition Documentation

◆ DEG2RAD

#define DEG2RAD   DEG2RAD

◆ M_2PIl

#define M_2PIl   (2.0L * 3.14159265358979323846264338327950288L)

Definition at line 64 of file core/include/mrpt/core/bits_math.h.

◆ M_PI

#define M_PI   3.14159265358979323846

Definition at line 43 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CPTG_RobotShape_Circular::add_robotShape_to_setOfLines(), mrpt::nav::CParameterizedTrajectoryGenerator::alpha2index(), mrpt::math::angDistance(), mrpt::hwdrivers::CServoeNeck::angle2RegValue(), mrpt::math::averageWrap2Pi(), mrpt::maps::CGasConcentrationGridMap2D::build_Gaussian_Wind_Grid(), mrpt::nav::collision_free_dist_arc_circ_robot(), mrpt::expr::CRuntimeCompiledExpression::compile(), mrpt::maps::COccupancyGridMap2D::computeClearance(), mrpt::hwdrivers::CIbeoLuxETH::convertTicksToHRad(), mrpt::hwdrivers::CIbeoLuxETH::convertToCartesian(), mrpt::math::covariancesAndMeanWeighted(), GraphSlamLevMarqTest< my_graph_t >::create_ring_path(), mrpt::opengl::CPolyhedron::CreateCupola(), mrpt::opengl::CPolyhedron::CreateIcosahedron(), mrpt::opengl::CPolyhedron::CreateJohnsonSolidWithConstantBase(), mrpt::math::TPolygon3D::createRegularPolygon(), mrpt::math::TPolygon2D::createRegularPolygon(), mrpt::opengl::CPolyhedron::CreateRhombicuboctahedron(), mrpt::opengl::CPolyhedron::CreateTrapezohedron(), mrpt::DEG2RAD(), mrpt::nav::CHolonomicND::direction2sector(), mrpt::nav::CHolonomicFullEval::direction2sector(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), mrpt::ros1bridge::fromROS(), mrpt::opengl::CPolyhedron::generateBase(), mrpt::opengl::CPolyhedron::generateShiftedBase(), mrpt::math::getAngle(), mrpt::nav::CParameterizedTrajectoryGenerator::index2alpha(), insertCupola(), insertRotunda(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::nav::CPTG_DiffDrive_C::inverseMap_WS2TP(), mrpt::poses::CPose3D::isHorizontal(), mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::maps::CLandmarksMap::TLikelihoodOptions::loadFromConfigFile(), mrpt::nav::CHolonomicVFF::navigate(), mrpt::nav::CPTG_DiffDrive_CCS::ptgDiffDriveSteeringFunction(), mrpt::nav::CPTG_DiffDrive_CC::ptgDiffDriveSteeringFunction(), mrpt::nav::CPTG_DiffDrive_alpha::ptgDiffDriveSteeringFunction(), mrpt::nav::CPTG_DiffDrive_C::ptgDiffDriveSteeringFunction(), mrpt::RAD2DEG(), ransac_data_assoc_run(), mrpt::hwdrivers::CServoeNeck::regValue2angle(), mrpt::nav::PlannerTPS_VirtualBase::renderMoveTree(), mrpt::math::CQuaternion< T >::rpy_and_jacobian(), mrpt::hwdrivers::CServoeNeck::setAngle(), mrpt::hwdrivers::CServoeNeck::setAngleAndSpeed(), mrpt::vision::CDifodo::setFOV(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), mrpt::math::spline(), TEST(), TEST_F(), mrpt::nav::PlannerRRT_SE2_TPS::TPlannerInput::TPlannerInput(), mrpt::hwdrivers::CHokuyoURG::turnOn(), mrpt::math::unwrap2PiSequence(), velodyne_scan_to_pointcloud(), mrpt::math::wrapTo2PiInPlace(), and mrpt::math::wrapToPi().

◆ M_PIl

#define M_PIl   3.14159265358979323846264338327950288L

Definition at line 63 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::DEG2RAD(), and mrpt::RAD2DEG().

◆ RAD2DEG

#define RAD2DEG   RAD2DEG

Function Documentation

◆ abs_diff()

template<typename T >
T mrpt::abs_diff ( const T  a,
const T  b 
)
inline

Efficient and portable evaluation of the absolute difference of two unsigned integer values (but will also work for signed and floating point types)

Definition at line 118 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CHolonomicND::calcRepresentativeSectorForGap(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), mrpt::nav::CHolonomicND::evaluateGaps(), and TEST().

Here is the caller graph for this function:

◆ d2f()

float mrpt::d2f ( const double  d)
inline

shortcut for static_cast<float>(double)

Definition at line 189 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::opengl::TRenderMatrices::applyLookAt(), aux_add3DpointWithEigenVectors(), mrpt::vision::CDifodo::calculateDepthDerivatives(), mrpt::obs::carmen_log_parse_line(), mrpt::maps::CRandomFieldGridMap2D::cell2float(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::poses::CPose3D::composePoint(), mrpt::maps::CPointsMap::compute3DDistanceToMesh(), mrpt::maps::CLandmarksMap::compute3DMatchingRatio(), mrpt::maps::COccupancyGridMap2D::computeEntropy(), mrpt::maps::CBeaconMap::computeMatchingWith3DLandmarks(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::maps::COccupancyGridMap2D::computePathCost(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::obs::detail::cost_func(), mrpt::maps::CPointsMap::determineMatching2D(), mrpt::maps::COccupancyGridMap2D::determineMatching2D(), mrpt::maps::CPointsMap::determineMatching3D(), mrpt::obs::CObservationRotatingScan::fromScan2D(), generate_list_of_points(), mrpt::maps::COccupancyGridMap3D::getAsOctoMapVoxels(), mrpt::opengl::CPlanarLaserScan::getLocalRepresentativePoint(), mrpt::maps::CHeightGridMap2D_Base::getMinMaxHeight(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::vision::TKeyPointList_templ< TKeyPoint >::getScale(), mrpt::obs::CSinCosLookUpTableFor2DScans::getSinCosForScan(), mrpt::maps::CGasConcentrationGridMap2D::getWindAs3DObject(), IMPLEMENTS_SERIALIZABLE(), mrpt::maps::CHeightGridMap2D::insertIndividualPoint(), mrpt::maps::CPointsMap::insertPoint(), mrpt::vision::CFeatureExtraction::internal_computeSpinImageDescriptors(), mrpt::vision::CFeature::internal_distanceBetweenPolarImages(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::gui::CDisplayWindowPlots::internal_plot_interface(), mrpt::obs::CObservationGasSensors::CMOSmodel::inverse_MOSmodeling(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint2D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint2DsqrError(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint2D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint2DIdx(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::vision::CDifodo::odometryCalculation(), mrpt::gui::CWindowDialogPlots::OnMenuSelected(), mrpt::vision::CFeature::patchCorrelationTo(), mrpt::topography::path_from_rtk_gps(), mrpt::gui::CDisplayWindowPlots::plotEllipse(), ply_read(), mrpt::opengl::CSetOfObjects::posePDF2opengl(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::opengl::CCylinder::reachesHeight(), mrpt::opengl::CPointCloudColoured::render_subset(), mrpt::opengl::CPointCloud::render_subset(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::CCollisionGrid::saveToFile(), mrpt::math::SegmentsIntersection(), mrpt::maps::CPointsMap::setPoint(), mrpt::opengl::CCamera::setPointingAt(), mrpt::maps::CLandmark::setPose(), mrpt::maps::CPointsMap::squareDistanceToClosestCorrespondenceT(), mrpt::tfest::TMatchingPairList::squareErrorVector(), store_item(), TEST(), mrpt::opengl::CCylinder::traceRay(), mrpt::vision::pinhole::undistort_point(), mrpt::vision::pinhole::undistort_points(), mrpt::kinematics::CKinematicChain::update3DObject(), velodyne_scan_to_pointcloud(), and write_binary_item().

Here is the caller graph for this function:

◆ DEG2RAD() [1/4]

constexpr double mrpt::DEG2RAD ( const double  x)
inline

Degrees to radians.

Examples:
serialization_json_example/test.cpp.

Definition at line 47 of file core/include/mrpt/core/bits_math.h.

References M_PI.

Referenced by ICPTests::align2scans(), mrpt::slam::CGridMapAligner::AlignPDF_correlation(), atan2_lut_test(), mrpt::obs::carmen_log_parse_line(), mrpt::opengl::CFrustum::CFrustum(), mrpt::opengl::TRenderMatrices::computeProjectionMatrix(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), mrpt::math::TTwist2D::fromString(), mrpt::math::TPose2D::fromString(), mrpt::math::TTwist3D::fromString(), mrpt::math::TPose3D::fromString(), mrpt::poses::CPose2D::fromString(), mrpt::poses::CPose3D::fromString(), mrpt::obs::CObservationRotatingScan::fromVelodyne(), mrpt::maps::CBeacon::generateRingSOG(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getAlignCmd(), mrpt::hwdrivers::CBoardSonars::getObservation(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::apps::CGridMapAlignerApp::initialize(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::obs::VelodyneCalibration::internal_loadFromXMLNode(), mrpt::kinematics::CVehicleSimul_Holo::internal_simulControlStep(), mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::hwdrivers::CSickLaserUSB::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUIntersense::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSkeletonTracker::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGyroKVHDSP3000::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboPeakLidar::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIbeoLuxETH::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSICKTim561Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserSerial::loadConfig_sensorSpecific(), mrpt::hwdrivers::CBoardSonars::loadConfig_sensorSpecific(), mrpt::hwdrivers::CLMS100Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CVelodyneScanner::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2_RGBD360::loadConfig_sensorSpecific(), mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), mrpt::nav::CPTG_Holo_Blend::loadDefaultParams(), mrpt::nav::CPTG_DiffDrive_alpha::loadDefaultParams(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::loadDefaultParams(), mrpt::slam::CICP::TConfigParams::loadFromConfigFile(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::loadFromConfigFile(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_TBI(), mrpt::opengl::CAxis::onUpdateBuffers_Wireframe(), mrpt::operator"" _deg(), mrpt::opengl::COpenGLViewport::renderNormalSceneMode(), mrpt::hwdrivers::CNTRIPClient::retrieveListOfMountpoints(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), run_rnav_test(), run_test_pf_localization(), mrpt::tfest::se2_l2_robust(), mrpt::opengl::CFrustum::setHorzFOV(), mrpt::opengl::CFrustum::setHorzFOVAsymmetric(), mrpt::opengl::CFrustum::setVertFOV(), mrpt::opengl::CFrustum::setVertFOVAsymmetric(), mrpt::topography::TDatum10Params::TDatum10Params(), mrpt::topography::TDatum7Params::TDatum7Params(), mrpt::topography::TDatumHelmert2D::TDatumHelmert2D(), mrpt::topography::TDatumHelmert3D::TDatumHelmert3D(), mrpt::topography::TDatumTransfInterpolation::TDatumTransfInterpolation(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), TEST(), TEST_F(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::TOptions(), mrpt::hmtslam::CHMTSLAM::TOptions::TOptions(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::updateLaserScansVisualization(), mrpt::gui::CGlCanvasBase::updatePan(), mrpt::gui::CGlCanvasBase::updateRotate(), and mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateVisuals().

Here is the caller graph for this function:

◆ DEG2RAD() [2/4]

constexpr float mrpt::DEG2RAD ( const float  x)
inline

Degrees to radians.

Definition at line 49 of file core/include/mrpt/core/bits_math.h.

References M_PI.

◆ DEG2RAD() [3/4]

constexpr double mrpt::DEG2RAD ( const int  x)
inline

Degrees to radians.

Definition at line 54 of file core/include/mrpt/core/bits_math.h.

References M_PI.

◆ DEG2RAD() [4/4]

constexpr long double mrpt::DEG2RAD ( const long double  x)
inline

Degrees to radians.

Definition at line 67 of file core/include/mrpt/core/bits_math.h.

References M_PIl.

◆ f2u8()

uint8_t mrpt::f2u8 ( const float  f)
inline

◆ fix()

template<typename T >
int mrpt::fix ( x)
inline

Rounds toward zero.

Definition at line 136 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::topography::GeodeticToUTM(), mrpt::topography::geodeticToUTM(), and TEST().

Here is the caller graph for this function:

◆ hypot_fast()

template<class T >
T mrpt::hypot_fast ( const T  x,
const T  y 
)
inline

Faster version of std::hypot(), to use when overflow is not an issue and we prefer fast code.

Definition at line 31 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::build_movement_candidate(), mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::nav::CPTG_RobotShape_Polygonal::evalClearanceToRobotShape(), mrpt::nav::CPTG_RobotShape_Circular::evalClearanceToRobotShape(), mrpt::nav::CPTG_RobotShape_Circular::isPointInsideRobotShape(), mrpt::math::TPose2D::norm(), and TEST().

Here is the caller graph for this function:

◆ keep_max()

template<typename T , typename K >
void mrpt::keep_max ( T &  var,
const K  test_val 
)
inline

If the second argument is above the first one, set the first argument to this higher value.

Definition at line 152 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CHolonomicND::calcRepresentativeSectorForGap(), mrpt::opengl::CFrustum::CFrustum(), mrpt::nav::CMultiObjectiveMotionOptimizerBase::decide(), mrpt::system::CTimeLogger::do_leave(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::nav::CPTG_RobotShape_Polygonal::evalClearanceToRobotShape(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), mrpt::math::MatrixBlockSparseCols< Scalar, NROWS, NCOLS, INFO, HAS_REMAP, INDEX_REMAP_MAP_IMPL >::findCurrentNumberOfRows(), mrpt::ros1bridge::fromROS(), mrpt::nav::CHolonomicND::gapsEstimator(), mrpt::slam::CIncrementalMapPartitioner::getAs3DScene(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::math::TPolygon2D::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CMesh3D::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::poses::CPoseInterpolatorBase< 3 >::getBoundingBox(), mrpt::opengl::CSetOfLines::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::vision::TKeyPointList_templ< TKeyPoint >::getMaxID(), mrpt::vision::CFeatureList::getMaxID(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), mrpt::nav::CParameterizedTrajectoryGenerator::loadFromConfigFile(), mrpt::vision::matchFeatures(), mrpt::math::maximum(), mrpt::math::minimum_maximum(), mrpt::nav::CHolonomicFullEval::navigate(), mrpt::opengl::COctreePointRenderer< CPointCloudColoured >::octree_recursive_render(), mrpt::graphslam::optimize_graph_spa_levmarq(), mrpt::hwdrivers::CGPSInterface::parseBuffer(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfAuxiliaryPFOptimal(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::system::CTimeLogger::registerUserMeasure(), mrpt::nav::PlannerTPS_VirtualBase::renderMoveTree(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::renderUpdateBuffers(), mrpt::opengl::CFrustum::setHorzFOV(), mrpt::opengl::CFrustum::setHorzFOVAsymmetric(), mrpt::nav::CPTG_RobotShape_Polygonal::setRobotShape(), mrpt::opengl::CFrustum::setVertFOV(), mrpt::opengl::CFrustum::setVertFOVAsymmetric(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), TEST(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), mrpt::opengl::CMesh::updateColorsMatrix(), and mrpt::vision::CMatchedFeatureList::updateMaxID().

Here is the caller graph for this function:

◆ keep_min()

template<typename T , typename K >
void mrpt::keep_min ( T &  var,
const K  test_val 
)
inline

If the second argument is below the first one, set the first argument to this lower value.

Definition at line 145 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CAbstractPTGBasedReactive::calc_move_candidate_scores(), mrpt::nav::CHolonomicND::calcRepresentativeSectorForGap(), mrpt::opengl::CFrustum::CFrustum(), mrpt::maps::COccupancyGridMap2D::computeLikelihoodField_Thrun(), mrpt::obs::CObservation3DRangeScan::convertTo2DScan(), mrpt::system::CTimeLogger::do_leave(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::nav::CParameterizedTrajectoryGenerator::evalClearanceSingleObstacle(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), find_chessboard_corners_multiple(), mrpt::ros1bridge::fromROS(), mrpt::nav::CHolonomicND::gapsEstimator(), mrpt::slam::CIncrementalMapPartitioner::getAs3DScene(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::math::TPolygon2D::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CMesh3D::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::poses::CPoseInterpolatorBase< 3 >::getBoundingBox(), mrpt::opengl::CSetOfLines::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihoodPointCloud3D(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::internal_initialize(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::nav::CParameterizedTrajectoryGenerator::internal_TPObsDistancePostprocess(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), mrpt::math::minimum(), mrpt::math::minimum_maximum(), mrpt::nav::CHolonomicFullEval::navigate(), mrpt::opengl::COctreePointRenderer< CPointCloudColoured >::octree_recursive_render(), mrpt::system::CTimeLogger::registerUserMeasure(), mrpt::opengl::CGeneralizedEllipsoidTemplate< 3 >::renderUpdateBuffers(), mrpt::opengl::CFrustum::setHorzFOV(), mrpt::opengl::CFrustum::setHorzFOVAsymmetric(), mrpt::opengl::CFrustum::setVertFOV(), mrpt::opengl::CFrustum::setVertFOVAsymmetric(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), TEST(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), mrpt::opengl::CMesh::updateColorsMatrix(), and mrpt::nav::CPTG_Holo_Blend::updateTPObstacleSingle().

Here is the caller graph for this function:

◆ lowestPositive()

template<typename T >
T mrpt::lowestPositive ( const T  a,
const T  b 
)

Returns the smallest positive number among a and b.

Definition at line 104 of file core/include/mrpt/core/bits_math.h.

Referenced by TEST().

Here is the caller graph for this function:

◆ max3()

template<typename T >
const T mrpt::max3 ( const T &  A,
const T &  B,
const T &  C 
)
inline

Definition at line 129 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::maps::COccupancyGridMap3D::insertRay(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::img::rgb2hsv(), and TEST().

Here is the caller graph for this function:

◆ min3()

template<typename T >
const T mrpt::min3 ( const T &  A,
const T &  B,
const T &  C 
)
inline

Definition at line 124 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::nav::CHolonomicND::evaluateGaps(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::img::rgb2hsv(), and TEST().

Here is the caller graph for this function:

◆ operator"" _deg()

constexpr double mrpt::operator"" _deg ( long double  v)
inline

degrees to radian literal operator (e.g.

x=90.0_deg;)

Definition at line 83 of file core/include/mrpt/core/bits_math.h.

References mrpt::DEG2RAD().

Here is the call graph for this function:

◆ RAD2DEG() [1/3]

constexpr double mrpt::RAD2DEG ( const double  x)
inline

Radians to degrees.

Definition at line 56 of file core/include/mrpt/core/bits_math.h.

References M_PI.

Referenced by mrpt::slam::CGridMapAligner::AlignPDF_correlation(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::math::TTwist2D::asString(), mrpt::math::TPose2D::asString(), mrpt::math::TTwist3D::asString(), mrpt::math::TPose3D::asString(), mrpt::poses::CPose2D::asString(), mrpt::poses::CPose3D::asString(), mrpt::obs::CObservationBearingRange::debugPrintOut(), mrpt::apps::RawlogGrabberApp::dump_IMU_info(), mrpt::hmtslam::CLocalMetricHypothesis::dumpAsText(), mrpt::slam::TKLDParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderICP::TConfigParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions::dumpToTextStream(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::vision::TMultiResDescMatchOptions::dumpToTextStream(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::graphslam::deciders::CIncrementalNodeRegistrationDecider< GRAPH_T >::TParams::getAsString(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::getAsString(), mrpt::nav::TWaypoint::getAsText(), mrpt::nav::CPTG_DiffDrive_alpha::getDescription(), mrpt::obs::CObservationRange::getDescriptionAsText(), mrpt::obs::CObservationBearingRange::getDescriptionAsText(), mrpt::obs::CObservationIMU::getDescriptionAsText(), mrpt::obs::CObservationRotatingScan::getDescriptionAsText(), mrpt::opengl::CFrustum::getHorzFOV(), mrpt::opengl::CFrustum::getHorzFOVLeft(), mrpt::opengl::CFrustum::getHorzFOVRight(), mrpt::opengl::CRenderizable::getPosePitch(), mrpt::opengl::CRenderizable::getPoseRoll(), mrpt::opengl::CRenderizable::getPoseYaw(), mrpt::opengl::CFrustum::getVertFOV(), mrpt::opengl::CFrustum::getVertFOVDown(), mrpt::opengl::CFrustum::getVertFOVUp(), mrpt::slam::CICP::TConfigParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::TOptions::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_TBI(), mrpt::poses::operator<<(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), mrpt::hwdrivers::CNTRIPClient::retrieveListOfMountpoints(), mrpt::nav::CPTG_Holo_Blend::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_alpha::saveToConfigFile(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::saveToConfigFile(), mrpt::nav::CParameterizedTrajectoryGenerator::saveToConfigFile(), mrpt::hwdrivers::CServoeNeck::setAngle(), TEST(), mrpt::hwdrivers::CHokuyoURG::turnOn(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().

Here is the caller graph for this function:

◆ RAD2DEG() [2/3]

constexpr float mrpt::RAD2DEG ( const float  x)
inline

Radians to degrees.

Definition at line 58 of file core/include/mrpt/core/bits_math.h.

References M_PI.

◆ RAD2DEG() [3/3]

constexpr long double mrpt::RAD2DEG ( const long double  x)
inline

Radians to degrees.

Definition at line 72 of file core/include/mrpt/core/bits_math.h.

References M_PIl.

◆ round2up()

template<class T >
T mrpt::round2up ( val)

Round up to the nearest power of two of a given number.

Definition at line 177 of file core/include/mrpt/core/bits_math.h.

References val.

Referenced by mrpt::math::cross_correlation_FFT(), mrpt::math::dft2_complex(), mrpt::math::idft2_complex(), mrpt::math::idft2_real(), and TEST().

Here is the caller graph for this function:

◆ saturate()

template<typename T >
void mrpt::saturate ( T &  var,
const T  sat_min,
const T  sat_max 
)
inline

Saturate the value of var (the variable gets modified) so it does not get out of [min,max].

Definition at line 159 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::maps::CRandomFieldGridMap2D::getAsMatrix(), TEST(), and mrpt::maps::CRandomFieldGridMap2D::updateMapEstimation_GMRF().

Here is the caller graph for this function:

◆ saturate_val()

template<typename T >
T mrpt::saturate_val ( const T &  value,
const T  sat_min,
const T  sat_max 
)
inline

Like saturate() but it returns the value instead of modifying the variable.

Definition at line 167 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::maps::CRandomFieldGridMap2D::getAs3DObject(), mrpt::maps::CRandomFieldGridMap2D::saveAsMatlab3DGraph(), and TEST().

Here is the caller graph for this function:

◆ sign()

template<typename T >
int mrpt::sign ( x)
inline

◆ signWithZero()

template<typename T >
int mrpt::signWithZero ( x)
inline

Returns the sign of X as "0", "1" or "-1".

Definition at line 97 of file core/include/mrpt/core/bits_math.h.

References mrpt::sign().

Referenced by mrpt::nav::CPTG_Holo_Blend::directionToMotionCommand(), mrpt::nav::CRobot2NavInterfaceForSimulator_Holo::getAlignCmd(), mrpt::nav::CPTG_Holo_Blend::getPathPose(), and TEST().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ square()

template<typename num_t , typename return_t = num_t>
return_t mrpt::square ( const num_t  x)
inline

Inline function for the square of a number.

Definition at line 23 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::opengl::CPolyhedron::TPolyhedronFace::area(), mrpt::poses::CPosePDFGaussian::assureMinCovariance(), aux_projectPoint_with_distortion(), mrpt::graphs::detail::graph_ops< graph_t >::auxEuclid2Dist(), mrpt::graphs::detail::graph_ops< graph_t >::auxMaha2Dist(), mrpt::poses::CPointPDFSOG::bayesianFusion(), mrpt::maps::CGasConcentrationGridMap2D::build_Gaussian_Wind_Grid(), mrpt::vision::CDifodo::calculateDepthDerivatives(), mrpt::maps::CPointsMap::clipOutOfRange(), mrpt::math::closestSquareDistanceFromPointToLine(), mrpt::nav::collision_free_dist_segment_circ_robot(), mrpt::poses::CPose3DQuat::composePoint(), mrpt::maps::CLandmarksMap::compute3DMatchingRatio(), mrpt::maps::COccupancyGridMap2D::computeClearance(), mrpt::maps::CRandomFieldGridMap2D::computeConfidenceCellValue_DM_DMV(), mrpt::obs::CActionRobotMovement2D::computeFromOdometry_modelGaussian(), mrpt::graphslam::computeJacobiansAndErrors(), mrpt::poses::CPointPDFParticles::computeKurtosis(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::COccupancyGridMap2D::computeLikelihoodField_II(), mrpt::maps::COccupancyGridMap2D::computeLikelihoodField_Thrun(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::maps::CRandomFieldGridMap2D::computeMeanCellValue_DM_DMV(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_rayTracing(), mrpt::nav::PlannerSimple2D::computePath(), mrpt::maps::COccupancyGridMap2D::computePathCost(), mrpt::maps::CRandomFieldGridMap2D::computeVarCellValue_DM_DMV(), mrpt::vision::CDifodo::computeWeights(), mrpt::obs::detail::cost_func(), mrpt::opengl::CPolyhedron::CreateIcosahedron(), mrpt::opengl::CPolyhedron::CreateJohnsonSolidWithConstantBase(), mrpt::opengl::CPolyhedron::CreateRhombicuboctahedron(), mrpt::math::cross_correlation_FFT(), mrpt::img::CImage::cross_correlation_FFT(), mrpt::vision::CFeature::descriptorBLDDistanceTo(), mrpt::vision::CFeature::descriptorLATCHDistanceTo(), mrpt::vision::CFeature::descriptorSIFTDistanceTo(), mrpt::vision::CFeature::descriptorSpinImgDistanceTo(), mrpt::vision::CFeature::descriptorSURFDistanceTo(), mrpt::maps::CPointsMap::determineMatching2D(), mrpt::maps::COccupancyGridMap2D::determineMatching2D(), mrpt::maps::CPointsMap::determineMatching3D(), mrpt::nav::PoseDistanceMetric< TNodeSE2 >::distance(), mrpt::poses::CPose2D::distance2DFrobeniusTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance2DToSquare(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance3DToSquare(), mrpt::poses::CPose3D::distanceEuclidean6D(), mrpt::math::distanceSqrBetweenPoints(), mrpt::math::TPoint3D_< float >::distanceTo(), mrpt::bayes::CParticleFilterDataImpl< CMultiMetricMapPDF, mrpt::bayes::CParticleFilterData< CRBPFParticleData >::CParticleList >::ESS(), mrpt::poses::CPointPDFSOG::ESS(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::evalPWConsistenciesMatrix(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), mrpt::nav::CHolonomicND::evaluateGaps(), mrpt::poses::CPosePDFParticles::evaluatePDF_parzen(), mrpt::obs::CObservation2DRangeScanWithUncertainty::evaluateScanLikelihood(), mrpt::bayes::CParticleFilter::executeOn(), mrpt::maps::CPointsMap::extractCylinder(), mrpt::math::fft_real(), mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::vision::frameJac(), mrpt::maps::CPointsMap::fuseWith(), mrpt::math::generateAxisBaseFromDirection(), mrpt::maps::CBeacon::generateRingSOG(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::GeodeticToUTM(), mrpt::math::getAngleBisector(), mrpt::maps::COccupancyGridMap2D::getArea(), mrpt::maps::CRandomFieldGridMap2D::getAs3DObject(), mrpt::poses::CPointPDFParticles::getCovarianceAndMean(), mrpt::poses::CPose3DPDFParticles::getCovarianceAndMean(), mrpt::poses::CPosePDFParticles::getCovarianceAndMean(), mrpt::opengl::CPolyhedron::getDual(), getHeight(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::getLargestDistanceFromOrigin(), mrpt::maps::CPointsMap::getLargestDistanceFromOrigin(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::slam::CICP::ICP_Method_LM(), insertCupola(), mrpt::maps::CRandomFieldGridMap2D::insertIndividualReading(), mrpt::maps::CRandomFieldGridMap2D::insertObservation_KernelDM_DMV(), mrpt::maps::CRandomFieldGridMap2D::insertObservation_KF(), mrpt::maps::CRandomFieldGridMap2D::insertObservation_KF2(), mrpt::maps::CRandomFieldGridMap2D::internal_clear(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), mrpt::maps::CReflectivityGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihoodPointCloud3D(), mrpt::vision::CFeatureExtraction::internal_computeSpinImageDescriptors(), mrpt::maps::CLandmarksMap::internal_CreateFromMapDefinition(), mrpt::vision::CFeature::internal_distanceBetweenPolarImages(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::CWirelessPowerGridMap2D::internal_insertObservation(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::vision::CGenericFeatureTracker::internal_trackFeatures(), mrpt::poses::CPose3DQuat::inverseComposePoint(), mrpt::nav::CPTG_Holo_Blend::inverseMap_WS2TP(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::inverseMap_WS2TP(), mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(), mrpt::img::CCanvas::line(), mrpt::math::CQuaternion< T >::ln_noresize(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_TBI(), mrpt::math::meanAndCovMat(), mrpt::math::meanAndCovVec(), mrpt::math::meanAndStd(), mrpt::math::meanAndStdColumns(), mrpt::math::minDistBetweenLines(), mrpt::math::minimumDistanceFromPointToSegment(), mrpt::nav::CHolonomicFullEval::navigate(), mrpt::math::ncc_vector(), mrpt::math::noncentralChi2CDF(), mrpt::math::TPose3DQuat::norm(), mrpt::math::TPose3D::norm(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::norm(), mrpt::math::normalize(), mrpt::math::normalPDF(), mrpt::math::CQuaternion< T >::normSqr(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetObservationNoise(), mrpt::slam::CRangeBearingKFSLAM::OnGetObservationNoise(), mrpt::slam::CRangeBearingKFSLAM::OnNormalizeStateVector(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationJacobians(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationModel(), mrpt::slam::CRangeBearingKFSLAM2D::OnTransitionNoise(), mrpt::slam::CRangeBearingKFSLAM::OnTransitionNoise(), mrpt::opengl::CVectorField3D::onUpdateBuffers_Wireframe(), mrpt::graphslam::optimize_graph_spa_levmarq(), mrpt::topography::path_from_rtk_gps(), mrpt::vision::CDifodo::performWarping(), mrpt::vision::pointJac(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::maps::CRandomFieldGridMap2D::predictMeasurement(), mrpt::poses::CPoint2DPDFGaussian::productIntegralNormalizedWith(), mrpt::poses::CPointPDFGaussian::productIntegralNormalizedWith(), mrpt::poses::CPointPDFGaussian::productIntegralNormalizedWith2D(), project_point(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::nav::CPTG_DiffDrive_CC::PTG_IsIntoDomain(), mrpt::nav::CPTG_DiffDrive_CCS::PTG_IsIntoDomain(), mrpt::nav::CPTG_DiffDrive_CS::PTG_IsIntoDomain(), mrpt::nav::CPTG_DiffDrive_CS::ptgDiffDriveSteeringFunction(), mrpt::nav::CPTG_DiffDrive_alpha::ptgDiffDriveSteeringFunction(), ransac_data_assoc_run(), mrpt::obs::CObservation3DRangeScan::recoverCameraCalibrationParameters(), reprojectionResidualsElement(), mrpt::maps::CRandomFieldGridMap2D::resize(), mrpt::math::CQuaternion< T >::rpy_and_jacobian(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_observationLikelihood(), mrpt::maps::CBeaconMap::saveToTextFile(), mrpt::tfest::se2_l2(), mrpt::tfest::se2_l2_robust(), se3_l2_internal(), mrpt::tfest::se3_l2_robust(), mrpt::maps::CRandomFieldGridMap2D::setMeanAndSTD(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::math::TSegment2D::signedDistance(), mrpt::maps::CGasConcentrationGridMap2D::simulateAdvection(), mrpt::nav::CPTG_DiffDrive_CollisionGridBased::simulateTrajectories(), mrpt::math::slerp(), mrpt::math::TPose3D::SO3_to_yaw_pitch_roll(), solveEqn(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), mrpt::math::TPoint3D_< float >::sqrDistanceTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::sqrDistanceTo(), mrpt::math::TPoint3D_< float >::sqrNorm(), mrpt::maps::CPointsMap::squareDistanceToClosestCorrespondence(), mrpt::tfest::TMatchingPairList::squareErrorVector(), mrpt::math::squareNorm(), mrpt::vision::StereoObs2BRObs(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), TEST(), Pose3DQuatTests::test_invComposePointJacob(), mrpt::opengl::CCylinder::traceRay(), mrpt::opengl::CEllipsoid3D::traceRay(), mrpt::opengl::CEllipsoid2D::traceRay(), mrpt::vision::detail::trackFeatures_addNewFeats< CFeatureList >(), mrpt::slam::COccupancyGridMapFeatureExtractor::uncached_extractFeatures(), mrpt::topography::UTMToGeodetic(), and mrpt::nav::CWaypointsNavigator::waypoints_navigationStep().

◆ u8tof()

float mrpt::u8tof ( const uint8_t  v)
inline

converts a uint8_t [0,255] into a float [0,1]

See also
f2u8

Definition at line 196 of file core/include/mrpt/core/bits_math.h.

Referenced by mrpt::img::CImage::getAsRGBMatrices(), mrpt::opengl::CRenderizable::getColorA(), mrpt::opengl::CRenderizable::getColorB(), mrpt::opengl::CRenderizable::getColorG(), mrpt::opengl::CRenderizable::getColorR(), mrpt::opengl::CPointCloudColoured::getPointColor_fast(), and mrpt::opengl::PointCloudAdapter< mrpt::opengl::CPointCloudColoured >::getPointXYZ_RGBAf().

Here is the caller graph for this function:



Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020