Global Namespace
// namespaces
namespace Bonxai;
namespace Bonxai::details;
namespace TCLAP;
namespace mrpt;
namespace mrpt::apps;
namespace mrpt::bayes;
namespace mrpt::bayes::detail;
namespace mrpt::comms;
namespace mrpt::comms::net;
namespace mrpt::config;
namespace mrpt::config::internal;
namespace mrpt::containers;
namespace mrpt::containers::internal;
namespace mrpt::cpu;
namespace mrpt::cpu::internal;
namespace mrpt::detectors;
namespace mrpt::expr;
namespace mrpt::global_settings;
namespace mrpt::graphs;
namespace mrpt::graphs::detail;
namespace mrpt::graphslam;
namespace mrpt::graphslam::apps;
namespace mrpt::graphslam::deciders;
namespace mrpt::graphslam::detail;
namespace mrpt::graphslam::optimizers;
namespace mrpt::gtsam_wrappers;
namespace mrpt::gui;
namespace mrpt::gui::detail;
namespace mrpt::gui::internal;
namespace mrpt::hwdrivers;
namespace mrpt::img;
namespace mrpt::internal;
namespace mrpt::io;
namespace mrpt::io::internal;
namespace mrpt::io::zip;
namespace mrpt::kinematics;
namespace mrpt::maps;
namespace mrpt::maps::detail;
namespace mrpt::maps::internal;
namespace mrpt::maps::mrpt;
namespace mrpt::maps::mrpt::maps;
namespace mrpt::maps::mrpt::maps::COctoMapBase;
namespace mrpt::math;
namespace mrpt::math::detail;
namespace mrpt::math::internal;
namespace mrpt::nav;
namespace mrpt::obs;
namespace mrpt::obs::detail;
namespace mrpt::obs::gnss;
namespace mrpt::obs::gnss::nv_oem6_ins_status_type;
namespace mrpt::obs::gnss::nv_oem6_position_type;
namespace mrpt::obs::gnss::nv_oem6_solution_status;
namespace mrpt::obs::stock_observations;
namespace mrpt::obs::utils;
namespace mrpt::opengl;
namespace mrpt::opengl::graph_tools;
namespace mrpt::opengl::internal;
namespace mrpt::opengl::stock_objects;
namespace mrpt::poses;
namespace mrpt::poses::Lie;
namespace mrpt::poses::detail;
namespace mrpt::poses::internal;
namespace mrpt::random;
namespace mrpt::ros1bridge;
namespace mrpt::ros2bridge;
namespace mrpt::rtti;
namespace mrpt::rtti::internal;
namespace mrpt::serialization;
namespace mrpt::serialization::detail;
namespace mrpt::serialization::internal;
namespace mrpt::serialization::metaprogramming;
namespace mrpt::slam;
namespace mrpt::slam::detail;
namespace mrpt::system;
namespace mrpt::system::os;
namespace mrpt::tfest;
namespace mrpt::tfest::internal;
namespace mrpt::topography;
namespace mrpt::typemeta;
namespace mrpt::typemeta::detail;
namespace mrpt::typemeta::internal;
namespace mrpt::vision;
namespace mrpt::vision::detail;
namespace mrpt::vision::pinhole;
namespace mrpt::vision::pnp;
namespace nanoflann;
namespace nanogui;
namespace octomap;
namespace ros;
namespace sensor_msgs;
namespace std;
namespace string_literals;
namespace testing;
// typedefs
typedef std::function<void(mrpt::config::CConfigFileBase&)> config_changer_t;
typedef std::function<void(mrpt::apps::ICP_SLAM_App_Base&)> post_tester_t;
typedef std::function<void(mrpt::config::CConfigFileBase&)> config_changer_t;
typedef std::function<void(mrpt::config::CConfigFileBase&)> config_changer_t;
typedef std::function<void(mrpt::apps::MonteCarloLocalization_Base&)> post_tester_t;
typedef mrpt::apps::MonteCarloLocalization_Rawlog MCL;
typedef void(*)(mrpt::io::CFileGZInputStream&in_rawlog, TCLAP::CmdLine&cmdline, bool verbose) TOperationFunctor;
typedef std::function<void(mrpt::config::CConfigFileBase&)> config_changer_t;
typedef std::function<void(mrpt::apps::RBPF_SLAM_App_Base&)> post_tester_t;
typedef int cb_t;
typedef unsigned int data_t;
typedef mrpt::containers::vector_with_small_size_optimization<data_t, SMALL_LEN> vwsso_t;
typedef std::set<std::tuple<std::string, std::string>> in_out_filenames;
typedef GraphTester<CNetworkOfPoses2D> GraphTester2D;
typedef GraphTester<CNetworkOfPoses3D> GraphTester3D;
typedef GraphTester<CNetworkOfPoses2DInf> GraphTester2DInf;
typedef GraphTester<CNetworkOfPoses3DInf> GraphTester3DInf;
typedef struct _IplImage IplImage;
typedef std::unordered_map<std::string, XPMColorMapData> XPMColorMap;
typedef std::unordered_map<int64_t, int64_t> Long2LongHash;
typedef unsigned char boolean;
typedef JSAMPLE FAR* JSAMPROW;
typedef JSAMPROW* JSAMPARRAY;
typedef JSAMPARRAY* JSAMPIMAGE;
typedef JCOEF JBLOCK[DCTSIZE2];
typedef JBLOCK FAR* JBLOCKROW;
typedef JBLOCKROW* JBLOCKARRAY;
typedef JBLOCKARRAY* JBLOCKIMAGE;
typedef JCOEF FAR* JCOEFPTR;
typedef struct jpeg_marker_struct FAR* jpeg_saved_marker_ptr;
typedef struct jpeg_common_struct* j_common_ptr;
typedef struct jpeg_compress_struct* j_compress_ptr;
typedef struct jpeg_decompress_struct* j_decompress_ptr;
typedef struct jvirt_sarray_control* jvirt_sarray_ptr;
typedef struct jvirt_barray_control* jvirt_barray_ptr;
typedef CObservationRotatingScan RotScan;
typedef void(*)(const CSparseMatrix&M1, const CSparseMatrix&M2, CSparseMatrix&res) TMatrixSMOperator;
typedef void(*)(const CMatrixDouble&M1, const CMatrixDouble&M2, CMatrixDouble&res) TMatrixDenseOperator;
typedef double Scalar;
typedef mrpt::system::CGenericMemoryPool<CObservation3DRangeScan_Points_MemPoolParams, CObservation3DRangeScan_Points_MemPoolData> TMyPointsMemPool;
typedef mrpt::system::CGenericMemoryPool<CObservation3DRangeScan_Ranges_MemPoolParams, CObservation3DRangeScan_Ranges_MemPoolData> TMyRangesMemPool;
typedef mrpt::obs::CObservationVelodyneScan Velo;
typedef TPixelLabelInfoBase plib;
typedef struct PlyProperty PlyProperty;
typedef struct PlyElement PlyElement;
typedef mrpt::system::CGenericMemoryPool<CRenderizableShaderTexturedTriangles_MemPoolParams, CRenderizableShaderTexturedTriangles_MemPoolData> TMyMemPool;
typedef SE_traits_tests<mrpt::poses::CPose3D> SE3_traits_tests;
typedef SE_traits_tests<mrpt::poses::CPose2D> SE2_traits_tests;
typedef struct mxArray_tag mxArray;
typedef std::vector<std::vector<double>> TPoints;
typedef double precnum_t;
// enums
enum
{
PLY_START_TYPE = 0,
PLY_CHAR = 1,
PLY_SHORT = 2,
PLY_INT = 3,
PLY_UCHAR = 4,
PLY_USHORT = 5,
PLY_UINT = 6,
PLY_FLOAT = 7,
PLY_DOUBLE = 8,
PLY_END_TYPE = 9,
};
enum Directions;
enum J_COLOR_SPACE;
enum J_DCT_METHOD;
enum J_DITHER_MODE;
enum JohnsonBodyPart;
enum TestColors;
// structs
struct Bar1;
struct Bar2;
struct CAngularObservationMesh_fnctr;
struct CObject;
struct CObservation3DRangeScan_Points_MemPoolData;
struct CObservation3DRangeScan_Points_MemPoolParams;
struct CObservation3DRangeScan_Ranges_MemPoolData;
struct CObservation3DRangeScan_Ranges_MemPoolParams;
struct CRenderizableShaderTexturedTriangles_MemPoolData;
struct CRenderizableShaderTexturedTriangles_MemPoolParams;
struct CvCBCorner;
struct CvCBQuad;
struct CvContourEx;
struct FontData;
template <unsigned int INTER_SPACE>
struct Foo;
struct JHUFF_TBL;
struct JQUANT_TBL;
struct LUT_info;
struct LoadedModuleInfo;
struct MapAuxPFCleanup;
struct MapCanComputeLikelihood;
struct MapExecutor;
struct MapIsEmpty;
struct MatchingVertex;
struct ModulesRegistry;
struct MyFooClass;
struct MyGlobalProfiler;
struct PlyElement;
struct PlyFile;
struct PlyProperty;
struct SegmentVector;
struct T2ListsOfSegments;
struct TAuxLoadFunctor;
struct TAuxRangeMeasInfo;
struct TCommonRegion;
struct TDUOParams;
struct TDataPerGPS;
struct TDataPerGPSGAS;
struct TFace;
struct TFunctorLaserSimulData;
struct TGPSDataPoint;
struct TGPSGASDataPoint;
struct TGap;
struct TInfoPerSensorLabel;
struct TInterpQuery;
struct TLocalPoint;
struct TObs;
struct TOldCellTypeInVersion1;
struct TOutputRawlogCreator;
struct TParsersRegistry;
struct TSegmentWithLine;
struct TTempIntersection;
struct TVertex;
struct XPMColorMapData;
template <class T>
struct has_variance<T, std::void_t<decltype(T::variance)>>;
template <class T, class = void>
struct has_variance;
struct jpeg_common_struct;
struct jpeg_component_info;
struct jpeg_compress_struct;
struct jpeg_decompress_struct;
struct jpeg_destination_mgr;
struct jpeg_error_mgr;
struct jpeg_marker_struct;
struct jpeg_memory_mgr;
struct jpeg_progress_mgr;
struct jpeg_scan_info;
struct jpeg_source_mgr;
template <>
struct kfslam_traits<CRangeBearingKFSLAM>;
template <class IMPL>
struct kfslam_traits;
template <>
struct kfslam_traits<CRangeBearingKFSLAM2D>;
template <>
struct pf2gauss_t<CMonteCarloLocalization3D>;
template <class PDF>
struct pf2gauss_t;
template <>
struct pf2gauss_t<mrpt::slam::CMonteCarloLocalization2D>;
struct rgbRecord;
struct sort_pred;
// classes
class CAboutBox;
class CAboutBoxBase;
class CAboutBoxQt;
class CDialogAskUserForCamera;
class CDisplayWindow_WXAPP;
template <class GRAPH_T = mrpt::graphs::CNetworkOfPoses2DInf>
class CGraphSlamHandler;
class CMyRedirector;
class FAddUntracedLines;
class FCreatePolygon;
template <class T>
class FCreatePolygonFromFace;
class FUnprojectPolygon2D;
template <class my_graph_t>
class GraphSlamLevMarqTest;
template <class my_graph_t>
class GraphTester;
class ICPTests;
class KmTree;
class MD5;
class POSIT;
class Pose3DPDFGaussTests;
class Pose3DQuatPDFGaussTests;
class Pose3DQuatTests;
class Pose3DTests;
class PosePDFGaussTests;
class QuaternionTests;
template <class POSE_TYPE>
class SE_traits_tests;
class TextureResourceHandler;
class WxSubSystemGlobalData;
// global variables
const std::string gridmap1_fil = mrpt::UNITTEST_BASEDIR() + std::string("/share/mrpt/datasets/malaga-cs-fac-building.simplemap.gz");
try;
constexpr auto sect = "MappingApplication";
static auto tester_for_2006_01_21 = [](mrpt::apps::ICP_SLAM_App_Base& o) { EXPECT_EQ(o.out_estimated_path.size(), 224U); const auto p = mrpt::poses::CPose3D(o.out_estimated_path.rbegin()->second); const auto p_gt = mrpt::poses::CPose3D::FromString("[3.4548 -18.0399 0.000000 -86.48 0.000000 0.000000]"); EXPECT_LT(mrpt::poses::Lie::SE<3>::log(p - p_gt).norm(), 1.0)<<"actual pose ="<<p.asString()<<"\nexpected pose="<<p_gt.asString(); };
static bool tester_result_ok = true;
static auto tester_for_localization_demo = [](mrpt::apps::MonteCarloLocalization_Base& o) { EXPECT_EQ(o.out_estimated_path.size(), 37U); if(o.out_estimated_path.empty()) return; const mrpt::math::TPose3D p = o.out_estimated_path.rbegin()->second; const auto p_gt = mrpt::math::TPose3D::FromString("[15.89 -10.0 0.000000 4.8 0.000000 0.000000]"); const auto p_err = mrpt::poses::CPose3D(p_gt - p); const double err = mrpt::poses::Lie::SE<3>::log(p_err).norm(); if(err<0.5) { tester_result_ok = true; } else { tester_result_ok = false; std::cerr<<"Final pose mismatch(will retry N times):\n" "Expected: "<<p_gt.asString()<<"\n" "Actual : "<<p.asString()<<"\n"; } };
const std::string ini_fil = mrpt::UNITTEST_BASEDIR() + "/share/mrpt/config_files/rawlog-grabber/camera_ffmpeg_video_file.ini"s;
const std::string video_fil = mrpt::UNITTEST_BASEDIR() + "/share/mrpt/datasets/dummy_video.avi"s;
try { mrpt::apps::RawlogGrabberApp app;
const char* argv[] = {"rawlog-grabber", ini_fil.c_str()};
const int argc = sizeof(argv) / sizeof(argv[0]);
const auto out_dir = mrpt::system::getTempFileName() + "_dir"s;
constexpr auto sect = "MappingApplication";
static auto tester_for_2006_01_21 = [](mrpt::apps::RBPF_SLAM_App_Base& o) { EXPECT_EQ(o.out_estimated_path.size(), 224U); const auto p = mrpt::poses::CPose3D(o.out_estimated_path.rbegin()->second); const auto p_gt = mrpt::poses::CPose3D::FromString("[3.4548 -18.0399 0.000000 -86.48 0.000000 0.000000]"); EXPECT_LT(mrpt::poses::Lie::SE<3>::log(p - p_gt).norm(), 1.0)<<"actual pose ="<<p.asString()<<"\nexpected pose="<<p_gt.asString(); };
static auto tester_for_ROSLAM_demo = [](mrpt::apps::RBPF_SLAM_App_Base& o) { EXPECT_EQ(o.out_estimated_path.size(), 99U); const auto p = mrpt::poses::CPose3D(o.out_estimated_path.rbegin()->second); const auto p_gt = mrpt::poses::CPose3D::FromString("[1.938686 3.352273 0.000000 114.993417 0.000000 0.000000]"); EXPECT_LT(mrpt::poses::Lie::SE<3>::log(p - p_gt).norm(), 1.0)<<"actual pose ="<<p.asString()<<"\nexpected pose="<<p_gt.asString(); MRPT_TODO("Stricter unit tests: check for estimated landmark positions"); };
static int MRPT_SAVE_NAME_PADDING = 50;
static int MRPT_SAVE_VALUE_PADDING = 20;
const std::string sampleCfgTxt = "[test]\n" "key_str = this is a \\\n" "long value that can be \\\n" "split into several lines \\\n" "but read as a single line. \n";
const std::string expectedStr = std::string("this is a long value that can be split into several lines but read as a " "single line.");
const int LOADABLEOPTS_COLUMN_WIDTH = 41;
constexpr size_t SMALL_LEN = 16;
int counter = 0;
const mrpt::containers::yaml testMap = mrpt::containers::yaml::Map({{"K", 2.0}, {"book", "silmarillion"}, {"mySequence", mrpt::containers::yaml::Sequence({1.0, 2.0, mrpt::containers::yaml::Map({{"P", 1.0}, {"Q", 2.0}})})}, {"myEmptyVal", {}}, {"myDict", mrpt::containers::yaml::Map({{"A", 1.0}, {"B", 2.0}, {"C", 3.0}})}});
std::string persistent_error_msg;
const std::map<std::string, in_out_filenames> inout_graph_files { {"GraphTester2D", {{"graphslam_SE2_in.graph", "graphslam_SE2_out_good.graph"}, {"graphslam_SE2_in2.graph", "graphslam_SE2_out_good2.graph"}, {"graphslam_SE2_in3.graph", "graphslam_SE2_out_good3.graph"}}}, {"GraphTester2DInf", {{"graphslam_SE2_in.graph", "graphslam_SE2_out_good.graph"}, {"graphslam_SE2pdf_in.graph", "graphslam_SE2pdf_out_good.graph"}}}, {"GraphTester3D", {{"graphslam_SE3_in_torus3D-first100.graph", "graphslam_SE3_out_good_torus3D-first100.graph"}, {"graphslam_SE2_in2.graph", "graphslam_SE2_out_good2.graph"}}}};
const long ID_MENUITEM1 = wxNewId();
const long ID_MENUITEM2 = wxNewId();
const long ID_MENUITEM3 = wxNewId();
const long ID_MENUITEM1 = wxNewId();
const long ID_MENUITEM2 = wxNewId();
const int INVALID_CLICK_COORDS = -99999;
bool isConsoleApp_value = true;
const long ID_TIMER_WX_PROCESS_REQUESTS = wxNewId();
const char* mrpt_default_icon_xpm[];
std::map<const mrpt::hwdrivers::TCaptureOptions_DUO3D*, TDUOParams> duo_params;
const size_t MAX_NMEA_LINE_LENGTH = 1024;
const int MINIMUM_PACKETS_TO_SET_TIMESTAMP_REFERENCE = 10;
const unsigned char SearchForAF = 0;
const unsigned char SearchForFE = 1;
const unsigned char SearchForC0 = 2;
const unsigned char SearchForC2 = 3;
const unsigned char PacketFound = 4;
const unsigned char SaveData = 5;
std::vector<std::shared_ptr<COpenNI2Generic::CDevice>> vDevices;
std::recursive_mutex vDevices_mx;
string jointNames[] = { "head", "neck", "torso", "left_shoulder", "left_elbow", "left_hand", "left_hip", "left_knee", "left_foot", "right_shoulder", "right_elbow", "right_hand", "right_hip", "right_knee", "right_foot"};
static char ALawCompressTable[128] = { 1, 1, 2, 2, 3, 3, 3, 3, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7};
uint8_t table_16u_to_8u[0x10000];
bool table_16u_to_8u_init = false;
map<string, FontData> list_registered_fonts;
bool list_fonts_init = false;
static int LINUX_IMG_WIDTH_value = 800;
static int LINUX_IMG_HEIGHT_value = 600;
static bool DISABLE_JPEG_COMPRESSION_value = true;
static int SERIALIZATION_JPEG_QUALITY_value = 95;
const thread_local bool MRPT_DEBUG_IMG_LAZY_LOAD = mrpt::get_env<bool>("MRPT_DEBUG_IMG_LAZY_LOAD", false);
static const rgbRecord theRGBRecords[];
static const int numTheRGBRecords = 235;
const auto tstImgFileColor = mrpt::UNITTEST_BASEDIR() + "/samples/img_basic_example/frame_color.jpg"s;
FILE* outfile;
FILE* infile;
boolean suppress;
int val;
static const unsigned char mrpt_font_gz_10x20[];
static const unsigned char mrpt_font_gz_18x18ja[];
static const unsigned char mrpt_font_gz_5x7[];
static const unsigned char mrpt_font_gz_6x13[];
static const unsigned char mrpt_font_gz_6x13B[];
static const unsigned char mrpt_font_gz_6x13O[];
static const unsigned char mrpt_font_gz_9x15[];
static const unsigned char mrpt_font_gz_9x15B[];
const size_t tst_data_len = 1000U;
const float R = 0.01f;
const double xMin = -4.0;
const double xMax = 4.0;
const double yMin = -4.0;
const double yMax = 4.0;
const double val = 0.2;
const double sigma = 1.0;
const bool ti = true;
const bool um = false;
bool HEIGHTGRIDMAP_EXPORT3D_AS_MESH_value = true;
static const float MAX_H = 0.69314718055994531f;
static CLogOddsGridMapLUT<COccupancyGridMap2D::cellType> logodd_lut;
static CLogOddsGridMapLUT<COccupancyGridMap3D::voxelType> logodd_lut;
static constexpr unsigned FRBITS = 9;
static TAuxLoadFunctor dummy_loader;
const size_t demo9_N = 9;
const float demo9_xs[demo9_N] = {0, 0, 0, 1, 1, 1, 2, 2, 2};
const float demo9_ys[demo9_N] = {0, 1, 2, 0, 1, 2, 0, 1, 2};
const float demo9_zs[demo9_N] = {0, 1, 2, 0, 1, 2, 0, 1, 2};
static thread_local std::optional<mrpt::math::TBoundingBox> bbMemory;
double bbMemoryFading = 0.99;
const double eps = 1e-12;
static long double const sqrt_2pi = 2.506628274631000502415765284811045253006L;
static double geometryEpsilon = 1e-5;
static vector<ostream*> gLogOutputs;
static vector<ostream*> gVerboseLogOutputs;
const double dat_A[] = {4, 5, 8, -2, 1, 3};
const double dat_B[] = {2, 6, 9, 8};
const double dat_Cok[] = {53, 64, -2, 32, 29, 30};
static double test_nums[3 *4] = { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12};
const double eps = 1e-14;
const double eps = 1e-9;
const double list_test_kernel_none[][5] = { {0.0, .0, 0.0, 1.0, 0.0}, {1.0, .0, 1.0, 1.0, 0.0}, {10.0, .0, 10.0, 1.0, 0.0}};
const double list_test_kernel_pshb[][5] = { {0.0, 1.0, 0.0, 1.0, -0.5}, {0.0, 4.0, 0.0, 1.0, -0.125}, {0.0, 9.0, 0.0, 1.0, -0.0555556}, {1.0, 1.0, 0.828427, 0.707107, -0.176777}, {1.0, 4.0, 0.944272, 0.894427, -0.0894427}, {1.0, 9.0, 0.973666, 0.948683, -0.0474342}, {4.0, 1.0, 2.47214, 0.447214, -0.0447214}, {4.0, 4.0, 3.31371, 0.707107, -0.0441942}, {4.0, 9.0, 3.63331, 0.83205, -0.0320019}};
CAbstractHolonomicReactiveMethod;
mrpt::nav const unsigned NUM_FACTORS = 7U;
const double PREVIOUS_POSES_MAX_AGE = 20;
const mrpt::rtti::TRuntimeClassId* lstClasses[] = { CLASS_ID(CLogFileRecord), };
static IMPLEMENTS_VIRTUAL_SERIALIZABLE(CParameterizedTrajectoryGenerator, CSerializable, mrpt::nav) static std PTG_collision_behavior_t COLLISION_BEHAVIOR = mrpt::nav::COLL_BEH_BACK_AWAY;
const uint32_t COLGRID_FILE_MAGIC = 0xC0C0C0C3;
static std::unordered_map<LUT_info, CObservation3DRangeScan::unproject_LUT_t> LUTs;
static std::mutex LUTs_mtx;
static bool EXTERNALS_AS_TEXT_value = false;
constexpr unsigned int TEST_RANGEIMG_WIDTH = 32;
constexpr unsigned int TEST_RANGEIMG_HEIGHT = 24;
constexpr float SECOND_LAYER_CONSTANT_RANGE = 50.0f;
static CSinCosLookUpTableFor2DScans velodyne_sincos_tables;
const float VLP16_BLOCK_TDURATION = 110.592f;
const float VLP16_DSR_TOFFSET = 2.304f;
const float VLP16_FIRING_TOFFSET = 55.296f;
const double HDR32_DSR_TOFFSET = 1.152;
const double HDR32_FIRING_TOFFSET = 46.08;
const mrpt::rtti::TRuntimeClassId* lstClasses[] = { CLASS_ID(CObservation2DRangeScan), CLASS_ID(CObservation3DRangeScan), CLASS_ID(CObservation3DScene), CLASS_ID(CObservationRGBD360), CLASS_ID(CObservationBearingRange), CLASS_ID(CObservationBatteryState), CLASS_ID(CObservationWirelessPower), CLASS_ID(CObservationRFID), CLASS_ID(CObservationBeaconRanges), CLASS_ID(CObservationComment), CLASS_ID(CObservationGasSensors), CLASS_ID(CObservationGPS), CLASS_ID(CObservationReflectivity), CLASS_ID(CObservationIMU), CLASS_ID(CObservationOdometry), CLASS_ID(CObservationRange), CLASS_ID(CObservationImage), CLASS_ID(CObservationStereoImages), CLASS_ID(CObservationCANBusJ1939), CLASS_ID(CObservationRawDAQ), CLASS_ID(CObservation6DFeatures), CLASS_ID(CObservationVelodyneScan), CLASS_ID(CActionRobotMovement2D), CLASS_ID(CActionRobotMovement3D)};
const auto fn_pair_make_unique = [](auto& ptr) { ptr.pose.reset(dynamic_cast<mrpt::poses::CPose3DPDF*>(ptr.pose->clone())); ptr.sf.reset(dynamic_cast<mrpt::obs::CSensoryFrame*>(ptr.sf->clone())); };
static const unsigned char sample_image1[];
static const unsigned char sample_image2[];
const char* velodyne_default_calib_HDL32;
const char* velodyne_default_calib_HDL64E_S3_part1;
const char* velodyne_default_calib_HDL64E_S3_part2;
const std::string velodyne_default_calib_HDL64E_S3 = std::string(velodyne_default_calib_HDL64E_S3_part1) + std::string(velodyne_default_calib_HDL64E_S3_part2);
const char* velodyne_default_calib_VLP16;
static std::map<std::string, VelodyneCalibration> cache_default_calibs;
const thread_local bool MRPT_FBORENDER_SHOW_DEVICES = mrpt::get_env<bool>("MRPT_FBORENDER_SHOW_DEVICES");
const thread_local bool MRPT_FBORENDER_USE_LUT = mrpt::get_env<bool>("MRPT_FBORENDER_USE_LUT", true);
static math::TPolygon3D tmpPoly (3);
static const uint8_t grid_line_indices[] = {0, 1, 1, 2, 2, 3, 3, 0, 4, 5, 5, 6, 6, 7, 7, 4, 0, 5, 1, 6, 2, 7, 3, 4};
static const uint8_t cube_indices[2 *6 *3] = { 0, 1, 2, 0, 2, 3, 3, 4, 0, 4, 5, 0, 0, 5, 6, 6, 1, 0, 1, 6, 7, 7, 2, 1, 7, 3, 4, 2, 3, 7, 4, 7, 6, 5, 6, 4};
static const mrpt::math::TPoint3Df normals_cube[6 *2] = { {1, 0, 0}, {1, 0, 0}, {0, 1, 0}, {0, 1, 0}, {0, 0, 1}, {0, 0, 1}, {0, -1, 0}, {0, -1, 0}, {0, 0, -1}, {0, 0, -1}, {-1, 0, 0}, {-1, 0, 0}};
float OCTREE_RENDER_MAX_DENSITY_POINTS_PER_SQPIXEL_value = 0.10f;
size_t OCTREE_RENDER_MAX_POINTS_PER_NODE_value = 1e6;
constexpr double text_spacing = 1.5;
constexpr double text_kerning = 0.1;
Point mono_vertices[];
Font::Index mono_triangles[];
Font::Index mono_lines[];
Font::Char mono_chars[];
Font mono_font = { mono_vertices, mono_triangles, mono_lines, mono_chars, " $(,048<@DHLPTX\\`dhlptx|#'+/" "37;?CGKOSW[_cgkosw{\"&*.26:>BFJNRVZ^bfjnrvz~\t!%)-159=" "AEIMQUY]aeimquy}"};
Point sans_vertices[];
Font::Index sans_triangles[];
Font::Index sans_lines[];
Font::Char sans_chars[];
Font sans_font = { sans_vertices, sans_triangles, sans_lines, sans_chars, " $(,048<@DHLPTX\\`dhlptx|#'+/" "37;?CGKOSW[_cgkosw{\"&*.26:>BFJNRVZ^bfjnrvz~\t!%)-159=" "AEIMQUY]aeimquy}"};
Point serif_vertices[];
Font::Index serif_triangles[];
Font::Index serif_lines[];
Font::Char serif_chars[];
Font serif_font = { serif_vertices, serif_triangles, serif_lines, serif_chars, " $(,048<@DHLPTX\\`dhlptx|#'+/" "37;?CGKOSW[_cgkosw{\"&*.26:>BFJNRVZ^bfjnrvz~\t!%)-159=" "AEIMQUY]aeimquy}"};
const int NO_OTHER_PROPS = -1;
const char DONT_STORE_PROP = 0;
const char STORE_PROP = 1;
const char OTHER_PROP = 0;
const char NAMED_PROP = 1;
const std::string type_names[] = { string("invalid"), string("char"), string("short"), string("int"), string("uchar"), string("ushort"), string("uint"), string("float"), string("double"), };
const int ply_type_size[] = {0, 1, 2, 4, 1, 2, 4, 4, 8};
const float VAL_NOT_SET = -1e10;
const PlyProperty vert_props[] = { {"x", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, x), 0, 0, 0, 0}, {"y", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, y), 0, 0, 0, 0}, {"z", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, z), 0, 0, 0, 0}, {"intensity", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, intensity), 0, 0, 0, 0}};
const PlyProperty face_props[] = { {"intensity", PLY_FLOAT, PLY_FLOAT, offsetof(TFace, intensity), 0, 0, 0, 0}, {"vertex_indices", PLY_INT, PLY_INT, offsetof(TFace, verts), 1, PLY_UCHAR, PLY_UCHAR, offsetof(TFace, nverts)}};
const double POSE_TAIL_LENGTH = 0.1;
const double POSE_TAIL_WIDTH = 3.0;
const float POSE_POINT_SIZE = 4.0f;
const float POSE_AXIS_SCALE = 0.1f;
const bool MRPT_OPENGL_VERBOSE = mrpt::get_env<bool>("MRPT_OPENGL_VERBOSE", false);
const bool MRPT_OPENGL_DEBUG_SHOW_SHADOW_MAP = mrpt::get_env<bool>("MRPT_OPENGL_DEBUG_SHOW_SHADOW_MAP", false);
static const std::vector<mrpt::poses::CPose3D> ptc = { {.0, .0, .0, .0_deg, .0_deg, .0_deg}, {1.0, 2.0, 3.0, .0_deg, .0_deg, .0_deg}, {1.0, 2.0, 3.0, 10.0_deg, .0_deg, .0_deg}, {1.0, 2.0, 3.0, .0_deg, 1.0_deg, .0_deg}, {1.0, 2.0, 3.0, .0_deg, .0_deg, 1.0_deg}, {1.0, 2.0, 3.0, 80.0_deg, 5.0_deg, 5.0_deg}, {1.0, 2.0, 3.0, -20.0_deg, -30.0_deg, -40.0_deg}, {1.0, 2.0, 3.0, -45.0_deg, 10.0_deg, 70.0_deg}, {1.0, 2.0, 3.0, 40.0_deg, -5.0_deg, 25.0_deg}, {1.0, 2.0, 3.0, 40.0_deg, 20.0_deg, -15.0_deg}, {-6.0, 2.0, 3.0, 40.0_deg, 20.0_deg, 15.0_deg}, {6.0, -5.0, 3.0, 40.0_deg, 20.0_deg, 15.0_deg}, {6.0, 2.0, -9.0, 40.0_deg, 20.0_deg, 15.0_deg}, {0.0, 8.0, 5.0, -45.0_deg, 10.0_deg, 70.0_deg}, {1.0, 0.0, 5.0, -45.0_deg, 10.0_deg, 70.0_deg}, {1.0, 8.0, 0.0, -45.0_deg, 10.0_deg, 70.0_deg}};
bool USE_SUT_QUAT2EULER_CONVERSION_value = false;
const auto bb_min = mrpt::math::TPose3D(1, 2, 3, -20.0_deg, -30.0_deg, -40.0_deg);
const auto bb_max = mrpt::math::TPose3D(3, 4, 5, 20.0_deg, 30.0_deg, 40.0_deg);
bool USE_SUT_EULER2QUAT_CONVERSION_value = false;
static const std::vector<mrpt::poses::CPose3D> ptc = { {.0, .0, .0, .0_deg, .0_deg, .0_deg}, {1.0, 2.0, 3.0, .0_deg, .0_deg, .0_deg}, {1.0, 2.0, 3.0, 10.0_deg, .0_deg, .0_deg}, {1.0, 2.0, 3.0, .0_deg, 1.0_deg, .0_deg}, {1.0, 2.0, 3.0, .0_deg, .0_deg, 1.0_deg}, {-6.0, 2.0, 3.0, 40.0_deg, 20.0_deg, 15.0_deg}, {1.0, 8.0, 0.0, -45.0_deg, 10.0_deg, 70.0_deg}, {1.0, 2.0, 3.0, 89.0_deg, .5_deg, 1.0_deg}, {1.0, -2.0, 0.4, -89.0_deg, .5_deg, 1.0_deg}, {1.0, 2.0, 3.0, .1_deg, 89.0_deg, 1.0_deg}, {1.0, -2.0, 0.4, .1_deg, -88.0_deg, 1.0_deg}, {1.0, 2.0, 3.0, .1_deg, .9_deg, 178.0_deg}, {1.0, -2.0, 0.4, .1_deg, .9_deg, -179.1_deg}, };
static thread_local CRandomGenerator randomGenerator;
const uint8_t SERIALIZATION_END_FLAG = 0x88;
const size_t NUM_OBSERVATIONS_TO_SIMUL = 15;
const size_t RANSAC_MINIMUM_INLIERS = 9;
const float normalizationStd = 0.10f;
const float ransac_mahalanobisDistanceThreshold = 5.0f;
const size_t MINIMUM_RANSAC_ITERS = 100000;
const size_t NUM_MAP_FEATS = 50;
const double MAP_SIZE_X = 30;
const double MAP_SIZE_Y = 15;
const unsigned char alphabet[64+1] = "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/";
static std::array<mrpt::system::ConsoleForegroundColor, NUMBER_OF_VERBOSITY_LEVELS> logging_levels_to_colors = { ConsoleForegroundColor::BLUE, ConsoleForegroundColor::DEFAULT, ConsoleForegroundColor::GREEN, ConsoleForegroundColor::RED };
static std::array<std::string, NUMBER_OF_VERBOSITY_LEVELS> logging_levels_to_names = { "DEBUG", "INFO ", "WARN ", "ERROR" };
static MyGlobalProfiler global_profiler;
const char* sLicenseTextF = " Mobile Robot Programming Toolkit(MRPT) " " \n" " https://www.mrpt.org/ " " " " \n" " " " \n" " Copyright(c) 2005-%Y, Individual contributors, see AUTHORS file " "\n" " See: https://www.mrpt.org/Authors - All rights reserved. " " " " \n" " Released under BSD License. See details in https://www.mrpt.org/License " " " " \n";
static std::condition_variable cv2;
static std::mutex cv_m;
static std::mutex cv2_m;
static std::atomic<int> thrCnt = 0;
static std::atomic<int> thrDone = 0;
static const std::string sNewName = "NewName";
mrpt::vision::TCalibrationStereoImageList images { using namespace std::string_literals;
mrpt::vision::TStereoCalibParams params;
mrpt::vision::TStereoCalibResults out;
const auto dir = mrpt::UNITTEST_BASEDIR() + "/share/mrpt/datasets/stereo-calib/"s;
const unsigned int NUM_IMGS = 4;
params check_size_x = 6;
params check_size_y = 9;
params optimize_k1 = true;
params optimize_k2 = true;
params optimize_k3 = true;
params optimize_t1 = true;
params optimize_t2 = true;
params check_squares_length_X_meters = 0.034;
params check_squares_length_Y_meters = 0.034;
params verbose = false;
bool ok = mrpt::vision::checkerBoardStereoCalibration(images, params, out);
mrpt::pimpl<Impl> m_video;
const int FEAT_FREE = -1;
// global functions
EXPECT_TRUE(mrpt::system::fileExists(ini_fil));
EXPECT_TRUE(mrpt::system::fileExists(gridmap1_fil));
catch(const std::exception& e);
template <class SLAM_CLASS>
void generic_icp_slam_test(
const std::string& ini_filename,
const std::string& rawlog_filename,
config_changer_t cfg_changer,
post_tester_t post_tester
);
TEST(
ICP_SLAM_App,
MapFromRawlog_PointMap
);
TEST(
ICP_SLAM_App,
MapFromRawlog_Grid
);
TEST(
ICP_SLAM_App,
MapFromRawlog_LM
);
void generic_kf_slam_test(
const std::string& ini_filename,
const std::string& rawlog_filename,
config_changer_t cfg_changer
);
TEST(
KFSLAMApp,
EKF_SLAM_3D
);
TEST(
KFSLAMApp,
EKF_SLAM_2D
);
TEST(
KFSLAMApp,
EKF_SLAM_3D_data_assoc_JCBB_Maha
);
TEST(
KFSLAMApp,
EKF_SLAM_3D_data_assoc_NN_Maha
);
void generic_pf_test(
const std::string& ini_filename,
const std::string& rawlog_filename,
const std::string& map_filename,
config_changer_t cfg_changer,
post_tester_t post_tester
);
TEST(
MonteCarloLocalization_Rawlog,
RunForSampleDataset_2D
);
TEST(
MonteCarloLocalization_Rawlog,
RunForSampleDataset_3D
);
template <typename T>
bool getArgValue(
TCLAP::CmdLine& cmdline,
const std::string& arg_name,
T& out_val
);
bool isFlagSet(
TCLAP::CmdLine& cmdline,
const std::string& arg_name
);
DECLARE_OP_FUNCTION(op_export_txt);
DECLARE_OP_FUNCTION(op_export_2d_scans_txt);
DECLARE_OP_FUNCTION(op_export_txt);
DECLARE_OP_FUNCTION(op_export_anemometer_txt);
DECLARE_OP_FUNCTION(op_camera_params);
DECLARE_OP_FUNCTION(op_cut);
DECLARE_OP_FUNCTION(op_deexternalize);
DECLARE_OP_FUNCTION(op_describe);
DECLARE_OP_FUNCTION(op_export_enose_txt);
DECLARE_OP_FUNCTION(op_export_txt);
DECLARE_OP_FUNCTION(op_externalize);
DECLARE_OP_FUNCTION(op_remove_label);
DECLARE_OP_FUNCTION(op_keep_label);
DECLARE_OP_FUNCTION(op_generate_3d_pointclouds);
DECLARE_OP_FUNCTION(op_export_gps_kml);
DECLARE_OP_FUNCTION(op_export_gps_txt);
DECLARE_OP_FUNCTION(op_export_gps_all);
DECLARE_OP_FUNCTION(op_export_gps_gas_kml);
DECLARE_OP_FUNCTION(op_export_txt);
DECLARE_OP_FUNCTION(op_export_imu_txt);
DECLARE_OP_FUNCTION(op_info);
DECLARE_OP_FUNCTION(op_list_images);
DECLARE_OP_FUNCTION(op_list_poses);
DECLARE_OP_FUNCTION(op_list_rangebearing);
DECLARE_OP_FUNCTION(op_list_timestamps);
DECLARE_OP_FUNCTION(op_export_txt);
DECLARE_OP_FUNCTION(op_export_odometry_txt);
DECLARE_OP_FUNCTION(op_recalc_odometry);
DECLARE_OP_FUNCTION(op_export_rawdaq_txt);
DECLARE_OP_FUNCTION(op_remap_timestamps);
DECLARE_OP_FUNCTION(op_rename_externals);
DECLARE_OP_FUNCTION(op_sensors_pose);
DECLARE_OP_FUNCTION(op_stereo_rectify);
DECLARE_OP_FUNCTION(op_undistort);
DECLARE_OP_FUNCTION(op_camera_params);
DECLARE_OP_FUNCTION(op_cut);
DECLARE_OP_FUNCTION(op_deexternalize);
DECLARE_OP_FUNCTION(op_describe);
DECLARE_OP_FUNCTION(op_export_gps_all);
DECLARE_OP_FUNCTION(op_export_gps_gas_kml);
DECLARE_OP_FUNCTION(op_export_gps_kml);
DECLARE_OP_FUNCTION(op_export_enose_txt);
DECLARE_OP_FUNCTION(op_export_gps_txt);
DECLARE_OP_FUNCTION(op_export_rawdaq_txt);
DECLARE_OP_FUNCTION(op_export_txt);
DECLARE_OP_FUNCTION(op_export_2d_scans_txt);
DECLARE_OP_FUNCTION(op_export_anemometer_txt);
DECLARE_OP_FUNCTION(op_export_imu_txt);
DECLARE_OP_FUNCTION(op_export_odometry_txt);
DECLARE_OP_FUNCTION(op_externalize);
DECLARE_OP_FUNCTION(op_generate_3d_pointclouds);
DECLARE_OP_FUNCTION(op_info);
DECLARE_OP_FUNCTION(op_keep_label);
DECLARE_OP_FUNCTION(op_list_images);
DECLARE_OP_FUNCTION(op_list_poses);
DECLARE_OP_FUNCTION(op_list_rangebearing);
DECLARE_OP_FUNCTION(op_list_timestamps);
DECLARE_OP_FUNCTION(op_recalc_odometry);
DECLARE_OP_FUNCTION(op_remap_timestamps);
DECLARE_OP_FUNCTION(op_remove_label);
DECLARE_OP_FUNCTION(op_rename_externals);
DECLARE_OP_FUNCTION(op_sensors_pose);
DECLARE_OP_FUNCTION(op_stereo_rectify);
DECLARE_OP_FUNCTION(op_undistort);
TCLAP::CmdLine cmd(
"rawlog-edit",
' ',
mrpt::format("%s - Sources timestamp: %s\n", MRPT_getVersion().c_str(), MRPT_getCompilationDate().c_str())
);
TCLAP::ValueArg<std::string> arg_input_file(
"i",
"input",
"Input dataset(required)(*.rawlog)",
true,
"",
"dataset.rawlog",
cmd
);
TCLAP::ValueArg<std::string> arg_output_file(
"o",
"output",
"Output dataset(*.rawlog)",
false,
"",
"dataset_out.rawlog",
cmd
);
TCLAP::ValueArg<std::string> arg_plugins(
"p",
"plugins",
"Single or comma-separated list of .so/.dll plugins to load for additional " "user-supplied classes",
false,
"",
"mylib.so",
cmd
);
TCLAP::ValueArg<std::string> arg_outdir(
"",
"out-dir",
"Output directory(used by some commands only)",
false,
".",
".",
cmd
);
TCLAP::ValueArg<std::string> arg_external_img_extension(
"",
"image-format",
"External image format",
false,
"png",
" jpg,
png,
pgm,
...",
cmd
);
TCLAP::ValueArg<std::string> arg_externals_filename_fmt(
"",
"externals-filename-format",
"Format string for the command --rename-externals." "(Default: \"${type}_${label}_%.06%f\"). Refer to docs for " "mrpt::obs::format_externals_filename().",
false,
"\"${type}_${label}_%.06%f\"",
"\"${type}_${label}_%.06%f\"",
cmd
);
TCLAP::SwitchArg arg_txt_externals(
"",
"txt-externals",
"When externalizing CObservation3DRangeScan objects,
switched from binary " "files(default) to plain text.",
cmd,
false
);
TCLAP::ValueArg<std::string> arg_img_size(
"",
"image-size",
"Resize output images",
false,
"",
"COLSxROWS",
cmd
);
TCLAP::SwitchArg arg_rectify_centers(
"",
"rectify-centers-coincide",
"In stereo rectification,
force that both image centers after coincide " "after rectifying.",
cmd,
false
);
TCLAP::ValueArg<std::string> arg_out_text_file(
"",
"text-file-output",
"Output for a text file",
false,
"out.txt",
"out.txt",
cmd
);
TCLAP::ValueArg<uint64_t> arg_from_index(
"",
"from-index",
"Starting index for --cut",
false,
0,
"N0",
cmd
);
TCLAP::ValueArg<uint64_t> arg_to_index(
"",
"to-index",
"End index for --cut",
false,
0,
"N1",
cmd
);
TCLAP::ValueArg<double> arg_from_time(
"",
"from-time",
"Starting time for -- cut,
as UNIX timestamp,
optionally with fractions of " "seconds.",
false,
0,
"T0",
cmd
);
TCLAP::ValueArg<double> arg_to_time(
"",
"to-time",
"End time for -- cut,
as UNIX timestamp,
optionally with fractions of " "seconds.",
false,
0,
"T1",
cmd
);
TCLAP::ValueArg<double> arg_odo_KL(
"",
"odo-KL",
"Constant from encoder ticks to meters left wheel,
used in " "--recalc-odometry.",
false,
0,
"KL",
cmd
);
TCLAP::ValueArg<double> arg_odo_KR(
"",
"odo-KR",
"Constant from encoder ticks to meters right wheel,
used in " "--recalc-odometry.",
false,
0,
"KR",
cmd
);
TCLAP::ValueArg<double> arg_odo_D(
"",
"odo-D",
"Distance between left-right wheels meters,
used in --recalc-odometry.",
false,
0,
"D",
cmd
);
TCLAP::SwitchArg arg_overwrite(
"w",
"overwrite",
"Force overwrite target file without prompting.",
cmd,
false
);
TCLAP::ValueArg<std::string> arg_select_label(
"",
"select-label",
"Select one sensor label on which to apply the operation.\n" "Several labels can be provided separated by commas.\n" "Only for those ops that mention --select-label as optional.",
false,
"",
"label" [, label...],
cmd
);
TCLAP::SwitchArg arg_quiet(
"q",
"quiet",
"Terse output",
cmd,
false
);
bool isFlagSet(
TCLAP::CmdLine& cmdline,
const std::string& arg_name
);
template <typename T>
bool getArgValue(
TCLAP::CmdLine& cmdline,
const std::string& arg_name,
T& out_val
);
template bool getArgValue(
TCLAP::CmdLine& cmdline,
const std::string& arg_name,
std::string& out_val
);
template bool getArgValue(
TCLAP::CmdLine& cmdline,
const std::string& arg_name,
double& out_val
);
template bool getArgValue(
TCLAP::CmdLine& cmdline,
const std::string& arg_name,
size_t& out_val
);
template bool getArgValue(
TCLAP::CmdLine& cmdline,
const std::string& arg_name,
int& out_val
);
EXPECT_TRUE(mrpt::system::fileExists(ini_fil));
EXPECT_TRUE(mrpt::system::fileExists(video_fil));
app setMinLoggingLevel(mrpt::system::LVL_ERROR);
app initialize(
argc,
argv
);
void generic_rbpf_slam_test(
const std::string& ini_filename,
const std::string& rawlog_filename,
config_changer_t cfg_changer,
post_tester_t post_tester
);
TEST(
RBPF_SLAM_App,
MapFromRawlog_Lidar2D_optimal_sampling
);
TEST(
RBPF_SLAM_App,
MapFromRawlog_Lidar2D_gridICP
);
TEST(
RBPF_SLAM_App,
MapFromRawlog_Lidar2D_pointsICP
);
TEST(
RBPF_SLAM_App,
MapFromRawlog_ROSLAM_MC
);
TEST(
RBPF_SLAM_App,
MapFromRawlog_ROSLAM_SOG
);
MRPT_INITIALIZER(registerAllClasses_mrpt_apps);
MRPT_INITIALIZER(registerAllClasses_mrpt_detectors);
MRPT_INITIALIZER(registerAllClasses_mrpt_graphs);
MRPT_INITIALIZER(registerAllClasses_mrpt_gui);
MRPT_INITIALIZER(registerAllClasses_mrpt_hwdrivers);
MRPT_INITIALIZER(registerAllClasses_mrpt_img);
MRPT_INITIALIZER(registerAllClasses_mrpt_kinematics);
MRPT_INITIALIZER(registerAllClasses_mrpt_maps);
MRPT_INITIALIZER(registerAllClasses_mrpt_math);
MRPT_INITIALIZER(registerAllClasses_mrpt_nav);
MRPT_INITIALIZER(registerAllClasses_mrpt_obs);
MRPT_INITIALIZER(registerAllClasses_mrpt_opengl);
MRPT_INITIALIZER(registerAllClasses_mrpt_poses);
MRPT_INITIALIZER(registerAllClasses_mrpt_slam);
MRPT_INITIALIZER(registerAllClasses_mrpt_tfest);
MRPT_INITIALIZER(registerAllClasses_mrpt_topography);
MRPT_INITIALIZER(registerAllClasses_mrpt_vision);
MRPT_FILL_ENUM(kfEKFNaive);
MRPT_FILL_ENUM(kfEKFAlaDavison);
MRPT_FILL_ENUM(kfIKFFull);
MRPT_FILL_ENUM(kfIKF);
MRPT_FILL_ENUM_MEMBER(
mrpt::bayes::CParticleFilter,
pfStandardProposal
);
MRPT_FILL_ENUM_MEMBER(
mrpt::bayes::CParticleFilter,
pfAuxiliaryPFOptimal
);
MRPT_FILL_ENUM_MEMBER(
mrpt::bayes::CParticleFilter,
pfAuxiliaryPFStandard
);
MRPT_FILL_ENUM_MEMBER(
mrpt::bayes::CParticleFilter,
pfOptimalProposal
);
MRPT_FILL_ENUM_MEMBER(
mrpt::bayes::CParticleFilter,
prMultinomial
);
MRPT_FILL_ENUM_MEMBER(
mrpt::bayes::CParticleFilter,
prResidual
);
MRPT_FILL_ENUM_MEMBER(
mrpt::bayes::CParticleFilter,
prStratified
);
MRPT_FILL_ENUM_MEMBER(
mrpt::bayes::CParticleFilter,
prSystematic
);
project(ALL_MRPT_LIBS);
TEST(
NodeletsTests,
pub_sub_multithread_test
);
TEST(
SocketTests,
send_receive_object
);
static std::string local_file_get_contents(const std::string& fileName);
TEST(
CConfigFileMemory,
readwrite
);
TEST(
CConfigFileMemory,
Sections
);
TEST(
CConfigFileMemory,
Names
);
TEST(
CConfigFileMemory,
setFromString
);
TEST(
CConfigFileMemory,
readMultiLineStrings
);
TEST(
CConfigFile,
readMultiLineStrings
);
TEST(
CConfigFileMemory,
parseVariables
);
TEST(
bimap,
operations
);
TEST(
CDynamicGrid,
GetSetAndResize
);
TEST(
CDynamicGrid,
rangeForLoop
);
TEST(
circular_buffer_tests,
EmptyPop
);
TEST(
circular_buffer_tests,
EmptyPopAfterPushes
);
TEST(
circular_buffer_tests,
RandomWriteAndPeek
);
TEST(
circular_buffer_tests,
RandomWriteManyAndPeek
);
TEST(
circular_buffer_tests,
RandomWriteAndPeekOverrun
);
TEST(
circular_buffer_tests,
Size
);
template <typename T>
void impl_WritePeekCheck();
TEST(
circular_buffer_tests,
WritePeekCheck_uint8_t
);
TEST(
circular_buffer_tests,
WritePeekCheck_uint16_t
);
TEST(
circular_buffer_tests,
WritePeekCheck_uint32_t
);
TEST(
circular_buffer_tests,
WritePeekCheck_uint64_t
);
TEST(
find_closest,
testStdMap
);
TEST(
find_closest,
testStdMultiMap
);
TEST(
find_closest_with_tolerance,
testStdMap
);
TEST(
copy_ptr,
SimpleOps
);
TEST(
copy_ptr,
StlContainer
);
TEST(
poly_ptr,
SimpleOps
);
TEST(
poly_ptr,
StlContainer
);
template <typename T>
void simple_test_hash_string();
TEST(
ts_hash_map,
string_hash_u8
);
TEST(
ts_hash_map,
string_hash_u16
);
TEST(
ts_hash_map,
string_hash_u32
);
TEST(
ts_hash_map,
string_hash_u64
);
TEST(
ts_hash_map,
stdstring_key
);
TEST(
vector_with_small_size_optimization,
Empty
);
TEST(
vector_with_small_size_optimization,
ResizeSize
);
TEST(
vector_with_small_size_optimization,
ResizeWriteRead
);
TEST(
vector_with_small_size_optimization,
ResizeWriteReadIterators
);
TEST(
vector_with_small_size_optimization,
GrowCheckContents
);
TEST(
vector_with_small_size_optimization,
ShrinkCheckContents
);
TEST(
vector_with_small_size_optimization,
GrowCheckFrontBack
);
TEST(
vector_with_small_size_optimization,
push_back
);
TEST(
containers_visit_each,
call_all
);
static std::string shortenComment(const std::optional<std::string>& c);
static void internalPrintRightComment(
std::ostream& o,
const std::string& c
);
static yaml::scalar_t textToScalar(const std::string& s);
static std::string local_file_get_contents(const std::string& fileName);
const yaml::node_t& findKeyNode(
const yaml::node_t* me,
const std::string& key
);
MRPT_TEST(
yaml,
emptyCtor
);
MRPT_TEST(
yaml,
assignments
);
MRPT_TEST(
yaml,
initializers
);
MRPT_TEST(
yaml,
initializerMap
);
MRPT_TEST(
yaml,
initializerSequence
);
MRPT_TEST(
yaml,
nested
);
MRPT_TEST(
yaml,
nested2
);
MRPT_TEST(
yaml,
printYAML
);
MRPT_TEST(
yaml,
printDebugStructure
);
MRPT_TEST(
yaml,
ctorMap
);
MRPT_TEST(
yaml,
comments
);
MRPT_TEST(
yaml,
iterate
);
MRPT_TEST(
yaml,
macros
);
MRPT_TEST(
yaml,
hexadecimal
);
void foo(mrpt::containers::yaml& p);
MRPT_TEST(
yaml,
assignmentsInCallee
);
template <class Dest, class Source>
Dest bit_cast(const Source& source);
template <
std::size_t alignment,
typename T,
typename = std::enable_if_t<std::is_pointer<T>::value>
>
bool my_is_aligned(T ptr);
TEST(
aligned_allocator,
aligned_malloc
);
TEST(
aligned_allocator,
aligned_calloc
);
TEST(
bits_math,
sign
);
TEST(
bits_math,
keep_min
);
TEST(
bits_math,
keep_max
);
TEST(
bits_math,
round2up
);
TEST(
bits_math,
hypot_fast
);
TEST(
bits_math,
deg_rad
);
TEST(
bits_math,
signWithZero
);
TEST(
bits_math,
abs_diff
);
TEST(
bits_math,
min3
);
TEST(
bits_math,
max3
);
TEST(
bits_math,
fix
);
TEST(
bits_math,
saturate_val
);
TEST(
bits_math,
saturate
);
TEST(
bits_math,
lowestPositive
);
uint64_t as_nanoseconds(const struct timespec& ts);
void from_nanoseconds(
const uint64_t ns,
struct timespec& ts
);
static uint64_t to100ns(const timespec& tim);
static uint64_t getCurrentTime();
static void test_delay();
TEST(
clock,
delay_Realtime
);
TEST(
clock,
changeSource
);
TEST(
clock,
checkSynchEpoch
);
TEST(
clock,
simulatedTime
);
TEST(
constexpr_for,
compileTest
);
TEST(
cpu,
features_as_string
);
TEST(
cpu,
supports
);
TEST(
exception,
stackedExceptionBasic
);
template <typename T>
void test_except_3rd_lvl(T val);
void test_except_2nd_lvl();
void test_except_toplevel();
TEST(
exception,
stackedExceptionComplex
);
TEST(
exception,
assertException
);
static std::string testFoo();
TEST(
exception,
infiniteRecurseBug
);
TEST(
exception,
assertMacros
);
TEST(
FormatTest,
LargeStrings
);
TEST(
FormatTest,
ToString
);
TEST(
FromStringTests,
Basic
);
TEST(
is_defined,
tests1
);
TEST(
lock_helper,
testCompilation
);
template <typename T>
void reverseBytesInPlace_2b(T& v_in_out);
template <typename T>
void reverseBytesInPlace_4b(T& v_in_out);
template <typename T>
void reverseBytesInPlace_8b(T& v_in_out);
TEST(
bits,
reverseBytes
);
TEST(
round,
longRound
);
static void mySetThreadName(
const std::string& name,
std::thread& theThread
);
TEST(
WorkerThreadsPool,
runTasks
);
IMPLEMENTS_VIRTUAL_SERIALIZABLE(
CDetectableObject,
CSerializable,
mrpt::detectors
);
TEST(
RuntimeCompiledExpression,
SimpleTest
);
static double myNullary();
static double myNeg(double x);
static double myAdd(
double x,
double y
);
static double myDiff(
double x,
double y,
double z
);
TEST(
RuntimeCompiledExpression,
CustomFunctions
);
MRPT_FILL_ENUM(featNotDefined);
MRPT_FILL_ENUM(featKLT);
MRPT_FILL_ENUM(featHarris);
MRPT_FILL_ENUM(featSIFT);
MRPT_FILL_ENUM(featSURF);
MRPT_FILL_ENUM(featBeacon);
MRPT_FILL_ENUM(featFAST);
MRPT_FILL_ENUM(featORB);
MRPT_FILL_ENUM(featAKAZE);
MRPT_FILL_ENUM(featLSD);
MRPT_FILL_ENUM(descAny);
MRPT_FILL_ENUM(descSIFT);
MRPT_FILL_ENUM(descSURF);
MRPT_FILL_ENUM(descSpinImages);
MRPT_FILL_ENUM(descPolarImages);
MRPT_FILL_ENUM(descLogPolarImages);
MRPT_FILL_ENUM(descORB);
MRPT_FILL_ENUM(descBLD);
MRPT_FILL_ENUM(descLATCH);
void mouseGlitchFilter(
const int x,
const int y,
const int& mouseClickX,
const int& mouseClickY
);
static void MyGetScaledClientSize(
const wxWindow* w,
int& width,
int& height
);
EVT_RIGHT_DOWN(mpWindow::OnMouseRightDown);
wxAppConsole* mrpt_wxCreateApp();
CDisplayWindow_WXAPP& wxGetApp();
int mrpt_wxEntryReal();
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers::CGenericSensor,
ssInitializing
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers::CGenericSensor,
ssWorking
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers::CGenericSensor,
ssError
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers::CGenericSensor,
ssUninitialized
);
MRPT_FILL_ENUM_MEMBER(
CGPSInterface,
NONE
);
MRPT_FILL_ENUM_MEMBER(
CGPSInterface,
AUTO
);
MRPT_FILL_ENUM_MEMBER(
CGPSInterface,
NMEA
);
MRPT_FILL_ENUM_MEMBER(
CGPSInterface,
NOVATEL_OEM6
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers,
CAMERA_CV_AUTODETECT
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers,
CAMERA_CV_DC1394
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers,
CAMERA_CV_VFL
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers,
CAMERA_CV_VFW
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers,
CAMERA_CV_MIL
);
MRPT_FILL_ENUM_MEMBER(
mrpt::hwdrivers,
CAMERA_CV_DSHOW
);
MRPT_FILL_ENUM_MEMBER(
CKinect,
VIDEO_CHANNEL_RGB
);
MRPT_FILL_ENUM_MEMBER(
CKinect,
VIDEO_CHANNEL_IR
);
MRPT_FILL_ENUM_MEMBER(
CVelodyneScanner,
VLP16
);
MRPT_FILL_ENUM_MEMBER(
CVelodyneScanner,
HDL32
);
MRPT_FILL_ENUM_MEMBER(
CVelodyneScanner,
HDL64
);
MRPT_FILL_ENUM_MEMBER(
CVelodyneScanner,
UNCHANGED
);
MRPT_FILL_ENUM_MEMBER(
CVelodyneScanner,
STRONGEST
);
MRPT_FILL_ENUM_MEMBER(
CVelodyneScanner,
LAST
);
MRPT_FILL_ENUM_MEMBER(
CVelodyneScanner,
DUAL
);
char hexCharToInt(char n);
TEST(
CGPSInterface,
parse_NMEA_GGA
);
TEST(
CGPSInterface,
parse_NMEA_RMC
);
TEST(
CGPSInterface,
parse_NMEA_GLL
);
TEST(
CGPSInterface,
parse_NMEA_VTG
);
TEST(
CGPSInterface,
parse_NMEA_ZDA
);
TEST(
CGPSInterface,
parse_NMEA_ZDA_stream
);
TEST(
CGPSInterface,
parse_NOVATEL6_stream
);
TEST(
CGPSInterface,
parse_NMEA_stream
);
std::atomic<int> numInstances(0);
bool isValidParameter(const mrpt::img::TCamera& param);
unsigned char LinearToALawSample(uint16_t sample);
void do_init_table_16u_to_8u();
MRPT_FILL_ENUM_MEMBER(
mrpt::img,
cmNONE
);
MRPT_FILL_ENUM_MEMBER(
mrpt::img,
cmGRAYSCALE
);
MRPT_FILL_ENUM_MEMBER(
mrpt::img,
cmJET
);
MRPT_FILL_ENUM_MEMBER(
mrpt::img,
cmHOT
);
MRPT_FILL_ENUM_MEMBER(
mrpt::img::DistortionModel,
none
);
MRPT_FILL_ENUM_MEMBER(
mrpt::img::DistortionModel,
plumb_bob
);
MRPT_FILL_ENUM_MEMBER(
mrpt::img::DistortionModel,
kannala_brandt
);
DECLARE_MEXPLUS_FROM(mrpt::img::TCamera);
void init_fonts_list();
static int interpolationMethod2Cv(TInterpolationMethod i);
template <typename RET = uint32_t>
constexpr RET pixelDepth2CvDepth(PixelDepth d);
template <typename RET = uint32_t>
RET pixelDepth2IPLCvDepth(PixelDepth d);
static PixelDepth cvDepth2PixelDepth(int64_t d);
static bool my_img_to_grayscale(
const cv::Mat& src,
cv::Mat& dest
);
template <unsigned int HALF_WIN_SIZE>
void MRPT_DISABLE_FULL_OPTIMIZATION image_KLT_response_template(
const uint8_t* in,
const int widthStep,
unsigned int x,
unsigned int y,
int32_t& _gxx,
int32_t& _gyy,
int32_t& _gxy
);
void image_SSE2_scale_half_1c8u(
const uint8_t* in,
uint8_t* out,
int w,
int h,
size_t in_step,
size_t out_step
);
void image_SSSE3_scale_half_3c8u(
const uint8_t* in,
uint8_t* out,
int w,
int h,
size_t in_step,
size_t out_step
);
void image_SSE2_scale_half_smooth_1c8u(
const uint8_t* in,
uint8_t* out,
int w,
int h,
size_t in_step,
size_t out_step
);
void image_SSSE3_rgb_to_gray_8u(
const uint8_t* in,
uint8_t* out,
int w,
int h,
size_t in_step,
size_t out_step
);
void image_SSSE3_bgr_to_gray_8u(
const uint8_t* in,
uint8_t* out,
int w,
int h,
size_t in_step,
size_t out_step
);
static const char* ParseColor(const char* data);
static unsigned char ParseHexadecimal(
char digit1,
char digit2
);
static bool GetRGBFromName(
const char* inname,
bool* isNone,
unsigned char* r,
unsigned char* g,
unsigned char* b
);
static void fillImagePseudoRandom(
uint32_t seed,
mrpt::img::CImage& img
);
static bool expect_identical(
const mrpt::img::CImage& a,
const mrpt::img::CImage& b,
const std::string& s = std::string()
);
TEST(
CImage,
CtorDefault
);
static void CtorSized_gray(
unsigned int w,
unsigned int h
);
TEST(
CImage,
CtorSized
);
TEST(
CImage,
GetSetPixel
);
TEST(
CImage,
CopyMoveSwap
);
TEST(
CImage,
ExternalImage
);
TEST(
CImage,
ConvertGray
);
TEST(
CImage,
CtorRefOrGray
);
TEST(
CImage,
HalfAndDouble
);
TEST(
CImage,
getChannelsOrder
);
TEST(
CImage,
ChangeCvMatCopies
);
TEST(
CImage,
ScaleImage
);
TEST(
CImage,
Serialize
);
TEST(
CImage,
KLT_response
);
TEST(
CImage,
LoadAndComparePseudoRnd
);
TEST(
CImage,
LoadAndSave
);
TEST(
CImage,
DifferentAccessMethodsColor
);
TEST(
CImage,
DifferentAccessMethodsGray
);
TEST(
color_maps,
cmGRAYSCALE
);
TEST(
color_maps,
cmJET
);
TEST(
color_maps,
cmHOT
);
typedef JMETHOD(
boolean,
jpeg_marker_parser_method,
(j_decompress_ptr cinfo)
);
jpeg_std_error JPP((struct jpeg_error_mgr*err));
jpeg_CreateCompress JPP((j_compress_ptr cinfo, int version, size_t structsize));
jpeg_CreateDecompress JPP((j_decompress_ptr cinfo, int version, size_t structsize));
EXTERN(void);
jpeg_set_colorspace JPP((j_compress_ptr cinfo, J_COLOR_SPACE colorspace));
jpeg_set_quality JPP((j_compress_ptr cinfo, int quality, boolean force_baseline));
jpeg_set_linear_quality JPP((j_compress_ptr cinfo, int scale_factor, boolean force_baseline));
jpeg_add_quant_table JPP((j_compress_ptr cinfo, int which_tbl, const unsigned int*basic_table, int scale_factor, boolean force_baseline));
EXTERN(int);
EXTERN(JQUANT_TBL*);
EXTERN(JHUFF_TBL*);
jpeg_start_compress JPP((j_compress_ptr cinfo, boolean write_all_tables));
jpeg_write_scanlines JPP((j_compress_ptr cinfo, JSAMPARRAY scanlines, JDIMENSION num_lines));
jpeg_write_raw_data JPP((j_compress_ptr cinfo, JSAMPIMAGE data, JDIMENSION num_lines));
jpeg_write_marker JPP((j_compress_ptr cinfo, int marker, const JOCTET*dataptr, unsigned int datalen));
jpeg_write_m_header JPP((j_compress_ptr cinfo, int marker, unsigned int datalen));
jpeg_read_header JPP((j_decompress_ptr cinfo, boolean require_image));
EXTERN(boolean);
jpeg_read_scanlines JPP((j_decompress_ptr cinfo, JSAMPARRAY scanlines, JDIMENSION max_lines));
jpeg_read_raw_data JPP((j_decompress_ptr cinfo, JSAMPIMAGE data, JDIMENSION max_lines));
jpeg_start_output JPP((j_decompress_ptr cinfo, int scan_number));
jpeg_save_markers JPP((j_decompress_ptr cinfo, int marker_code, unsigned int length_limit));
jpeg_set_marker_processor JPP((j_decompress_ptr cinfo, int marker_code, jpeg_marker_parser_method routine));
EXTERN(jvirt_barray_ptr*);
jpeg_write_coefficients JPP((j_compress_ptr cinfo, jvirt_barray_ptr*coef_arrays));
jpeg_copy_critical_parameters JPP((j_decompress_ptr srcinfo, j_compress_ptr dstinfo));
jpeg_resync_to_restart JPP((j_decompress_ptr cinfo, int desired));
static TCamera getSampleCameraParamsBase();
static TCamera getSampleCameraParamsPlumbBob();
static TCamera getSampleCameraParamsFishEye();
TEST(
TCamera,
EqualOperator
);
TEST(
TCamera,
CopyCtor
);
TEST(
TCamera,
ToFromINI_PlumbBob
);
TEST(
TCamera,
ToFromINI_FishEye
);
void generate_test_data(std::vector<uint8_t>& tst_data);
TEST(
CFileGZStreams,
readwriteTmpFileCompressed
);
TEST(
CFileGZStreams,
compareWithTestGZFiles
);
TEST(
CMemoryStream,
readwrite
);
TEST(
CTextFileLinesParser,
parse
);
static std::string LAZY_LOAD_PATH_BASE(".");
TEST(
file_get_contents,
readTestFile
);
TEST(
file_get_contents,
throwOnError
);
TEST(
Compress,
DataBlockGZ
);
void addBar_D(
mrpt::opengl::CSetOfObjects::Ptr& objs,
const double d
);
void addBar_A(
mrpt::opengl::CSetOfObjects::Ptr& objs,
const double a
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CColouredPointsMap::TColouringMethod,
cmFromHeightRelativeToSensor
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CColouredPointsMap::TColouringMethod,
cmFromHeightRelativeToSensorJet
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CColouredPointsMap::TColouringMethod,
cmFromHeightRelativeToSensorGray
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CColouredPointsMap::TColouringMethod,
cmFromIntensityImage
);
MRPT_FILL_ENUM_MEMBER(
maps::CHeightGridMap2D::TMapRepresentation,
mrSimpleAverage
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap2D,
lmMeanInformation
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap2D,
lmRayTracing
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap2D,
lmConsensus
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap2D,
lmCellsDifference
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap2D,
lmLikelihoodField_Thrun
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap2D,
lmLikelihoodField_II
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap2D,
lmConsensusOWA
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap3D,
lmRayTracing
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::COccupancyGridMap3D,
lmLikelihoodField_Thrun
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CRandomFieldGridMap2D::TMapRepresentation,
mrKernelDM
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CRandomFieldGridMap2D::TMapRepresentation,
mrKalmanFilter
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CRandomFieldGridMap2D::TMapRepresentation,
mrKalmanApproximate
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CRandomFieldGridMap2D::TMapRepresentation,
mrKernelDMV
);
MRPT_FILL_ENUM_MEMBER(
mrpt::maps::CRandomFieldGridMap2D::TMapRepresentation,
mrGMRF_SD
);
static void aux_projectPoint_with_distortion(
const mrpt::math::TPoint3D& P,
const TCamera& params,
TPixelCoordf& pixel,
] bool accept_points_behind
);
IMPLEMENTS_SERIALIZABLE(
CGasConcentrationGridMap2D,
CRandomFieldGridMap2D,
mrpt::maps
);
static void test_CGasConcentrationGridMap2D_insertAndRead(
mrpt::maps::CRandomFieldGridMap2D::TMapRepresentation mapType,
const double resolution,
const std::function<double(const mrpt::maps::TRandomFieldCell&)>& cellToValue
);
TEST(
CGasConcentrationGridMap2D,
insertAndRead
);
template <class MAP>
void do_test_insertCheckMapBounds();
TEST(
CHeightGridMap2Ds,
insertCheckMapBounds
);
template <class MAP>
void do_test_insertPointsAndRead();
TEST(
CHeightGridMap2Ds,
insertPointsAndRead
);
template <typename cell_t>
void test_monotonic();
TEST(
CLogOddsGridMapLUT,
monotonic_8bit
);
TEST(
CLogOddsGridMapLUT,
monotonic_16bit
);
TEST(
CMultiMetricMapTests,
isEmpty
);
static mrpt::maps::CMultiMetricMap initializer1();
static mrpt::maps::CMultiMetricMap initializer2();
TEST(
CMultiMetricMapTests,
initializers
);
TEST(
CMultiMetricMapTests,
copyCtorOp
);
TEST(
CMultiMetricMapTests,
moveOp
);
static void func_laserSimul_callback(
const mrpt::math::CVectorFixedDouble<3>& x_pose,
const TFunctorLaserSimulData& fixed_param,
mrpt::math::CVectorDouble& y_scanRanges
);
TEST(
COccupancyGridMap2DTests,
insert2DScan
);
TEST(
COccupancyGridMap2DTests,
NearestNeighborsCapable
);
TEST(
COccupancyGridMap3DTests,
insert2DScan
);
TEST(
COccupancyGridMap3DTests,
NearestNeighborsCapable
);
TEST(
COccupancyGridMap3DTests,
insertScan3D
);
TEST(
COctoMapTests,
updateVoxels
);
TEST(
COctoMapTests,
insert2DScan
);
void run_pc_filter_test(
const double map2_x_off,
const double map2_tim_off,
const size_t expected_m1_count,
const size_t expected_m2_count
);
TEST(
CPointCloudFilterByDistance,
noOutliers
);
TEST(
CPointCloudFilterByDistance,
withOutliers
);
TEST(
CPointCloudFilterByDistance,
tooOldMap
);
void internal_build_points_map_from_scan2D(
const mrpt::obs::CObservation2DRangeScan& obs,
mrpt::maps::CMetricMap::Ptr& out_map,
const void* insertOps
);
template <class MAP>
void load_demo_9pts_map(MAP& pts);
template <class MAP>
void do_test_insertPoints();
template <class MAP>
void do_test_clipOutOfRangeInZ();
template <class MAP>
void do_test_clipOutOfRange();
template <class MAP>
void do_tests_loadSaveStreams();
TEST(
CSimplePointsMapTests,
insertPoints
);
TEST(
CWeightedPointsMapTests,
insertPoints
);
TEST(
CColouredPointsMapTests,
insertPoints
);
TEST(
CPointsMapXYZI,
insertPoints
);
TEST(
CSimplePointsMapTests,
clipOutOfRangeInZ
);
TEST(
CWeightedPointsMapTests,
clipOutOfRangeInZ
);
TEST(
CColouredPointsMapTests,
clipOutOfRangeInZ
);
TEST(
CSimplePointsMapTests,
clipOutOfRange
);
TEST(
CWeightedPointsMapTests,
clipOutOfRange
);
TEST(
CColouredPointsMapTests,
clipOutOfRange
);
TEST(
CSimplePointsMapTests,
loadSaveStreams
);
TEST(
CWeightedPointsMapTests,
loadSaveStreams
);
TEST(
CColouredPointsMapTests,
loadSaveStreams
);
TEST(
CPointsMapXYZI,
loadFromKittiVelodyneFile
);
TEST(
CRandomFieldGridMap3D,
insertCheckMapBounds
);
TEST(
CRandomFieldGridMap3D,
insertPointsAndRead
);
IMPLEMENTS_SERIALIZABLE(
CWirelessPowerGridMap2D,
CRandomFieldGridMap2D,
mrpt::maps
);
TEST_CLASS_MOVE_COPY_CTORS(CBeacon);
TEST_CLASS_MOVE_COPY_CTORS(CBeaconMap);
TEST_CLASS_MOVE_COPY_CTORS(CColouredPointsMap);
TEST_CLASS_MOVE_COPY_CTORS(CGasConcentrationGridMap2D);
TEST_CLASS_MOVE_COPY_CTORS(CWirelessPowerGridMap2D);
TEST_CLASS_MOVE_COPY_CTORS(CHeightGridMap2D);
TEST_CLASS_MOVE_COPY_CTORS(CReflectivityGridMap2D);
TEST_CLASS_MOVE_COPY_CTORS(COccupancyGridMap2D);
TEST_CLASS_MOVE_COPY_CTORS(COccupancyGridMap3D);
TEST_CLASS_MOVE_COPY_CTORS(CSimplePointsMap);
TEST_CLASS_MOVE_COPY_CTORS(CRandomFieldGridMap3D);
TEST_CLASS_MOVE_COPY_CTORS(CWeightedPointsMap);
TEST_CLASS_MOVE_COPY_CTORS(CPointsMapXYZI);
TEST_CLASS_MOVE_COPY_CTORS(COctoMap);
TEST_CLASS_MOVE_COPY_CTORS(CColouredOctoMap);
TEST_CLASS_MOVE_COPY_CTORS(CVoxelMap);
TEST_CLASS_MOVE_COPY_CTORS(CVoxelMapRGB);
TEST_CLASS_MOVE_COPY_CTORS(CSinCosLookUpTableFor2DScans);
TEST_CLASS_MOVE_COPY_CTORS(CObservationPointCloud);
TEST_CLASS_MOVE_COPY_CTORS(CObservationRotatingScan);
TEST_CLASS_MOVE_COPY_CTORS(CAngularObservationMesh);
TEST_CLASS_MOVE_COPY_CTORS(CPlanarLaserScan);
TEST(
SerializeTestMaps,
WriteReadToMem
);
TEST(
SerializeTestOpenGL,
WriteReadToMem
);
TEST(
SerializeTestOpenGL,
PredefinedSceneFile
);
IMPLEMENTS_SERIALIZABLE(
CObservationPointCloud,
CObservation,
mrpt::obs
);
MRPT_TODO("toPointCloud / calibration");
TEST(
CObservationRotatingScan,
fromKittiUndistorted
);
TEST(
CObservationRotatingScan,
fromVelodyne
);
TEST(
CObservationRotatingScan,
from2DScan
);
static void add_common_to_viz(
const CObservation& obs,
const VisualizationParameters& p,
mrpt::opengl::CSetOfObjects& out
);
TPolygon3D createFromTriangle(const mrpt::opengl::TTriangle& t);
void ClearKMeansLogging();
void AddKMeansLogging(
std::ostream* out,
bool verbose
);
Scalar RunKMeans(
int n,
int k,
int d,
Scalar* points,
int attempts,
Scalar* centers,
int* assignments
);
Scalar RunKMeansPlusPlus(
int n,
int k,
int d,
Scalar* points,
int attempts,
Scalar* centers,
int* assignments
);
MRPT_WARNING(
"Deprecated header<mrpt/math/lightweight_geom_data.h>,
use " "<mrpt/math/XXX.h> instead for the required types " "(XXX=TPose3D, TPoint2D, etc.)"
);
MRPT_WARNING(
"Deprecated header<mrpt/math/lightweight_geom_data_frwds.h>,
use " "<mrpt/math/TPoseOrPoint.h> instead"
);
template <class LUT_CLASS>
void atan2_lut_test(
const LUT_CLASS& atan2lut,
const double SIZE,
const double max_deg_errors,
const double skip_area
);
TEST(
CAtan2LookUpTable,
ValidValidTest
);
TEST(
CAtan2LookUpTable,
MultiResTest
);
TEST(
LevMarq,
optimizeTest
);
TEST(
CMatrixDynamic,
GetSetEigen
);
TEST(
CMatrixDynamic,
asString
);
TEST(
CMatrixDynamic,
CtorFromArray
);
TEST(
CMatrixDynamic,
Resizes
);
TEST(
CVectorDynamic,
segment
);
DO_MATFIXED_INSTANTIATION(float);
DO_MATFIXED_INSTANTIATION(double);
TEST(
CMatrixFixed,
CtorUninit
);
TEST(
CMatrixFixed,
CtorAllZeros
);
TEST(
CMatrixFixed,
Identity
);
TEST(
CMatrixFixed,
asString
);
TEST(
CMatrixFixed,
GetSetEigen
);
TEST(
CVectorDouble,
resize
);
TEST(
ops_containers,
ncc_vector
);
TEST(
ops_containers,
xcorr
);
void generateRandomSparseMatrix(
size_t N,
size_t M,
size_t nEntries,
CSparseMatrix& MAT
);
void do_test_init_to_unit(size_t N);
TEST(
SparseMatrix,
InitFromDenseUnit
);
void do_test_init_random(size_t N);
TEST(
SparseMatrix,
InitFromDenseRandom
);
TEST(
SparseMatrix,
InitFromTriplet
);
TEST(
SparseMatrix,
InitFromSparse
);
TEST(
SparseMatrix,
InitFromRandom
);
void do_matrix_op_test(
size_t nRows1,
size_t nCols1,
size_t nNonZeros1,
size_t nRows2,
size_t nCols2,
size_t nNonZeros2,
TMatrixSMOperator op1,
TMatrixDenseOperator op2
);
void op_sparse_add(
const CSparseMatrix& M1,
const CSparseMatrix& M2,
CSparseMatrix& res
);
void op_dense_add(
const CMatrixDouble& M1,
const CMatrixDouble& M2,
CMatrixDouble& res
);
TEST(
SparseMatrix,
Op_Add
);
void op_sparse_multiply_AB(
const CSparseMatrix& M1,
const CSparseMatrix& M2,
CSparseMatrix& res
);
void op_dense_multiply_AB(
const CMatrixDouble& M1,
const CMatrixDouble& M2,
CMatrixDouble& res
);
TEST(
SparseMatrix,
Op_Multiply_AB
);
TEST(
SparseMatrix,
CholeskyDecomp
);
DO_VECFIXED_INSTANTIATION(float);
DO_VECFIXED_INSTANTIATION(double);
TEST(
distributions,
normalPDF_1d
);
TEST(
distributions,
normalPDF_vector
);
TEST(
distributions,
erfc
);
TEST(
distributions,
erf
);
TEST(
distributions,
normalCDF
);
TEST(
distributions,
chi2inv
);
TEST(
distributions,
chi2PDF
);
TEST(
distributions,
noncentralChi2PDF_CDF
);
TEST(
data_utils,
mahalanobisDistance2AndLogPDF
);
TEST(
EigenAlignment,
PrintAlignment
);
template <unsigned int INTER_SPACE>
void checkAlignedFoo(
const Foo<INTER_SPACE>& d,
const std::string& testName
);
template <unsigned int INTER_SPACE>
void do_test_AlignedMemOnStack();
template <unsigned int INTER_SPACE>
void do_test_AlignedMemOnStackUpTo();
template <unsigned int INTER_SPACE>
void do_test_AlignedMemInSTL();
template <unsigned int INTER_SPACE>
void do_test_AlignedMemInSTLUpTo();
TEST(
EigenAlignment,
AlignedMemOnStack
);
TEST(
EigenAlignment,
AlignedMemInSTL
);
static void myGeneralDFT(
int sign,
const CMatrixFloat& in_real,
const CMatrixFloat& in_imag,
CMatrixFloat& out_real,
CMatrixFloat& out_imag
);
static long double Power_Series_S(long double x);
static long double xFresnel_Auxiliary_Cosine_Integral(long double x);
static long double xFresnel_Auxiliary_Sine_Integral(long double x);
static long double Power_Series_C(long double x);
static long double xChebyshev_Tn_Series(
long double x,
const long double a [],
int degree
);
long double lfresnel_sin_alt(long double x);
long double lfresnel_cos_alt(long double x);
double Fresnel_Sine_Integral(double x);
long double xFresnel_Sine_Integral(long double x);
double Fresnel_Auxiliary_Sine_Integral(double x);
static long double sin_Chebyshev_Expansion_0_1(long double x);
static long double sin_Chebyshev_Expansion_1_3(long double x);
static long double sin_Chebyshev_Expansion_3_5(long double x);
static long double sin_Chebyshev_Expansion_5_7(long double x);
static long double sin_Asymptotic_Series(long double x);
double Fresnel_Auxiliary_Cosine_Integral(double x);
static long double cos_Chebyshev_Expansion_0_1(long double x);
static long double cos_Chebyshev_Expansion_1_3(long double x);
static long double cos_Chebyshev_Expansion_3_5(long double x);
static long double cos_Chebyshev_Expansion_5_7(long double x);
static long double cos_Asymptotic_Series(long double x);
double Fresnel_Cosine_Integral(double x);
long double xFresnel_Cosine_Integral(long double x);
TEST(
fresnel,
fresnelc
);
TEST(
fresnel,
fresnels
);
template <class T2D, class U2D, class T3D, class U3D>
bool intersectInCommonPlane(
const T3D& o1,
const U3D& o2,
const mrpt::math::TPlane& p,
mrpt::math::TObject3D& obj
);
bool intersectInCommonLine(
const mrpt::math::TSegment3D& s1,
const mrpt::math::TSegment3D& s2,
const mrpt::math::TLine3D& lin,
mrpt::math::TObject3D& obj
);
bool intersectInCommonLine(
const TSegment2D& s1,
const TSegment2D& s2,
const TLine2D& lin,
TObject2D& obj
);
void unsafeProjectPoint(
const TPoint3D& point,
const TPose3D& pose,
TPoint2D& newPoint
);
bool intersect(
const TPolygonWithPlane& p1,
const TLine3D& l2,
double& d,
double bestKnown
);
bool intersect(
const TPolygonWithPlane& p1,
const TPolygonWithPlane& p2,
TObject3D& obj
);
void createFromPoseAndAxis(
const TPose3D& p,
TLine3D& r,
size_t axis
);
bool intersect(
const TSegmentWithLine& s1,
const TSegmentWithLine& s2,
TObject2D& obj
);
void getSegmentsWithLine(
const TPolygon2D& poly,
vector<TSegmentWithLine>& segs
);
bool intersectAux(
const TPolygon3D& p1,
const TPlane& pl1,
const TPolygon3D& p2,
const TPlane& pl2,
TObject3D& obj
);
bool compatibleBounds(
const TPoint3D& min1,
const TPoint3D& max1,
const TPoint3D& min2,
const TPoint3D& max2
);
void getPlanes(
const std::vector<TPolygon3D>& polys,
std::vector<TPlane>& planes
);
void getMinAndMaxBounds(
const std::vector<TPolygon3D>& v1,
std::vector<TPoint3D>& minP,
std::vector<TPoint3D>& maxP
);
void createPlaneFromPoseAndAxis(
const TPose3D& pose,
TPlane& plane,
size_t axis
);
template <class T>
size_t getIndexOfMin(
const T& e1,
const T& e2,
const T& e3
);
bool firstOrNonPresent(
size_t i,
const std::vector<MatchingVertex>& v
);
bool depthFirstSearch(
const CSparseMatrixTemplate<unsigned char>& mat,
std::vector<std::vector<MatchingVertex>>& res,
std::vector<bool>& used,
size_t searching,
unsigned char mask,
std::vector<MatchingVertex>& current
);
void depthFirstSearch(
const CSparseMatrixTemplate<unsigned char>& mat,
std::vector<std::vector<MatchingVertex>>& res,
std::vector<bool>& used
);
static std::vector<TPolygon3D> getPolygons(
const std::vector<TObject3D>& objs,
const mrpt::optional_ref<std::vector<mrpt::math::TObject3D>>& others = std::nullopt
);
static std::vector<TSegment3D> getSegments(
const std::vector<TObject3D>& objs,
const mrpt::optional_ref<std::vector<mrpt::math::TObject3D>>& others = std::nullopt
);
bool intersect(
const TLine2D& l1,
const TSegmentWithLine& s2,
TObject2D& obj
);
bool intersect(
const TSegmentWithLine& s1,
const TLine2D& l2,
TObject2D& obj
);
TEST(
Geometry,
Line2DIntersect
);
TEST(
Geometry,
Line2DAngle
);
TEST(
Geometry,
Line3DAngle
);
TEST(
Geometry,
PlaneAngle
);
TEST(
Geometry,
PlaneLineAngle
);
TEST(
Geometry,
PlanePointDistance
);
TEST(
Geometry,
PlanePointSignedDistance
);
TEST(
Geometry,
Line3DDistance
);
TEST(
Geometry,
Line3DDclosestPointTo
);
TEST(
Geometry,
Segment2DIntersect
);
TEST(
Geometry,
Intersection3D
);
TEST(
Geometry,
IntersectionPlanePlane
);
void myTestPolygonContainsPoint(
std::vector<TPoint2D>& vs,
bool convex
);
TEST(
Geometry,
PolygonConvexContainsPoint
);
TEST(
Geometry,
PolygonConcaveContainsPoint
);
TEST(
Geometry,
changeEpsilon
);
TEST(
Geometry,
conformAPlane
);
TEST(
Geometry,
RectanglesIntersection
);
TEST(
TLine2D,
asString
);
TEST(
TLine3D,
asString
);
TEST(
TPlane,
asString
);
TEST(
Geometry,
closestFromPointToSegment
);
TEST(
Geometry,
closestFromPointToLine
);
TEST(
Geometry,
squaredDistancePointToLine
);
TEST(
TPolygon2D,
toFromYAML
);
TEST(
TPolygon3D,
toFromYAML
);
TEST(
Geometry,
polygonIntersection
);
TEST(
Geometry,
areAligned_TPoint2D
);
TEST(
Geometry,
areAligned_TPoint3D
);
TEST(
Geometry,
project2D
);
TEST(
Geometry,
project3D
);
TEST(
Geometry,
getRegressionLine2D
);
TEST(
Geometry,
getRegressionLine3D
);
TEST(
Geometry,
getRegressionPlane
);
TEST(
KDTreeCapable,
test1
);
void AddKMeansLogging(
std::ostream* out,
bool verbose
);
void ClearKMeansLogging();
static double GetSeconds();
static void RunKMeansOnce(
const KmTree& tree,
int n,
int k,
int d,
Scalar* points,
Scalar* centers,
Scalar* min_cost,
Scalar* max_cost,
Scalar* total_cost,
double start_time,
double* min_time,
double* max_time,
double* total_time,
Scalar* best_centers,
int* best_assignment
);
void LogMetaStats(
Scalar min_cost,
Scalar max_cost,
Scalar total_cost,
double min_time,
double max_time,
double total_time,
int num_attempts
);
Scalar RunKMeans(
int n,
int k,
int d,
Scalar* points,
int attempts,
Scalar* ret_centers,
int* ret_assignment
);
Scalar RunKMeansPlusPlus(
int n,
int k,
int d,
Scalar* points,
int attempts,
Scalar* ret_centers,
int* ret_assignment
);
int __KMeansAssertionFailure(
const char* file,
int line,
const char* expression
);
Scalar* PointAllocate(int d);
void PointFree(Scalar* p);
void PointCopy(
Scalar* p1,
const Scalar* p2,
int d
);
void PointAdd(
Scalar* p1,
const Scalar* p2,
int d
);
void PointScale(
Scalar* p,
Scalar scale,
int d
);
Scalar PointDistSq(
const Scalar* p1,
const Scalar* p2,
int d
);
int __KMeansAssertionFailure(
const char* file,
int line,
const char* expression
);
int GetRandom(int n);
template <class T>
void noncentralChi2OneIteration(
T arg,
T& lans,
T& dans,
T& pans,
unsigned int& j
);
TEST(
Matrices,
DynMat_size
);
TEST(
Matrices,
A_times_B_dyn
);
TEST(
Matrices,
A_times_B_fix
);
TEST(
Matrices,
SerializeCMatrixD
);
TEST(
Matrices,
EigenVal2x2dyn
);
TEST(
Matrices,
eig_symmetric
);
TEST(
Matrices,
EigenVal3x3dyn
);
TEST(
Matrices,
EigenVal2x2fix
);
TEST(
Matrices,
EigenVal3x3fix
);
TEST(
Matrices,
inv_4x4_fix
);
TEST(
Matrices,
inv_LLt_4x4_fix
);
TEST(
Matrices,
inv_6x6_fix
);
TEST(
Matrices,
inv_6x6_dyn
);
TEST(
Matrices,
transpose
);
TEST(
Matrices,
multiply_A_skew3
);
TEST(
Matrices,
multiply_skew3_A
);
TEST(
Matrices,
fromMatlabStringFormat
);
TEST(
Matrices,
HCHt_3x2_2x2_2x3
);
TEST(
Matrices,
HCHt_scalar_1x2_2x2_2x1
);
TEST(
Matrices,
det_2x2_dyn
);
TEST(
Matrices,
det_2x2_fix
);
TEST(
Matrices,
det_3x3_dyn
);
TEST(
Matrices,
det_3x3_fix
);
TEST(
Matrices,
det_4x4_dyn
);
TEST(
Matrices,
det_4x4_fix
);
TEST(
Matrices,
det_10x10_dyn
);
TEST(
Matrices,
chol_2x2_dyn
);
TEST(
Matrices,
chol_2x2_fix
);
TEST(
Matrices,
chol_3x3_dyn
);
TEST(
Matrices,
chol_3x3_fix
);
TEST(
Matrices,
chol_10x10_dyn
);
TEST(
Matrices,
meanAndStdColumns
);
TEST(
Matrices,
meanAndStdAll
);
TEST(
Matrices,
laplacian
);
TEST(
Matrices,
loadFromTextFile
);
TEST(
Matrices,
loadFromArray
);
TEST(
Matrices,
CMatrixFixedNumeric_loadWithEigenMap
);
TEST(
Matrices,
EigenMatrix_loadWithEigenMap
);
TEST(
Matrices,
setSize
);
TEST(
Matrices,
extractSubmatrixSymmetricalBlocks
);
TEST(
Matrices,
extractSubmatrixSymmetrical
);
TEST(
Matrices,
removeColumns
);
TEST(
Matrices,
removeRows
);
MRPT_TEST(
MatrixYaml,
FromToEigen
);
MRPT_TEST(
MatrixYaml,
Vector
);
DO_MATFIXED_INSTANTIATION(double);
DO_MATFIXED_INSTANTIATION(float);
DO_MATFIXED_INSTANTIATION(double);
DO_MATFIXED_INSTANTIATION(float);
DO_MATFIXED_INSTANTIATION(float);
DO_MATFIXED_INSTANTIATION(double);
DO_VECFIXED_INSTANTIATION(float);
DO_VECFIXED_INSTANTIATION(double);
void CSqrt(
double x,
double y,
double& a,
double& b
);
int SolveP4Bi(
double* x,
double b,
double d
);
static void dblSort3(
double& a,
double& b,
double& c
);
int SolveP4De(
double* x,
double b,
double c,
double d
);
double N4Step(
double x,
double a,
double b,
double c,
double d
);
static double SolveP5_1(
double a,
double b,
double c,
double d,
double e
);
TEST(
poly_roots,
solve_poly2
);
TEST(
poly_roots,
solve_poly3
);
TEST(
poly_roots,
solve_poly4
);
EXPLICIT_INST_ransac_detect_3D_planes(float);
EXPLICIT_INST_ransac_detect_3D_planes(double);
EXPLICIT_INSTANT_ransac_detect_2D_lines(float);
EXPLICIT_INSTANT_ransac_detect_2D_lines(double);
template <TRobustKernelType KERNEL_TYPE>
void tester_robust_kernel(
const double table [][5],
const size_t N
);
TEST(
RobustKernels,
PlainLeastSquares
);
TEST(
RobustKernels,
PseudoHuber
);
DO_MATFIXED_INSTANTIATION(double);
DO_MATFIXED_INSTANTIATION(float);
DO_MATFIXED_INSTANTIATION(double);
TEST(
SLERP_tests,
correctShortestPath
);
template <typename T>
void testDefaultCtor();
TEST(
TBoundingBox,
defaultCtor
);
template <typename T>
void testFromCorners();
TEST(
TBoundingBox,
fromCorners
);
template <typename T>
void testInvalidThrows();
TEST(
TBoundingBox,
invalidThrows
);
template <typename T>
void testIntersections();
TEST(
TBoundingBox,
intersections
);
TEST(
TBoundingBox,
compose
);
TEST(
TBoundingBox,
inverseCompose
);
double isLeft(
const mrpt::math::TPoint2D& P0,
const mrpt::math::TPoint2D& P1,
const mrpt::math::TPoint2D& P2
);
TEST(
LightGeomData,
PragmaPack
);
TEST(
LightGeomData,
ConstExprCtors
);
TEST(
LightGeomData,
Conversions
);
TEST(
LightGeomData,
Comparisons
);
TEST(
LightGeomData,
Strings
);
TEST(
Wrap2PI_tests,
angDistance
);
DO_MATFIXED_INSTANTIATION(double);
DO_MATFIXED_INSTANTIATION(float);
MRPT_FILL_ENUM_MEMBER(
CHolonomicND,
SITUATION_TARGET_DIRECTLY
);
MRPT_FILL_ENUM_MEMBER(
CHolonomicND,
SITUATION_SMALL_GAP
);
MRPT_FILL_ENUM_MEMBER(
CHolonomicND,
SITUATION_WIDE_GAP
);
MRPT_FILL_ENUM_MEMBER(
CHolonomicND,
SITUATION_NO_WAY_FOUND
);
MRPT_FILL_ENUM_MEMBER(
CAbstractNavigator,
IDLE
);
MRPT_FILL_ENUM_MEMBER(
CAbstractNavigator,
NAVIGATING
);
MRPT_FILL_ENUM_MEMBER(
CAbstractNavigator,
SUSPENDED
);
MRPT_FILL_ENUM_MEMBER(
CAbstractNavigator,
NAV_ERROR
);
IMPLEMENTS_VIRTUAL_SERIALIZABLE(
CAbstractHolonomicReactiveMethod,
CSerializable,
mrpt::nav
);
IMPLEMENTS_SERIALIZABLE(
CLogFileRecord_FullEval,
CHolonomicLogFileRecord,
mrpt::nav
);
IMPLEMENTS_SERIALIZABLE(CHolonomicND, CAbstractHolonomicReactiveMethod, mrpt::nav);
IMPLEMENTS_SERIALIZABLE(
CHolonomicVFF,
CAbstractHolonomicReactiveMethod,
mrpt::nav
);
TEST(
NavTests,
NavGeomUtils_collision_straight_circ_robot
);
TEST(
PlannerSimple2D,
findPath
);
TEST(
NavTests,
Serialization_WriteReadToMem
);
TEST(
SerializeTestObs,
WriteReadToOctectVectors
);
TEST(
NavTests,
NavLogLoadFromTestFile
);
IMPLEMENTS_VIRTUAL_MRPT_OBJECT(
CMultiObjectiveMotionOptimizerBase,
CObject,
mrpt::nav
);
IMPLEMENTS_MRPT_OBJECT(
CMultiObjMotionOpt_Scalarization,
CMultiObjectiveMotionOptimizerBase,
mrpt::nav
);
template <typename RNAVCLASS>
void run_rnav_test_impl(
const std::string& sFilename,
const std::string& sHoloMethod,
const TPoint2D& nav_target,
const TPoint2D& world_topleft,
const TPoint2D& world_rightbottom,
const TPoint2D& block_obstacle_topleft = TPoint2D(0, 0),
const TPoint2D& block_obstacle_rightbottom = TPoint2D(0, 0)
);
template <typename RNAVCLASS>
void run_rnav_test(
const std::string& sFilename,
const std::string& sHoloMethod,
const TPoint2D& nav_target,
const TPoint2D& world_topleft,
const TPoint2D& world_rightbottom,
const TPoint2D& block_obstacle_topleft = TPoint2D(0, 0),
const TPoint2D& block_obstacle_rightbottom = TPoint2D(0, 0)
);
const TPoint2D no_obs_trg(
2. 0,
0. 4
);
const TPoint2D no_obs_topleft(
- 10,
10
);
const TPoint2D no_obs_bottomright(
10,
- 10
);
const TPoint2D with_obs_trg(
9. 0,
4. 0
);
const TPoint2D with_obs_topleft(
- 10,
10
);
const TPoint2D with_obs_bottomright(
30,
- 10
);
const TPoint2D obs_tl(
4. 0,
2. 0
);
const TPoint2D obs_br(
5. 0,
-2. 0
);
TEST(
CReactiveNavigationSystem,
no_obstacle_nav_VFF
);
TEST(
CReactiveNavigationSystem,
no_obstacle_nav_ND
);
TEST(
CReactiveNavigationSystem,
no_obstacle_nav_FullEval
);
TEST(
CReactiveNavigationSystem3D,
no_obstacle_nav_VFF
);
TEST(
CReactiveNavigationSystem3D,
no_obstacle_nav_ND
);
TEST(
CReactiveNavigationSystem3D,
no_obstacle_nav_FullEval
);
TEST(
CReactiveNavigationSystem,
with_obstacle_nav_VFF
);
TEST(
CReactiveNavigationSystem,
with_obstacle_nav_ND
);
TEST(
CReactiveNavigationSystem,
with_obstacle_nav_FullEval
);
TEST(
CReactiveNavigationSystem3D,
with_obstacle_nav_VFF
);
TEST(
CReactiveNavigationSystem3D,
with_obstacle_nav_ND
);
TEST(
CReactiveNavigationSystem3D,
with_obstacle_nav_FullEval
);
IMPLEMENTS_SERIALIZABLE(
CPTG_DiffDrive_alpha,
CParameterizedTrajectoryGenerator,
mrpt::nav
);
IMPLEMENTS_SERIALIZABLE(
CPTG_DiffDrive_C,
CParameterizedTrajectoryGenerator,
mrpt::nav
);
IMPLEMENTS_SERIALIZABLE(
CPTG_DiffDrive_CC,
CParameterizedTrajectoryGenerator,
mrpt::nav
);
IMPLEMENTS_SERIALIZABLE(
CPTG_DiffDrive_CCS,
CParameterizedTrajectoryGenerator,
mrpt::nav
);
IMPLEMENTS_SERIALIZABLE(
CPTG_DiffDrive_CS,
CParameterizedTrajectoryGenerator,
mrpt::nav
);
static double calc_trans_distance_t_below_Tramp_abc_numeric(
double T,
double a,
double b,
double c
);
TEST(
NavTests,
PTGs_tests
);
MRPT_FILL_ENUM_MEMBER(
mrpt::obs::CActionRobotMovement2D,
emOdometry
);
MRPT_FILL_ENUM_MEMBER(
mrpt::obs::CActionRobotMovement2D,
emScan2DMatching
);
MRPT_FILL_ENUM_MEMBER(
mrpt::obs::CObservation3DRangeScan,
CH_VISIBLE
);
MRPT_FILL_ENUM_MEMBER(
mrpt::obs::CObservation3DRangeScan,
CH_IR
);
bool operator == (
const LUT_info& a,
const LUT_info& o
);
static void mempool_donate_xyz_buffers(CObservation3DRangeScan& obs);
void mempool_donate_range_matrix(CObservation3DRangeScan& obs);
void fillSampleObs(
mrpt::obs::CObservation3DRangeScan& obs,
mrpt::obs::T3DPointsProjectionParams& pp,
int test_case
);
TEST(
CObservation3DRangeScan,
Project3D_noFilter
);
TEST(
CObservation3DRangeScan,
Project3D_filterMinMax1
);
TEST(
CObservation3DRangeScan,
Project3D_additionalLayers
);
TEST(
CObservation3DRangeScan,
Project3D_filterMinMaxAllBetween
);
TEST(
CObservation3DRangeScan,
Project3D_filterMinMaxNoneBetween
);
TEST(
CObservation3DRangeScan,
Project3D_filterMin
);
TEST(
CObservation3DRangeScan,
Project3D_filterMax
);
TEST(
CObservation3DRangeScan,
LoadAndCheckFloorPoints
);
TEST(
CObservation3DRangeScan,
SyntheticRange
);
TEST(
CObservation3DRangeScan,
SyntheticDepth
);
bool TIMECONV_GetJulianDateFromGPSTime(
const unsigned short gps_week,
const double gps_tow,
const unsigned int utc_offset,
double* julian_date
);
bool TIMECONV_IsALeapYear(const unsigned short year);
bool TIMECONV_GetNumberOfDaysInMonth(
const unsigned short year,
const unsigned char month,
unsigned char* days_in_month
);
bool TIMECONV_GetUTCTimeFromJulianDate(const double julian_date, mrpt::system::TTimeParts& utc);
static void checkExpectedValues(const mrpt::obs::CObservationIMU& o);
TEST(
CObservationIMU,
Deserialize_v3
);
TEST(
CObservationIMU,
Deserialize_v4
);
IMPLEMENTS_SERIALIZABLE(
CObservationStereoImagesFeatures,
CObservation,
mrpt::obs
);
static double HDL32AdjustTimeStamp(int firingblock, int dsr);
static double VLP16AdjustTimeStamp(int firingblock, int dsr, int firingwithinblock);
static void velodyne_scan_to_pointcloud(
const Velo& scan,
const Velo::TGeneratePointCloudParameters& params,
Velo::PointCloudStorageWrapper& out_pc
);
TEST_CLASS_MOVE_COPY_CTORS(CObservation2DRangeScan);
TEST_CLASS_MOVE_COPY_CTORS(CObservation3DRangeScan);
TEST_CLASS_MOVE_COPY_CTORS(CObservation3DScene);
TEST_CLASS_MOVE_COPY_CTORS(CObservationRGBD360);
TEST_CLASS_MOVE_COPY_CTORS(CObservationBearingRange);
TEST_CLASS_MOVE_COPY_CTORS(CObservationBatteryState);
TEST_CLASS_MOVE_COPY_CTORS(CObservationWirelessPower);
TEST_CLASS_MOVE_COPY_CTORS(CObservationRFID);
TEST_CLASS_MOVE_COPY_CTORS(CObservationBeaconRanges);
TEST_CLASS_MOVE_COPY_CTORS(CObservationComment);
TEST_CLASS_MOVE_COPY_CTORS(CObservationGasSensors);
TEST_CLASS_MOVE_COPY_CTORS(CObservationGPS);
TEST_CLASS_MOVE_COPY_CTORS(CObservationReflectivity);
TEST_CLASS_MOVE_COPY_CTORS(CObservationIMU);
TEST_CLASS_MOVE_COPY_CTORS(CObservationOdometry);
TEST_CLASS_MOVE_COPY_CTORS(CObservationRange);
TEST_CLASS_MOVE_COPY_CTORS(CObservationImage);
TEST_CLASS_MOVE_COPY_CTORS(CObservationStereoImages);
TEST_CLASS_MOVE_COPY_CTORS(CObservationCANBusJ1939);
TEST_CLASS_MOVE_COPY_CTORS(CObservationRawDAQ);
TEST_CLASS_MOVE_COPY_CTORS(CObservation6DFeatures);
TEST_CLASS_MOVE_COPY_CTORS(CObservationVelodyneScan);
TEST_CLASS_MOVE_COPY_CTORS(CActionRobotMovement2D);
TEST_CLASS_MOVE_COPY_CTORS(CActionRobotMovement3D);
TEST(
Observations,
WriteReadToMem
);
TEST(
Observations,
WriteReadToOctectVectors
);
static bool aux_get_sample_data(mrpt::obs::CObservation&);
static bool aux_get_sample_data(mrpt::obs::CAction&);
static bool aux_get_sample_data(mrpt::obs::CObservation2DRangeScan& o);
static bool aux_get_sample_data(mrpt::obs::CObservationImage& o);
static bool aux_get_sample_data(mrpt::obs::CObservationStereoImages& o);
template <class T>
void run_copy_tests();
TEST(
Observations,
CopyCtorAssignOp
);
IMPLEMENTS_SERIALIZABLE(
Foo,
CSerializable,
MyNS
);
TEST(
Serialization,
CustomClassSerialize
);
TEST(
Serialization,
ArchiveSharedPtrs
);
TEST(
Serialization,
optionalObjects
);
TEST(
Serialization,
enums
);
TEST(
CSimpleMap,
ParseFileInFormat_v1_5
);
void generic_dump_BESTPOS(
const Message_NV_OEM6_BESTPOS::content_t& fields,
std::ostream& out
);
void generic_dump_MARKTIME(
const Message_NV_OEM6_MARKTIME::content_t& fields,
std::ostream& out
);
void generic_getFieldValues_MARKTIME(
const Message_NV_OEM6_MARKTIME::content_t& fields,
std::ostream& o
);
static std::string stripNamespace(const std::string& n);
MRPT_FILL_ENUM_MEMBER(
TCullFace,
NONE
);
MRPT_FILL_ENUM_MEMBER(
TCullFace,
BACK
);
MRPT_FILL_ENUM_MEMBER(
TCullFace,
FRONT
);
bool solveEqn(
double a,
double b,
double c,
double& t
);
IMPLEMENTS_SERIALIZABLE(
CEllipsoid2D,
CRenderizableShaderWireFrame,
mrpt::opengl
);
IMPLEMENTS_SERIALIZABLE(
CEllipsoid3D,
CRenderizableShaderWireFrame,
mrpt::opengl
);
IMPLEMENTS_SERIALIZABLE(
CEllipsoidInverseDepth2D,
CRenderizableShaderWireFrame,
mrpt::opengl
);
IMPLEMENTS_SERIALIZABLE(
CEllipsoidInverseDepth3D,
CRenderizableShaderWireFrame,
mrpt::opengl
);
IMPLEMENTS_SERIALIZABLE(
CEllipsoidRangeBearing2D,
CRenderizableShaderWireFrame,
mrpt::opengl
);
static float imageDiff(
const mrpt::img::CImage& im1,
const mrpt::img::CImage& im2
);
static void test_opengl_CFBORender(const bool useCameraFromIntrinsics);
void aux_add3DpointWithEigenVectors(
const double x,
const double y,
const double z,
std::vector<mrpt::math::CMatrixFixed<float, 3, 1>>& pts,
const mrpt::math::CMatrixFixed<double, 3, 3>& M,
const mrpt::math::CMatrixFixed<double, 3, 1>& mean
);
IMPLEMENTS_SERIALIZABLE(CGridPlaneXY, CRenderizableShaderWireFrame, mrpt::opengl);
IMPLEMENTS_SERIALIZABLE(CGridPlaneXZ, CRenderizableShaderWireFrame, mrpt::opengl);
mrpt::math::TPolygonWithPlane createPolygonFromTriangle(const std::pair<mrpt::opengl::TTriangle, CMesh::TTriangleVertexIndices>& p);
bool sort_voxels_z(
const COctoMapVoxels::TVoxel& a,
const COctoMapVoxels::TVoxel& b
);
bool getVerticesAndFaces(
const vector<math::TPolygon3D>& polys,
vector<TPoint3D>& vertices,
vector<CPolyhedron::TPolyhedronFace>& faces
);
bool analyzeJohnsonPartsString(
const std::string& components,
uint32_t numBaseEdges,
vector<JohnsonBodyPart>& parts
);
size_t additionalVertices(
JohnsonBodyPart j,
uint32_t numBaseEdges
);
void insertCupola(
size_t numBaseEdges,
double angleShift,
double baseRadius,
double edgeLength,
bool isRotated,
bool isUpwards,
size_t base,
vector<TPoint3D>& verts,
vector<CPolyhedron::TPolyhedronFace>& faces
);
void insertRotunda(
double angleShift,
double baseRadius,
bool isRotated,
bool isUpwards,
size_t base,
vector<TPoint3D>& verts,
vector<CPolyhedron::TPolyhedronFace>& faces
);
size_t additionalFaces(
JohnsonBodyPart j,
uint32_t numBaseEdges
);
bool faceContainsEdge(
const CPolyhedron::TPolyhedronFace& f,
const CPolyhedron::TPolyhedronEdge& e
);
bool getPlanesIntersection(
const vector<const TPlane*>& planes,
TPoint3D& pnt
);
bool searchForFace(
const vector<CPolyhedron::TPolyhedronFace>& fs,
uint32_t v1,
uint32_t v2,
uint32_t v3
);
bool searchForEdge(
const vector<CPolyhedron::TPolyhedronEdge>& es,
uint32_t v1,
uint32_t v2,
size_t& where
);
bool searchForEdge(
const vector<CPolyhedron::TPolyhedronFace>::const_iterator& begin,
const vector<CPolyhedron::TPolyhedronFace>::const_iterator& end,
uint32_t v1,
uint32_t v2
);
double getHeight(
const TPolygon3D& p,
const TPoint3D& c
);
IMPLEMENTS_VIRTUAL_SERIALIZABLE(
CRenderizableShaderTexturedTriangles,
CRenderizable,
mrpt::opengl
);
IMPLEMENTS_SERIALIZABLE(
CSetOfTriangles,
CRenderizableShaderTriangles,
mrpt::opengl
);
PlyElement* find_element(
PlyFile* plyfile,
const std::string& s
);
PlyProperty* find_property(
PlyElement* elem,
const std::string& s,
int* index
);
void write_scalar_type(
FILE* fp,
int code
);
vector<string> get_words(
FILE* fp,
string& orig_line
);
void write_binary_item(
FILE* fp,
int int_val,
unsigned int uint_val,
double double_val,
int type
);
void write_ascii_item(
FILE* fp,
int int_val,
unsigned int uint_val,
double double_val,
int type
);
void add_element(
PlyFile* plyfile,
const vector<string>& words
);
void add_property(
PlyFile* plyfile,
const vector<string>& words
);
void add_comment(
PlyFile* plyfile,
const string& line
);
void add_obj_info(
PlyFile* plyfile,
const string& line
);
void copy_property(
PlyProperty* dest,
const PlyProperty* src
);
void store_item(
char* item,
int type,
int int_val,
unsigned int uint_val,
double double_val
);
void get_stored_item(
void* ptr,
int type,
int* int_val,
unsigned int* uint_val,
double* double_val
);
double get_item_value(
const char*,
int
);
void get_ascii_item(
const char* word,
int type,
int* int_val,
unsigned int* uint_val,
double* double_val
);
int get_binary_item(
FILE* fp,
int bin_file_type,
int type,
int* int_val,
unsigned int* uint_val,
double* double_val
);
void ascii_get_element(
PlyFile* plyfile,
char* elem_ptr
);
void binary_get_element(
PlyFile* plyfile,
char* elem_ptr
);
PlyFile* ply_write(
FILE* fp,
const vector<string>& elem_names,
int file_type
);
PlyFile* ply_open_for_writing(
const char* name,
const vector<string>& elem_names,
int file_type,
float* version
);
void ply_describe_element(
PlyFile* plyfile,
const string& elem_name,
int nelems,
vector<PlyProperty>& prop_list
);
void ply_describe_property(
PlyFile* plyfile,
const char* elem_name,
const PlyProperty* prop
);
void ply_element_count(
PlyFile* plyfile,
const string& elem_name,
int nelems
);
void ply_header_complete(PlyFile* plyfile);
void ply_put_element_setup(
PlyFile* plyfile,
const string& elem_name
);
void ply_put_element(
PlyFile* plyfile,
void* elem_ptr
);
void ply_put_comment(
PlyFile* plyfile,
const string& comment
);
void ply_put_obj_info(
PlyFile* plyfile,
const string& obj_info
);
PlyFile* ply_read(
FILE* fp,
vector<string>& elem_names
);
PlyFile* ply_open_for_reading(
const char* filename,
vector<string>& elem_names,
int* file_type,
float* version
);
vector<PlyProperty> ply_get_element_description(
PlyFile* plyfile,
const string& elem_name,
int& nelems,
int& nprops
);
void ply_get_property(
PlyFile* plyfile,
const string& elem_name,
const PlyProperty* prop
);
void ply_get_element(
PlyFile* plyfile,
void* elem_ptr
);
void ply_get_comments(
PlyFile* plyfile,
vector<string>& comments
);
void ply_get_obj_info(
PlyFile* plyfile,
vector<string>& obj_info
);
void ply_close(PlyFile* plyfile);
void ply_get_info(
PlyFile* ply,
float* version,
int* file_type
);
double get_item_value(
char* item,
int type
);
int get_prop_type(const string& type_name);
static std::tuple<mrpt::math::TPoint2Df, float> projectToScreenCoordsAndDepth(
const mrpt::math::TPoint3Df& localPt,
const mrpt::opengl::TRenderMatrices& objState
);
static unsigned char* reserveDataBuffer(
size_t len,
std::vector<uint8_t>& data
);
static void azimuthElevationFromDirection(
const mrpt::math::TVector3Df& v,
float& elevation,
float& azimuth
);
TEST(
OpenGL,
perspectiveMatrix
);
TEST(
OpenGL,
orthoMatrix
);
TEST(
OpenGL,
perspectiveMatrixFromPinhole
);
static int sizeFromRatio(
const int startCoord,
const double dSize,
const int iLength
);
static int startFromRatio(
const double frac,
const int dSize
);
MRPT_FILL_ENUM_MEMBER(
mrpt::poses,
imSpline
);
MRPT_FILL_ENUM_MEMBER(
mrpt::poses,
imLinear2Neig
);
MRPT_FILL_ENUM_MEMBER(
mrpt::poses,
imLinear4Neig
);
MRPT_FILL_ENUM_MEMBER(
mrpt::poses,
imSSLLLL
);
MRPT_FILL_ENUM_MEMBER(
mrpt::poses,
imLinearSlerp
);
MRPT_FILL_ENUM_MEMBER(
mrpt::poses,
imSplineSlerp
);
template <class POSE_T>
void readFileWithPoses(
const std::string& fname,
std::vector<POSE_T>* poses_vec,
std::vector<mrpt::system::TTimeStamp>* timestamps = NULL,
bool substract_init_offset = false
);
TEST(
CPoint,
toFromString_2D
);
TEST(
CPoint,
toFromString_3D
);
TEST(
CPose2DInterpolator,
interp
);
TEST_F(
Pose3DTests,
DefaultValues
);
TEST_F(
Pose3DTests,
Initialization
);
TEST_F(
Pose3DTests,
OperatorBracket
);
TEST_F(
Pose3DTests,
InverseHM
);
TEST_F(
Pose3DTests,
Compose
);
TEST_F(
Pose3DTests,
composeFrom
);
TEST_F(
Pose3DTests,
ToFromCPose2D
);
TEST_F(
Pose3DTests,
ComposeAndInvComposeWithPoint
);
TEST_F(
Pose3DTests,
ComposePointJacob
);
TEST_F(
Pose3DTests,
ComposePointJacobApprox
);
TEST_F(
Pose3DTests,
InvComposePointJacob
);
TEST_F(
Pose3DTests,
ComposePointJacob_se3
);
TEST_F(
Pose3DTests,
InvComposePointJacob_se3
);
TEST_F(
Pose3DTests,
ExpLnEqual
);
TEST_F(
Pose3DTests,
Jacob_dExpe_de_at_0
);
TEST_F(
Pose3DTests,
Jacob_dLnT_dT
);
TEST_F(
Pose3DTests,
Jacob_dexpeD_de
);
TEST_F(
Pose3DTests,
Jacob_dDexpe_de
);
TEST_F(
Pose3DTests,
Jacob_dAexpeD_de
);
TEST_F(
Pose3DTests,
translation
);
TEST(
CPose3DInterpolator,
interp
);
template <class MAT33, class MAT66>
void cov2to3(
const MAT33& c2d,
MAT66& c3d
);
static void aux_posequat2poseypr(
const CVectorFixedDouble<7>& x,
] const double& dummy,
CVectorFixedDouble<6>& y
);
TEST_F(
Pose3DPDFGaussTests,
ToQuatGaussPDFAndBack
);
TEST_F(
Pose3DPDFGaussTests,
CompositionJacobian
);
TEST_F(
Pose3DPDFGaussTests,
AllOperators
);
TEST_F(
Pose3DPDFGaussTests,
ChangeCoordsRef
);
TEST(
CPose3DPDFGrid,
uniformDistribution
);
TEST(
CPose3DPDFGrid,
setManualPDF
);
static void quat_vs_YPR(
double yaw,
double pitch,
double roll,
double qx,
double qy,
double qz,
double qw,
const std::string& sRotMat
);
TEST(
QuatTests,
Quat_vs_YPR
);
TEST_F(
Pose3DQuatTests,
FromYPRAndBack
);
TEST_F(
Pose3DQuatTests,
UnaryInverse
);
TEST_F(
Pose3DQuatTests,
CopyOperator
);
TEST_F(
Pose3DQuatTests,
Compose
);
TEST_F(
Pose3DQuatTests,
ComposeWithPoint
);
TEST_F(
Pose3DQuatTests,
ComposeWithPointJacob
);
TEST_F(
Pose3DQuatTests,
InvComposeWithPoint
);
TEST_F(
Pose3DQuatTests,
InvComposeWithPointJacob
);
TEST_F(
Pose3DQuatTests,
ComposeInvComposePoint
);
TEST_F(
Pose3DQuatTests,
ComposePoint_vs_CPose3D
);
TEST_F(
Pose3DQuatTests,
InvComposePoint_vs_CPose3D
);
TEST_F(
Pose3DQuatTests,
SphericalCoordsJacobian
);
TEST_F(
Pose3DQuatTests,
NormalizationJacobian
);
void aux_poseypr2posequat(
const CVectorFixedDouble<6>& x,
] const double& dummy,
CVectorFixedDouble<7>& y
);
TEST_F(
Pose3DQuatPDFGaussTests,
ToYPRGaussPDFAndBack
);
TEST_F(
Pose3DQuatPDFGaussTests,
CompositionJacobian
);
TEST_F(
Pose3DQuatPDFGaussTests,
Inverse
);
TEST_F(
Pose3DQuatPDFGaussTests,
Composition
);
TEST_F(
Pose3DQuatPDFGaussTests,
InverseComposition
);
TEST_F(
Pose3DQuatPDFGaussTests,
RelativeDisplacement
);
TEST_F(
Pose3DQuatPDFGaussTests,
ChangeCoordsRef
);
poses::CPosePDFGaussian operator + (
const mrpt::poses::CPose2D& A,
const mrpt::poses::CPosePDFGaussian& B
);
TEST_F(
PosePDFGaussTests,
Inverse
);
poses::CPosePDFGaussianInf operator + (
const mrpt::poses::CPose2D& A,
const mrpt::poses::CPosePDFGaussianInf& B
);
TEST(
CPosePDFGrid,
defaultCtor
);
TEST(
CPosePDFGrid,
resize
);
TEST(
CPosePDFGrid,
basicOps
);
TEST_F(
QuaternionTests,
crossProduct
);
TEST_F(
QuaternionTests,
gimbalLock
);
TEST_F(
QuaternionTests,
ToYPRAndBack
);
TEST_F(
QuaternionTests,
LnAndExpMatches
);
TEST_F(
QuaternionTests,
ExpAndLnMatches
);
TEST_F(
QuaternionTests,
ThrowOnNotNormalized
);
TEST_F(
QuaternionTests,
ensurePositiveRealPart
);
TEST(
CRobot2DPoseEstimator,
defaultCtor
);
TEST(
CRobot2DPoseEstimator,
extrapolateRobotPose
);
TEST(
CRobot2DPoseEstimator,
integrateOdometryAndLocalization
);
template <int DIM>
void run_tf_test1(const mrpt::poses::CPose2D& A2B_);
TEST(
FrameTransformer,
SimplePublishAndLookup
);
TEST_F(
SE3_traits_tests,
SE3_jacobs_DinvP1InvP2
);
TEST_F(
SE3_traits_tests,
SE3_jacobs_dAB_dAB
);
TEST_F(
SE2_traits_tests,
SE2_jacobs_DinvP1InvP2
);
TEST_F(
SE2_traits_tests,
SE2_jacobs_dAB_dAB
);
template <typename VEC3, typename MAT3x3, typename MAT3x9>
void M3x9(
const VEC3& a,
const MAT3x3& B,
MAT3x9& RES
);
void run_test_so2_avrg(
const double* angs,
const size_t N,
const double ang_correct_avr
);
TEST(
SE2_SE3_avrg,
SO2_average
);
void run_test_so3_avrg(
const double* angs,
const size_t N,
const mrpt::math::CMatrixDouble33& correct_avr
);
TEST(
SE2_SE3_avrg,
SO3_average
);
TEST(
Random,
Randomize
);
TEST(
Random,
KnownSequence
);
TEST(
Random,
drawGaussianMultivariateMany
);
TEST(
Random,
portable_uniform_distribution
);
TEST(
Random,
shuffle
);
uint32_t hiBit(const uint32_t u);
uint32_t loBit(const uint32_t u);
uint32_t loBits(const uint32_t u);
uint32_t mixBits(
const uint32_t u,
const uint32_t v
);
uint32_t twist(
const uint32_t m,
const uint32_t s0,
const uint32_t s1
);
void getEmptyRosMsg(nav_msgs::OccupancyGrid& msg);
TEST(
Map,
basicTestHeader
);
TEST(
Map,
check_ros2mrpt_and_back
);
void getEmptyRosMsg(nav_msgs::msg::OccupancyGrid& msg);
TEST(
Map,
basicTestHeader
);
TEST(
Map,
check_ros2mrpt_and_back
);
static bool check_field(
const sensor_msgs::PointField& input_field,
std::string check_name,
const sensor_msgs::PointField** output
);
static void get_float_from_field(
const sensor_msgs::PointField* field,
const unsigned char* data,
float& output
);
static void get_uint16_from_field(
const sensor_msgs::PointField* field,
const unsigned char* data,
uint16_t& output
);
static bool check_field(
const sensor_msgs::msg::PointField& input_field,
std::string check_name,
const sensor_msgs::msg::PointField** output
);
static void get_float_from_field(
const sensor_msgs::msg::PointField* field,
const unsigned char* data,
float& output
);
static void get_uint16_from_field(
const sensor_msgs::msg::PointField* field,
const unsigned char* data,
uint16_t& output
);
TEST(
PointCloud2,
toROS
);
TEST(
PointCloud2,
toROS
);
TEST(
PoseConversions,
copyMatrix3x3ToCMatrixDouble33
);
TEST(
PoseConversions,
copyCMatrixDouble33ToMatrix3x3
);
TEST(
PoseConversions,
reference_frame_change_with_rotations
);
void check_CPose3D_tofrom_ROS(
double x,
double y,
double z,
double yaw,
double pitch,
double roll
);
TEST(
PoseConversions,
check_CPose3D_tofrom_ROS
);
TEST(
PoseConversions,
check_CPose2D_to_ROS
);
TEST(
PoseConversions,
copyMatrix3x3ToCMatrixDouble33
);
TEST(
PoseConversions,
copyCMatrixDouble33ToMatrix3x3
);
TEST(
PoseConversions,
reference_frame_change_with_rotations
);
void check_CPose3D_tofrom_ROS(
double x,
double y,
double z,
double yaw,
double pitch,
double roll
);
TEST(
PoseConversions,
check_CPose3D_tofrom_ROS
);
TEST(
PoseConversions,
check_CPose2D_to_ROS
);
template <class MSG_T>
void fromROS_variance(
const MSG_T& msg,
mrpt::obs::CObservationRange& obj
);
template <class MSG_T>
void toROS_variance(
MSG_T& msg,
const mrpt::obs::CObservationRange::TMeasurement& m
);
TEST(
Time,
basicTest
);
TEST(
Time,
basicTest
);
static std::string& ltrim(std::string& s);
static std::string& rtrim(std::string& s);
static std::string& trim(std::string& s);
void do_register();
TEST(
rtti,
CObject_CLASSID
);
TEST(
rtti,
MyDerived1_CLASSID
);
TEST(
rtti,
Factory
);
TEST(
rtti,
CreateSmartPointerTypes
);
TEST(
rtti,
CListOfClasses
);
TEST(
Serialization,
bimap
);
TEST(
Serialization,
STL_stdvector
);
TEST(
Serialization,
STL_stdmap
);
TEST(
Serialization,
STL_complex_error_type
);
TEST(
Serialization,
optional_STL
);
CArchive& operator << (
CArchive& a,
const Foo& f
);
CArchive& operator >> (
CArchive& a,
Foo& f
);
TEST(
Serialization,
vector_custom_type
);
TEST(
Serialization,
vector_shared_ptr
);
MRPT_FILL_ENUM_MEMBER(
CGridMapAligner,
amRobustMatch
);
MRPT_FILL_ENUM_MEMBER(
CGridMapAligner,
amCorrelation
);
MRPT_FILL_ENUM_MEMBER(
CGridMapAligner,
amModifiedRANSAC
);
MRPT_FILL_ENUM(icpClassic);
MRPT_FILL_ENUM(icpLevenbergMarquardt);
MRPT_FILL_ENUM(icpCovLinealMSE);
MRPT_FILL_ENUM(icpCovFiniteDifferences);
MRPT_FILL_ENUM_MEMBER(
mrpt::slam,
smMETRIC_MAP_MATCHING
);
MRPT_FILL_ENUM_MEMBER(
mrpt::slam,
smOBSERVATION_OVERLAP
);
MRPT_FILL_ENUM_MEMBER(
mrpt::slam,
smCUSTOM_FUNCTION
);
MRPT_FILL_ENUM(assocNN);
MRPT_FILL_ENUM(assocJCBB);
MRPT_FILL_ENUM(metricMaha);
MRPT_FILL_ENUM(metricML);
static bool myVectorOrder(
const pair<size_t, float>& o1,
const pair<size_t, float>& o2
);
TEST_F(
ICPTests,
AlignScans_icpClassic
);
TEST_F(
ICPTests,
AlignScans_icpLevenbergMarquardt
);
TEST_F(
ICPTests,
RayTracingICP3D
);
static double eval_similarity_metric_map_matching(
const CIncrementalMapPartitioner* parent,
const map_keyframe_t& kf1,
const map_keyframe_t& kf2,
const mrpt::poses::CPose3D& relPose2wrt1
);
static double eval_similarity_observation_overlap(
const map_keyframe_t& kf1,
const map_keyframe_t& kf2,
const mrpt::poses::CPose3D& relPose2wrt1
);
TEST(
CIncrementalMapPartitioner,
test_dataset
);
void run_test_pf_localization(
CPose2D& meanPose,
CMatrixDouble33& cov
);
TEST(
MonteCarlo2D,
RunSampleDataset
);
TEST(
DataAssociation,
TestNoICs
);
bool ransac_data_assoc_run();
TEST(
tfest,
ransac_data_assoc
);
MRPT_FILL_ENUM(LVL_DEBUG);
MRPT_FILL_ENUM(LVL_INFO);
MRPT_FILL_ENUM(LVL_WARN);
MRPT_FILL_ENUM(LVL_ERROR);
MRPT_FILL_ENUM_CUSTOM_NAME(
LVL_DEBUG,
"DEBUG"
);
MRPT_FILL_ENUM_CUSTOM_NAME(
LVL_INFO,
"INFO"
);
MRPT_FILL_ENUM_CUSTOM_NAME(
LVL_WARN,
"WARN"
);
MRPT_FILL_ENUM_CUSTOM_NAME(
LVL_ERROR,
"ERROR"
);
TEST(
Base64,
RandomEncDec
);
bool cmpFileEntriesName_Asc(
const CDirectoryExplorer::TFileInfo& a,
const CDirectoryExplorer::TFileInfo& b
);
bool cmpFileEntriesName_Desc(
const CDirectoryExplorer::TFileInfo& a,
const CDirectoryExplorer::TFileInfo& b
);
template <typename T, typename... U>
size_t getAddress(std::function<T(U...)> f);
unsigned long CRC32Value(
int i,
const uint32_t CRC32_POLYNOMIAL
);
TEST(
crc,
crc32
);
std::string aux_format_string_multilines(
const std::string& s,
size_t len
);
static void doTimLogEntry(
mrpt::system::CTimeLogger& tl,
const char* name,
const int ms
);
TEST(
CTimeLogger,
getLastTime
);
TEST(
CTimeLogger,
getMeanTime
);
TEST(
CTimeLogger,
printStats
);
TEST(
CTimeLogger,
printStatsFaulty
);
TEST(
CTimeLogger,
multithread
);
static unsigned int calcSecFractions(const uint64_t tmp);
static std::string implIntervalFormat(const double seconds);
TEST(
DateTime,
dateTimeVsClock
);
TEST(
DateTime,
time_t_forth_back
);
TEST(
DateTime,
fixed_date_check
);
TEST(
DateTime,
double_to_from
);
TEST(
DateTime,
timestampAdd
);
std::string p2s(const fs::path& p);
TEST(
FileSystem,
fileNameChangeExtension
);
TEST(
FileSystem,
extractFileExtension
);
TEST(
FileSystem,
extractFileDirectory
);
TEST(
FileSystem,
extractFileName
);
TEST(
FileSystem,
filePathSeparatorsToNative
);
TEST(
FileSystem,
toAbsolutePath
);
TEST(
FileSystem,
pathJoin
);
std::ostream& operator << (
std::ostream& out,
MD5 md5
);
void my_aux_sighandler(int);
int myKbhit();
template void mrpt::system::tokenize< std::deque< std::string > >(
const std::string& inString,
const std::string& inDelimiters,
std::deque<std::string>& outTokens,
bool skipBlankTokens
);
template void mrpt::system::tokenize< std::vector< std::string > >(
const std::string& inString,
const std::string& inDelimiters,
std::vector<std::string>& outTokens,
bool skipBlankTokens
);
template <typename STRING_LIST>
static void impl_stringListAsString(
const STRING_LIST& lst,
std::string& outText,
const std::string& newline
);
TEST(
string_utils,
firstNLines
);
TEST(
thread_name,
set_get_current_thread
);
static void testerThread(const std::string& myName);
TEST(
thread_name,
set_get_other_thread
);
static mrpt::tfest::internal::se2_l2_impl_return_t<float> se2_l2_impl(const TMatchingPairList& in_correspondences);
void markAsPicked(
const TMatchingPair& c,
std::vector<bool>& alreadySelectedThis,
std::vector<bool>& alreadySelectedOther
);
static bool se3_l2_internal(
std::vector<mrpt::math::TPoint3D>& points_this,
std::vector<mrpt::math::TPoint3D>& points_other,
mrpt::poses::CPose3DQuat& out_transform,
double& out_scale,
bool forceScaleToUnity
);
CPose3DQuat generate_points(
TPoints& pA,
TPoints& pB
);
template <typename T>
void generate_list_of_points(
const TPoints& pA,
const TPoints& pB,
TMatchingPairListTempl<T>& list
);
void generate_vector_of_points(
const TPoints& pA,
const TPoints& pB,
vector<mrpt::math::TPoint3D>& ptsA,
vector<mrpt::math::TPoint3D>& ptsB
);
template <typename T>
void se3_l2_MatchList_test();
TEST(
tfest,
se3_l2_MatchList_float
);
TEST(
tfest,
se3_l2_MatchList_double
);
TEST(
tfest,
se3_l2_PtsLists
);
TEST(
tfest,
se3_l2_robust
);
void do_test_geodetic_geocentric(const TGeodeticCoords c1);
TEST(
TopographyConversion,
GeodeticToGeocentricToGeodetic
);
TEST(
TopographyConversion,
geodeticToENU_WGS84
);
template <class T>
std::set<T> make_set(
const T& v0,
const T& v1
);
TEST(
TopographyReconstructPathFrom3RTK,
sampleDataset
);
MRPT_FILL_ENUM_MEMBER(
TestColors,
Black
);
MRPT_FILL_ENUM_MEMBER(
TestColors,
Gray
);
MRPT_FILL_ENUM_MEMBER(
TestColors,
White
);
MRPT_FILL_ENUM(North);
MRPT_FILL_ENUM(East);
MRPT_FILL_ENUM(South);
MRPT_FILL_ENUM(West);
TEST(
TEnumType,
str2value
);
TEST(
TEnumType,
value2str
);
TEST(
StaticString,
ctor
);
TEST(
StaticString,
concat_literals
);
TEST(
StaticString,
concat_multi
);
TEST(
num_to_string,
ctor
);
DECLARE_CUSTOM_TTYPENAME(MyFooClass);
DECLARE_CUSTOM_TTYPENAME(MyNS::MyBarClass);
TEST(
TTypeName,
types2str
);
TEST(
TTypeName,
types2str_shared_ptr
);
TEST(
TTypeName,
types2stdstring
);
constexpr int foo_i_below_10(unsigned i);
TEST(
XAssert,
build_time
);
template <bool POSES_INVERSE>
void reprojectionResidualsElement(
const TCamera& camera_params,
const TFeatureObservation& OBS,
std::array<double, 2>& out_residual,
const TFramePosesVec::value_type& frame,
const TLandmarkLocationsVec::value_type& point,
double& sum,
const bool use_robust_kernel,
const double kernel_param,
double* out_kernel_1st_deriv
);
static void extractLines_CannyHough(
const cv::Mat& canny_image,
const std::vector<cv::Vec2f> lines,
std::vector<cv::Vec4i>& segments,
size_t threshold
);
bool find_chessboard_corners_multiple(
const CImage& img_,
CvSize pattern_size,
std::vector<std::vector<CvPoint2D32f>>& out_corners
);
bool do_special_dilation(
CImage& thresh_img,
const int dilations,
IplConvKernel* kernel_cross,
IplConvKernel* kernel_rect,
IplConvKernel* kernel_diag1,
IplConvKernel* kernel_diag2,
IplConvKernel* kernel_horz,
IplConvKernel* kernel_vert
);
int cvFindChessboardCorners3(
const CImage& img_,
CvSize pattern_size,
std::vector<CvPoint2D32f>& out_corners
);
double triangleArea(
double x0,
double y0,
double x1,
double y1,
double x2,
double y2
);
double median(const std::vector<double>& vec);
void icvCleanFoundConnectedQuads(
std::vector<CvCBQuad::Ptr>& quad_group,
const CvSize& pattern_size
);
void icvFindConnectedQuads(
std::vector<CvCBQuad::Ptr>& quad,
std::vector<CvCBQuad::Ptr>& out_group,
const int group_idx,
] const int dilation
);
void mrLabelQuadGroup(
std::vector<CvCBQuad::Ptr>& quad_group,
const CvSize& pattern_size,
bool firstRun
);
void mrFindQuadNeighbors2(
std::vector<CvCBQuad::Ptr>& quads,
int dilation
);
int mrAugmentBestRun(
std::vector<CvCBQuad::Ptr>& new_quads,
int new_dilation,
std::vector<CvCBQuad::Ptr>& old_quads,
int old_dilation
);
int icvGenerateQuads(
vector<CvCBQuad::Ptr>& out_quads,
vector<CvCBCorner::Ptr>& out_corners,
const CImage& image,
int flags,
] int dilation,
bool firstRun
);
int myQuads2Points(
const std::vector<CvCBQuad::Ptr>& output_quads,
const CvSize& pattern_size,
std::vector<CvPoint2D32f>& out_corners
);
void quadListMakeUnique(std::vector<CvCBQuad::Ptr>& quads);
int cvFindChessboardCorners3(
const mrpt::img::CImage& img_,
CvSize pattern_size,
std::vector<CvPoint2D32f>& out_corners
);
bool find_chessboard_corners_multiple(
const mrpt::img::CImage& img_,
CvSize pattern_size,
std::vector<std::vector<CvPoint2D32f>>& out_corners
);
int icvGenerateQuads(
std::vector<CvCBQuad::Ptr>& quads,
std::vector<CvCBCorner::Ptr>& corners,
const mrpt::img::CImage& img,
int flags,
int dilation,
bool firstRun
);
void mrFindQuadNeighbors2(
std::vector<CvCBQuad::Ptr>& quads,
int dilation
);
int mrAugmentBestRun(
std::vector<CvCBQuad::Ptr>& new_quads,
int new_dilation,
std::vector<CvCBQuad::Ptr>& old_quads,
int old_dilation
);
void icvFindConnectedQuads(
std::vector<CvCBQuad::Ptr>& in_quads,
std::vector<CvCBQuad::Ptr>& out_quad_group,
const int group_idx,
const int dilation
);
void mrLabelQuadGroup(
std::vector<CvCBQuad::Ptr>& quad_group,
const CvSize& pattern_size,
bool firstRun
);
void icvCleanFoundConnectedQuads(
std::vector<CvCBQuad::Ptr>& quads,
const CvSize& pattern_size
);
int myQuads2Points(
const std::vector<CvCBQuad::Ptr>& output_quads,
const CvSize& pattern_size,
std::vector<CvPoint2D32f>& out_corners
);
void quadListMakeUnique(std::vector<CvCBQuad::Ptr>& quads);
bool do_special_dilation(
mrpt::img::CImage& thresh_img,
const int dilations,
IplConvKernel* kernel_cross,
IplConvKernel* kernel_rect,
IplConvKernel* kernel_diag1,
IplConvKernel* kernel_diag2,
IplConvKernel* kernel_horz,
IplConvKernel* kernel_vert
);
static void jacob_db_dp(
const TPoint3D& p,
mrpt::math::CMatrixFixed<double, 2, 3>& G
);
static void jacob_dh_db_and_dh_dc(
const TPoint3D& nP,
const mrpt::math::CVectorFixedDouble<9>& c,
mrpt::math::CMatrixFixed<double, 2, 2>& Hb,
mrpt::math::CMatrixFixed<double, 2, 9>& Hc
);
static void jacob_deps_D_p_deps(
const TPoint3D& p_D,
mrpt::math::CMatrixFixed<double, 3, 6>& dpl_del
);
static void jacob_dA_eps_D_p_deps(
const CPose3D& A,
const CPose3D& D,
const TPoint3D& p,
mrpt::math::CMatrixFixed<double, 3, 6>& dp_deps
);
static void project_point(
const mrpt::math::TPoint3D& P,
const mrpt::img::TCamera& params,
const mrpt::math::TPose3D& cameraPose,
mrpt::img::TPixelCoordf& px
);
images resize(NUM_IMGS);
for();
EXPECT_LT(
out. final_rmse,
3. 0
);
EXPECT_GT(
out. final_iters,
10UL
);
EXPECT_NEAR(
out.cam_params.rightCameraPose. x,
0. 1194,
0. 005
);
EXPECT_EQ(
out.image_pair_was_used. size (),
NUM_IMGS
);
template <bool FASTLOAD>
bool buildPyramid_templ(
CImagePyramid& obj,
mrpt::img::CImage& img,
size_t nOctaves,
const bool smooth_halves,
const bool convert_grayscale
);
static void do_rectify(
const CStereoRectifyMap& me,
const cv::Mat& src_left,
const cv::Mat& src_right,
cv::Mat& out_left,
cv::Mat& out_right,
int16_t* map_xl,
int16_t* map_xr,
uint16_t* map_yl,
uint16_t* map_yr,
int interp_method
);
int solve_deg2(
double a,
double b,
double c,
double& x1,
double& x2
);
int solve_deg3(double a, double b, double c, double d, double& x0, double& x1, double& x2);
int solve_deg4(
double a,
double b,
double c,
double d,
double e,
double& x0,
double& x1,
double& x2,
double& x3
);
int solve_deg2(
double a,
double b,
double c,
double& x1,
double& x2
);
int solve_deg3(double a, double b, double c, double d, double& x0, double& x1, double& x2);
int solve_deg4(
double a,
double b,
double c,
double d,
double e,
double& x0,
double& x1,
double& x2,
double& x3
);
// macros
#define ADD_COLOR_MAP(c)
#define APPERTURE
#define APPERTURE
#define APPERTURE
#define ASRT_FAIL( \
__CONDITIONSTR, \
__A, \
__B, \
__ASTR, \
__BSTR \
)
#define ASSERTDEBMSG_( \
f, \
__ERROR_MSG \
)
#define ASSERTDEB_(f)
#define ASSERTDEB_EQUAL_( \
__A, \
__B \
)
#define ASSERTDEB_GE_( \
__A, \
__B \
)
#define ASSERTDEB_GT_( \
__A, \
__B \
)
#define ASSERTDEB_LE_( \
__A, \
__B \
)
#define ASSERTDEB_LT_( \
__A, \
__B \
)
#define ASSERTDEB_NOT_EQUAL_( \
__A, \
__B \
)
#define ASSERTMSG_( \
f, \
__ERROR_MSG \
)
#define ASSERT_(f)
#define ASSERT_DIRECTORY_EXISTS_(DIR)
#define ASSERT_EQUAL_( \
__A, \
__B \
)
#define ASSERT_FILE_EXISTS_(FIL)
#define ASSERT_GE_( \
__A, \
__B \
)
#define ASSERT_GT_( \
__A, \
__B \
)
#define ASSERT_LE_( \
__A, \
__B \
)
#define ASSERT_LT_( \
__A, \
__B \
)
#define ASSERT_NEAR_( \
__A, \
__B, \
__TOLERANCE \
)
#define ASSERT_NOT_EQUAL_( \
__A, \
__B \
)
#define BIG_STRING
#define BUFFER_OFFSET(offset)
#define BUILD_128BIT_CONST( \
_name, \
B0, \
B1, \
B2, \
B3, \
B4, \
B5, \
B6, \
B7, \
B8, \
B9, \
B10, \
B11, \
B12, \
B13, \
B14, \
B15 \
)
#define CALIB_DECIMAT
#define CARCHIVE_VERBOSE
#define CASCADE
#define CASCADE_CONST
#define CHECK_AND_RET_ERROR( \
_COND_, \
_MSG_ \
)
#define CHECK_AND_RET_ERROR( \
_COND_, \
_MSG_ \
)
#define CHECK_AND_RET_ERROR( \
_COND_, \
_MSG_ \
)
#define CHECK_AND_RET_ERROR( \
_COND_, \
_MSG_ \
)
#define CHECK_FC2_ERROR(_err)
#define CHECK_MEMBER(_m)
#define CHECK_TRICLOPS_ERROR(_err)
#define CLASS_ID(T)
#define CLASS_ID_NAMESPACE( \
class_name, \
namespaceName \
)
#define CLASS_ID_TEMPLATE( \
class_name, \
T \
)
#define COMMON_PTG_DESIGN_PARAMS
#define COPY_MEMBER(_m)
#define CV_PI
#define C_MAX_BLOCKS_IN_MCU
#define DCTSIZE
#define DCTSIZE2
#define DECLARE_CUSTOM_TTYPENAME(_TYPE)
#define DECLARE_MEXPLUS_FROM(complete_type)
#define DECLARE_MEX_CONVERSION
#define DECLARE_OP_FUNCTION(_NAME)
#define DECLARE_TTYPENAME_CLASSNAME(_CLASSNAME)
#define DEFAULT_LOGLVL_MRPT_UNSCOPED
#define DEFINE_GENERIC_SENSOR(class_name)
#define DEFINE_SCHEMA_SERIALIZABLE()
#define DEFINE_SERIALIZABLE( \
class_name, \
NS \
)
#define DEFINE_VIRTUAL_MRPT_OBJECT(class_name)
#define DEFINE_VIRTUAL_SERIALIZABLE(class_name)
#define DEF_TYPESTR(_NAME)
#define DEG2RAD
#define DOFOR(_MSG_ID)
#define DO_MATDYN_INSTANTIATION(T_)
#define DO_MATDYN_INSTANTIATION(T_)
#define DO_MATDYN_INSTANTIATION(T_)
#define DO_MATDYN_INSTANTIATION(T_)
#define DO_MATDYN_INSTANTIATION(T_)
#define DO_MATDYN_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION(T_)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_MATFIXED_INSTANTIATION_NM( \
T_, \
N_, \
M_ \
)
#define DO_RECURSE_CHILD( \
INDEX, \
SEQ0, \
SEQ1, \
SEQ2, \
SEQ3, \
SEQ4, \
SEQ5, \
SEQ6, \
SEQ7 \
)
#define DO_VECDYN_INSTANTIATION(T_)
#define DO_VECDYN_INSTANTIATION(T_)
#define DO_VECFIXED_INSTANTIATION(T_)
#define DO_VECFIXED_INSTANTIATION(T_)
#define DO_VECFIXED_INSTANTIATION_NM( \
T_, \
N_ \
)
#define DO_VECFIXED_INSTANTIATION_NM( \
T_, \
N_ \
)
#define DUMP_IMU_DATA(x)
#define D_MAX_BLOCKS_IN_MCU
#define EPSILON_LHM
#define EXPLICIT_INSTANT_ransac_detect_2D_lines(_TYPE_)
#define EXPLICIT_INST_ransac_detect_3D_planes(_TYPE_)
#define F5(t)
#define FC2_BUF_IMG
#define FC2_CAM
#define FC2_CAM_INFO
#define FILE_ATTRIB_ARCHIVE
#define FILE_ATTRIB_DIRECTORY
#define FILL_JOINT_DATA( \
_J1, \
_J2 \
)
#define FRBITS
#define GL_GLEXT_PROTOTYPES
#define GNSS_BINARY_MSG_DEFINITION_END
#define GNSS_BINARY_MSG_DEFINITION_MID
#define GNSS_BINARY_MSG_DEFINITION_MID_END
#define GNSS_BINARY_MSG_DEFINITION_START(_MSG_ID)
#define GNSS_MESSAGE_BINARY_BLOCK( \
DATA_PTR, \
DATA_LEN \
)
#define GRAPHS_TESTS(_TYPE)
#define HAVE_BOOLEAN
#define HAVE_FBO
#define
#define
#define
#define HEADER_PIXEL( \
data, \
pixel \
)
#define IMAGE_ALLOC_PERFLOG
#define IMPLEMENTS_GENERIC_SENSOR( \
class_name, \
NameSpace \
)
#define IMPLEMENTS_MEXPLUS_FROM(complete_type)
#define IMPLEMENTS_MRPT_OBJECT( \
class_name, \
base, \
NameSpace \
)
#define IMPLEMENTS_SERIALIZABLE( \
class_name, \
base, \
NameSpace \
)
#define IMPLEMENTS_VIRTUAL_MRPT_OBJECT( \
class_name, \
base, \
NS \
)
#define IMPLEMENTS_VIRTUAL_SERIALIZABLE( \
class_name, \
base_class, \
NS \
)
#define IMPLEMENTS_VIRTUAL_SERIALIZABLE_NS_PREFIX( \
class_name, \
base_class, \
NS \
)
#define INT16_MAX
#define INT16_MAX
#define INT16_MIN
#define INT16_MIN
#define INT8_MAX
#define INT8_MAX
#define INT8_MIN
#define INT8_MIN
#define INTERNAL_IMPLEMENTS_MRPT_OBJECT( \
class_name, \
base, \
NameSpace, \
class_registry_name \
)
#define INTERNAL_IMPLEMENTS_VIRTUAL_MRPT_OBJECT( \
class_name, \
base_name, \
NS, \
registered_name \
)
#define INTERNAL_MRPT_LOG( \
_LVL, \
_STRING \
)
#define INTERNAL_MRPT_LOG_FMT( \
_LVL, \
_FMT_STRING, \
... \
)
#define INTERNAL_MRPT_LOG_ONCE( \
_LVL, \
_STRING \
)
#define INTERNAL_MRPT_LOG_STREAM( \
_LVL, \
__CONTENTS \
)
#define INTERNAL_MRPT_LOG_THROTTLE( \
_LVL, \
_PERIOD_SECONDS, \
_STRING \
)
#define INTERNAL_MRPT_LOG_THROTTLE_FMT( \
_LVL, \
_PERIOD_SECONDS, \
_FMT_STRING, \
... \
)
#define INTERNAL_MRPT_LOG_THROTTLE_STREAM( \
_LVL, \
_PERIOD_SECONDS, \
__CONTENTS \
)
#define INTPRECNUMBIT
#define INVALID_SOCKET
#define INVALID_TIMESTAMP
#define INV_POSES_BOOL
#define IS_CLASS( \
obj, \
class_name \
)
#define IS_DERIVED( \
obj, \
class_name \
)
#define JDCT_DEFAULT
#define JDCT_FASTEST
#define JMSG_LENGTH_MAX
#define JMSG_STR_PARM_MAX
#define JPEG_APP0
#define JPEG_COM
#define JPEG_EOI
#define JPEG_HEADER_OK
#define JPEG_HEADER_TABLES_ONLY
#define JPEG_LIB_VERSION
#define JPEG_REACHED_EOI
#define JPEG_REACHED_SOS
#define JPEG_ROW_COMPLETED
#define JPEG_RST0
#define JPEG_SCAN_COMPLETED
#define JPEG_SUSPENDED
#define JPOOL_IMAGE
#define JPOOL_NUMPOOLS
#define JPOOL_PERMANENT
#define JPP(arglist)
#define KINECT_H
#define KINECT_RANGES_TABLE_LEN
#define KINECT_RANGES_TABLE_MASK
#define KINECT_W
#define KM_ASSERT(expression)
#define LIK_LF_CACHE_INVALID
#define LIST_ALL_MSGS
#define LOADABLEOPTS_DUMP_VAR( \
variableName, \
variableType \
)
#define LOADABLEOPTS_DUMP_VAR_DEG(variableName)
#define LOAD_FONT(FONTNAME)
#define LOG( \
verbose, \
text \
)
#define LOOP_MAX_COUNT
#define LUT_TABLE
#define MAKEWORD16B( \
__LOBYTE, \
__HILOBYTE \
)
#define MAKEWORD32B( \
__LOWORD16, \
__HIWORD16 \
)
#define MAKEWORD64B( \
__LOWORD32, \
__HIWORD32 \
)
#define MAP_DEFINITION_END(_CLASS_NAME_)
#define MAP_DEFINITION_REGISTER( \
_CLASSNAME_STRINGS, \
_CLASSNAME_WITH_NS \
)
#define MAP_DEFINITION_START(_CLASS_NAME_)
#define MASK2BYTES
#define MASK3BYTES
#define MASK4BYTES
#define MASK5BYTES
#define MASK6BYTES
#define MASKBITS
#define MASKBYTE
#define MAX_COMPS_IN_SCAN
#define MAX_CONTOUR_APPROX
#define MAX_SAMP_FACTOR
#define MAX_USERS
#define MCP_LOAD_OPT( \
Yaml__, \
Var__ \
)
#define MCP_LOAD_OPT_DEG( \
Yaml__, \
Var__ \
)
#define MCP_LOAD_REQ( \
Yaml__, \
Var__ \
)
#define MCP_LOAD_REQ_DEG( \
Yaml__, \
Var__ \
)
#define MCP_SAVE( \
Yaml__, \
Var__ \
)
#define MCP_SAVE_DEG( \
Yaml__, \
Var__ \
)
#define MRPT_CHECK_GCC_VERSION( \
major, \
minor \
)
#define MRPT_CHECK_NORMAL_NUMBER(v)
#define MRPT_CHECK_VISUALC_VERSION(major)
#define MRPT_DAQmxCfgInputBuffer
#define MRPT_DAQmxCfgOutputBuffer
#define MRPT_DAQmxCfgSampClkTiming
#define MRPT_DAQmxClearTask
#define MRPT_DAQmxCreateAIVoltageChan
#define MRPT_DAQmxCreateAOVoltageChan
#define MRPT_DAQmxCreateCIAngEncoderChan
#define MRPT_DAQmxCreateCICountEdgesChan
#define MRPT_DAQmxCreateCILinEncoderChan
#define MRPT_DAQmxCreateCIPeriodChan
#define MRPT_DAQmxCreateCIPulseWidthChan
#define MRPT_DAQmxCreateCOPulseChanFreq
#define MRPT_DAQmxCreateDIChan
#define MRPT_DAQmxCreateDOChan
#define MRPT_DAQmxCreateTask
#define MRPT_DAQmxGetExtendedErrorInfo
#define MRPT_DAQmxReadAnalogF64
#define MRPT_DAQmxReadCounterF64
#define MRPT_DAQmxReadDigitalU8
#define MRPT_DAQmxStartTask
#define MRPT_DAQmxStopTask
#define MRPT_DAQmxWriteAnalogF64
#define MRPT_DAQmxWriteDigitalLines
#define MRPT_DAQmxWriteDigitalU32
#define MRPT_DAQmx_ErrChk(functionCall)
#define MRPT_DECLARE_TTYPENAME(_TYPE)
#define MRPT_DECLARE_TTYPENAME_CONTAINER(_CONTAINER)
#define MRPT_DECLARE_TTYPENAME_CONTAINER_ASSOC(_CONTAINER)
#define MRPT_DECLARE_TTYPENAME_CONTAINER_FIX_SIZE(_CONTAINER)
#define MRPT_DECLARE_TTYPENAME_NAMESPACE( \
_TYPE, \
__NS \
)
#define MRPT_DECLARE_TTYPENAME_NO_NAMESPACE( \
_TYPE, \
__NS \
)
#define MRPT_DECLARE_TTYPENAME_PTR(_TYPE)
#define MRPT_DECLARE_TTYPENAME_PTR_NAMESPACE( \
_TYPE, \
__NS \
)
#define MRPT_END
#define MRPT_END_WITH_CLEAN_UP(stuff)
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
#define MRPT_ENUM_TYPE_BEGIN_NAMESPACE( \
_NAMESPACE, \
_ENUM_TYPE_WITH_NS \
)
#define MRPT_ENUM_TYPE_END()
#define MRPT_FILL_ENUM(_X)
#define MRPT_FILL_ENUM_CUSTOM_NAME( \
_X, \
_NAME \
)
#define MRPT_FILL_ENUM_MEMBER( \
_CLASS, \
_VALUE \
)
#define MRPT_HAS_OPENCV
#define MRPT_HAS_SOME_NIDAQMX
#define MRPT_INITIALIZER(f)
#define MRPT_LIKELY(EXPR)
#define MRPT_LOAD_CONFIG_VAR( \
variableName, \
variableType, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_CONFIG_VAR_CAST( \
variableName, \
variableType, \
variableTypeCast, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_CONFIG_VAR_CAST_NO_DEFAULT( \
variableName, \
variableType, \
variableTypeCast, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_CONFIG_VAR_CS( \
variableName, \
variableType \
)
#define MRPT_LOAD_CONFIG_VAR_DEGREES( \
variableName, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_CONFIG_VAR_DEGREES_NO_DEFAULT( \
variableName, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_CONFIG_VAR_DEGREESf( \
variableName, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_CONFIG_VAR_NO_DEFAULT( \
variableName, \
variableType, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_CONFIG_VAR_REQUIRED_CS( \
variableName, \
variableType \
)
#define MRPT_LOAD_HERE_CONFIG_VAR( \
variableName, \
variableType, \
targetVariable, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_HERE_CONFIG_VAR_CAST( \
variableName, \
variableType, \
variableTypeCast, \
targetVariable, \
configFileObject, \
sectionNameStr \
)
#define MRPT_LOAD_HERE_CONFIG_VAR_CAST_NO_DEFAULT( \
variableName, \
variableType, \
variableTypeCast, \
targetVariable, \
configFileObject