#include <mrpt/config.h>
#include <cmath>
#include <string>
#include <mrpt/base/link_pragmas.h>
#include <mrpt/utils/mrpt_macros.h>
#include <mrpt/utils/mrpt_stdint.h>
Go to the source code of this file.
Classes | |
struct | mrpt::utils::CProfilerProxy |
Namespaces | |
mrpt | |
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries. | |
mrpt::math | |
This base provides a set of functions for maths stuff. | |
mrpt::utils | |
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL. | |
Macros | |
#define | _USE_MATH_DEFINES |
#define | M_PI 3.14159265358979323846 |
#define | DEG2RAD DEG2RAD |
#define | RAD2DEG RAD2DEG |
#define | SELBYTE0(v) (v & 0xff) |
#define | SELBYTE1(v) ((v>>8) & 0xff) |
#define | SELBYTE2(v) ((v>>16) & 0xff) |
#define | SELBYTE3(v) ((v>>24) & 0xff) |
#define | MAKEWORD16B(__LOBYTE, __HILOBYTE) ((__LOBYTE) | ((__HILOBYTE)<<8)) |
#define | MAKEWORD32B(__LOWORD16, __HIWORD16) ((__LOWORD16) | ((__HIWORD16)<<16)) |
#define | MAKEWORD64B(__LOWORD32, __HIWORD32) ((__LOWORD32) | ((__HIWORD32)<<32)) |
#define | _USE_MATH_DEFINES |
#define | DEG2RAD DEG2RAD |
#define | RAD2DEG RAD2DEG |
#define | SELBYTE0(v) (v & 0xff) |
#define | SELBYTE1(v) ((v>>8) & 0xff) |
#define | SELBYTE2(v) ((v>>16) & 0xff) |
#define | SELBYTE3(v) ((v>>24) & 0xff) |
#define | MAKEWORD16B(__LOBYTE, __HILOBYTE) ((__LOBYTE) | ((__HILOBYTE)<<8)) |
#define | MAKEWORD32B(__LOWORD16, __HIWORD16) ((__LOWORD16) | ((__HIWORD16)<<16)) |
#define | MAKEWORD64B(__LOWORD32, __HIWORD32) ((__LOWORD32) | ((__HIWORD32)<<32)) |
Functions | |
std::string BASE_IMPEXP | mrpt::format (const char *fmt,...) MRPT_printf_format_check(1 |
A std::string version of C sprintf. More... | |
bool BASE_IMPEXP | mrpt::math::isNaN (float f) MRPT_NO_THROWS |
Returns true if the number is NaN. More... | |
bool BASE_IMPEXP | mrpt::math::isNaN (double f) MRPT_NO_THROWS |
Returns true if the number is NaN. More... | |
bool BASE_IMPEXP | mrpt::math::isFinite (float f) MRPT_NO_THROWS |
Returns true if the number is non infinity. More... | |
bool BASE_IMPEXP | mrpt::math::isFinite (double f) MRPT_NO_THROWS |
Returns true if the number is non infinity. More... | |
template<class MATRIXLIKE > | |
size_t | mrpt::math::size (const MATRIXLIKE &m, const int dim) |
template<class T > | |
T | mrpt::math::square (const T x) |
Inline function for the square of a number. More... | |
template<class T > | |
T | mrpt::math::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... | |
double | mrpt::utils::DEG2RAD (const double x) |
Degrees to radians. More... | |
float | mrpt::utils::DEG2RAD (const float x) |
Degrees to radians. More... | |
float | mrpt::utils::DEG2RAD (const int x) |
Degrees to radians. More... | |
double | mrpt::utils::RAD2DEG (const double x) |
Radians to degrees. More... | |
float | mrpt::utils::RAD2DEG (const float x) |
Radians to degrees. More... | |
template<typename T > | |
int | mrpt::utils::sign (T x) |
Returns the sign of X as "1" or "-1". More... | |
template<typename T > | |
int | mrpt::utils::signWithZero (T x) |
Returns the sign of X as "0", "1" or "-1". More... | |
template<typename T > | |
T | mrpt::utils::lowestPositive (const T a, const T b) |
Returns the lowest, possitive among two numbers. More... | |
template<typename T > | |
T | mrpt::utils::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::utils::min3 (const T &A, const T &B, const T &C) |
template<typename T > | |
const T | mrpt::utils::max3 (const T &A, const T &B, const T &C) |
template<typename T > | |
int | mrpt::utils::fix (T x) |
Rounds toward zero. More... | |
template<class R , class SMART_PTR > | |
R * | mrpt::utils::getAs (SMART_PTR &o) |
< Allow square() to be available under mrpt::math and mrpt::utils More... | |
template<class R , class SMART_PTR > | |
const R * | mrpt::utils::getAs (const SMART_PTR &o) |
Utility to get a cast'ed pointer from a smart pointer. More... | |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (bool &v_in_out) |
Reverse the order of the bytes of a given type (useful for transforming btw little/big endian) More... | |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (uint8_t &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (int8_t &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (uint16_t &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (int16_t &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (uint32_t &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (int32_t &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (uint64_t &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (int64_t &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (float &v_in_out) |
void BASE_IMPEXP | mrpt::utils::reverseBytesInPlace (double &v_in_out) |
template<class T > | |
void | mrpt::utils::reverseBytes (const T &v_in, T &v_out) |
Reverse the order of the bytes of a given type (useful for transforming btw little/big endian) More... | |
template<typename T , typename K > | |
void | mrpt::utils::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::utils::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::utils::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 > | |
T | mrpt::utils::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 > | |
void | mrpt::utils::delete_safe (T *&ptr) |
Calls "delete" to free an object only if the pointer is not NULL, then set the pointer to NULL. More... | |
template<class VECTOR_T > | |
void | mrpt::utils::vector_strong_clear (VECTOR_T &v) |
Like calling a std::vector<>'s clear() method, but really forcing deallocating the memory. More... | |
template<typename T > | |
T | mrpt::utils::length2length4N (T len) |
Returns the smaller number >=len such that it's a multiple of 4. More... | |
Auxiliary stuff for the global profiler used in MRPT_START / MRPT_END macros. | |
void BASE_IMPEXP | mrpt::utils::global_profiler_enter (const char *func_name) MRPT_NO_THROWS |
void BASE_IMPEXP | mrpt::utils::global_profiler_leave (const char *func_name) MRPT_NO_THROWS |
#define _USE_MATH_DEFINES |
Definition at line 15 of file maps/CColouredPointsMap.h.
#define _USE_MATH_DEFINES |
#define DEG2RAD DEG2RAD |
Definition at line 99 of file maps/CColouredPointsMap.h.
Referenced by addBar_A(), ICPTests::align2scans(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::alignOpticalWithMRPTFrame(), mrpt::slam::CGridMapAligner::AlignPDF_correlation(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::opengl::CFrustum::CFrustum(), GraphSlamLevMarqTest< my_graph_t >::create_ring_path(), SE_traits_tests< POSE_TYPE >::do_all_jacobs_test(), mrpt::obs::CObservation3DRangeScan::doDepthAndIntensityCamerasCoincide(), mrpt::hwdrivers::CIMUXSens_MT4::doProcess(), mrpt::hwdrivers::CIMUXSens::doProcess(), mrpt::hwdrivers::CGyroKVHDSP3000::doProcess(), mrpt::hwdrivers::CIMUIntersense::doProcess(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::poses::CPose2D::fromString(), mrpt::math::TPose2D::fromString(), mrpt::poses::CPose3D::fromString(), mrpt::math::TPose3D::fromString(), mrpt::math::TTwist2D::fromString(), mrpt::math::TTwist3D::fromString(), ICPTests::generateObjects(), mrpt::maps::CBeacon::generateRingSOG(), mrpt::topography::geocentricToENU_WGS84(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::GeodeticToUTM(), mrpt::topography::geodeticToUTM(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::hwdrivers::CPhidgetInterfaceKitProximitySensors::getObservation(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::hwdrivers::C2DRangeFinderAbstract::loadCommonParams(), mrpt::hwdrivers::CIMUXSens_MT4::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUXSens::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserUSB::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSkeletonTracker::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIMUIntersense::loadConfig_sensorSpecific(), mrpt::hwdrivers::CRoboPeakLidar::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGyroKVHDSP3000::loadConfig_sensorSpecific(), mrpt::hwdrivers::CIbeoLuxETH::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSickLaserSerial::loadConfig_sensorSpecific(), mrpt::hwdrivers::CLMS100Eth::loadConfig_sensorSpecific(), mrpt::hwdrivers::CVelodyneScanner::loadConfig_sensorSpecific(), mrpt::hwdrivers::CSwissRanger3DCamera::loadConfig_sensorSpecific(), mrpt::hwdrivers::CGPSInterface::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2_RGBD360::loadConfig_sensorSpecific(), mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific(), mrpt::hwdrivers::CHokuyoURG::loadConfig_sensorSpecific(), mrpt::hwdrivers::CKinect::loadConfig_sensorSpecific(), mrpt::hwdrivers::CCameraSensor::loadConfig_sensorSpecific(), mrpt::slam::CICP::TConfigParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::loadFromConfigFile(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::slam::CRangeBearingKFSLAM::TOptions::loadFromConfigFile(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::loadFromConfigFile(), mrpt::hmtslam::CHMTSLAM::TOptions::loadFromConfigFile(), mrpt::hwdrivers::CTuMicos::lowerSpeedQ(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_TBI(), mrpt::slam::CRangeBearingKFSLAM2D::OnPreComputingPredictions(), mrpt::slam::CRangeBearingKFSLAM::OnPreComputingPredictions(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), mrpt::hwdrivers::CSkeletonTracker::processPreviewNone(), mrpt::hwdrivers::CTuMicos::radQuerry(), mrpt::obs::CObservation2DRangeScan::readFromStream(), mrpt::opengl::CRenderizable::readFromStreamRender(), mrpt::vision::relocalizeMultiDesc(), mrpt::opengl::COpenGLViewport::render(), mrpt::hwdrivers::CPtuDPerception::resolution(), mrpt::hwdrivers::CNTRIPClient::retrieveListOfMountpoints(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), run_test_pf_localization(), mrpt::tfest::se2_l2_robust(), mrpt::opengl::CFrustum::setHorzFOV(), mrpt::opengl::CFrustum::setHorzFOVAsymmetric(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::opengl::CFrustum::setVertFOV(), mrpt::opengl::CFrustum::setVertFOVAsymmetric(), mrpt::maps::COccupancyGridMap2D::sonarSimulator(), mrpt::maps::detail::loadFromRangeImpl< Derived >::templ_loadFromRangeScan(), TEST(), TEST_F(), mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::TMotionModelOptions(), mrpt::obs::CActionRobotMovement2D::TMotionModelOptions::TMotionModelOptions(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::TOptions(), mrpt::hmtslam::CHMTSLAM::TOptions::TOptions(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateVisuals(), and mrpt::hwdrivers::CTuMicos::upperSpeedQ().
#define DEG2RAD DEG2RAD |
#define M_PI 3.14159265358979323846 |
Definition at line 78 of file bits.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::math::CRuntimeCompiledExpression::compile(), mrpt::maps::COccupancyGridMap2D::computeClearance(), mrpt::vision::computeMainOrientations(), 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::TPolygon2D::createRegularPolygon(), mrpt::math::TPolygon3D::createRegularPolygon(), mrpt::opengl::CPolyhedron::CreateRhombicuboctahedron(), mrpt::opengl::CPolyhedron::CreateTrapezohedron(), mrpt::utils::DEG2RAD(), mrpt::nav::CHolonomicFullEval::direction2sector(), mrpt::nav::CHolonomicND::direction2sector(), mrpt::hwdrivers::CHokuyoURG::doProcessSimple(), mrpt::nav::CHolonomicFullEval::evalSingleTarget(), mrpt::opengl::detail::generalizedEllipsoidPoints< 2 >(), mrpt::opengl::detail::generalizedEllipsoidPoints< 3 >(), 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_CC::ptgDiffDriveSteeringFunction(), mrpt::nav::CPTG_DiffDrive_CCS::ptgDiffDriveSteeringFunction(), mrpt::nav::CPTG_DiffDrive_alpha::ptgDiffDriveSteeringFunction(), mrpt::nav::CPTG_DiffDrive_C::ptgDiffDriveSteeringFunction(), mrpt::utils::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().
#define MAKEWORD16B | ( | __LOBYTE, | |
__HILOBYTE | |||
) | ((__LOBYTE) | ((__HILOBYTE)<<8)) |
Definition at line 219 of file maps/CColouredPointsMap.h.
Referenced by mrpt::utils::CStream::receiveMessage(), and mrpt::utils::reduced_hash().
#define MAKEWORD16B | ( | __LOBYTE, | |
__HILOBYTE | |||
) | ((__LOBYTE) | ((__HILOBYTE)<<8)) |
#define MAKEWORD32B | ( | __LOWORD16, | |
__HIWORD16 | |||
) | ((__LOWORD16) | ((__HIWORD16)<<16)) |
Definition at line 220 of file maps/CColouredPointsMap.h.
#define MAKEWORD32B | ( | __LOWORD16, | |
__HIWORD16 | |||
) | ((__LOWORD16) | ((__HIWORD16)<<16)) |
#define MAKEWORD64B | ( | __LOWORD32, | |
__HIWORD32 | |||
) | ((__LOWORD32) | ((__HIWORD32)<<32)) |
Definition at line 221 of file maps/CColouredPointsMap.h.
#define MAKEWORD64B | ( | __LOWORD32, | |
__HIWORD32 | |||
) | ((__LOWORD32) | ((__HIWORD32)<<32)) |
#define RAD2DEG RAD2DEG |
Definition at line 100 of file maps/CColouredPointsMap.h.
Referenced by mrpt::slam::CGridMapAligner::AlignPDF_correlation(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::poses::CPose3D::asString(), mrpt::math::TPose3D::asString(), mrpt::obs::CObservationBearingRange::debugPrintOut(), mrpt::hmtslam::CLocalMetricHypothesis::dumpAsText(), mrpt::hmtslam::CHierarchicalMapMHPartition::dumpAsText(), mrpt::slam::TKLDParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderICP::TConfigParams::dumpToTextStream(), mrpt::slam::CICP::TConfigParams::dumpToTextStream(), mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::vision::TMultiResDescMatchOptions::dumpToTextStream(), mrpt::pbmap::SubgraphMatcher::evalBinaryConstraints(), mrpt::topography::geocentricToGeodetic(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::getAsString(), mrpt::nav::CPTG_DiffDrive_alpha::getDescription(), mrpt::obs::CObservationRange::getDescriptionAsText(), mrpt::obs::CObservationBearingRange::getDescriptionAsText(), mrpt::obs::CObservationIMU::getDescriptionAsText(), mrpt::obs::CObservation2DRangeScan::getDescriptionAsText(), mrpt::hwdrivers::CPtuDPerception::init(), 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::hwdrivers::CTuMicos::moveToAbsPos(), mrpt::hwdrivers::CTuMicos::moveToOffPos(), mrpt::poses::operator<<(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), mrpt::hwdrivers::CTuMicos::radAsign(), mrpt::hwdrivers::CNTRIPClient::retrieveListOfMountpoints(), mrpt::hwdrivers::CServoeNeck::setAngle(), mrpt::obs::CActionRobotMovement2D::TMotionModelOptions::TMotionModelOptions(), mrpt::hwdrivers::CHokuyoURG::turnOn(), and mrpt::topography::UTMToGeodetic().
#define RAD2DEG RAD2DEG |
Definition at line 214 of file maps/CColouredPointsMap.h.
Referenced by mrpt::utils::reduced_hash().
Definition at line 215 of file maps/CColouredPointsMap.h.
Referenced by mrpt::utils::reduced_hash().
Definition at line 216 of file maps/CColouredPointsMap.h.
Referenced by mrpt::utils::reduced_hash().
Definition at line 217 of file maps/CColouredPointsMap.h.
Referenced by mrpt::utils::reduced_hash().
Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020 |