50 #include <Eigen/Dense> 68 " pf-localization - Part of the MRPT\n" 69 " MRPT C++ Library: %s - Sources timestamp: %s\n\n",
80 const std::string configFile = std::string(
argv[1]);
118 static constexpr
bool PF_IS_3D =
false;
127 PARTICLE_COUNT, init_min.
x, init_max.
x, init_min.
y, init_max.
y,
128 init_min.
yaw, init_max.
yaw);
137 init_min.
x, init_max.
x, init_min.
y, init_max.
y, init_min.
yaw,
138 init_max.
yaw, PARTICLE_COUNT);
145 static constexpr
bool PF_IS_3D =
true;
164 template <
class MONTECARLO_TYPE>
170 std::vector<int> particles_count;
176 sect,
"particles_count", std::vector<int>(1, 0), particles_count,
178 string OUT_DIR_PREFIX =
179 cfg.read_string(
sect,
"logOutput_dir",
"",
true);
182 string MAP_FILE = cfg.read_string(
sect,
"map_file",
"");
183 size_t rawlog_offset = cfg.read_int(
sect,
"rawlog_offset", 0);
184 string GT_FILE = cfg.read_string(
sect,
"ground_truth_path_file",
"");
185 const auto NUM_REPS = cfg.read_uint64_t(
sect,
"experimentRepetitions", 1);
186 int SCENE3D_FREQ = cfg.read_int(
sect,
"3DSceneFrequency", 10);
187 bool SCENE3D_FOLLOW = cfg.read_bool(
sect,
"3DSceneFollowRobot",
true);
188 unsigned int testConvergenceAt =
189 cfg.read_int(
sect,
"experimentTestConvergenceAtStep", -1);
191 bool SAVE_STATS_ONLY = cfg.read_bool(
sect,
"SAVE_STATS_ONLY",
false);
192 bool DO_RELIABILITY_ESTIMATE =
false;
193 bool DO_SCAN_LIKELIHOOD_DEBUG =
false;
197 bool SHOW_PROGRESS_3D_REAL_TIME =
198 cfg.read_bool(
sect,
"SHOW_PROGRESS_3D_REAL_TIME",
false);
199 int SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS =
200 cfg.read_int(
sect,
"SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS", 1);
201 double STATS_CONF_INTERVAL =
202 cfg.read_double(
sect,
"STATS_CONF_INTERVAL", 0.2);
205 initial_odo.
x(cfg.read_double(
sect,
"initial_odo_x", 0));
206 initial_odo.
y(cfg.read_double(
sect,
"initial_odo_y", 0));
207 initial_odo.
phi(cfg.read_double(
sect,
"initial_odo_phi", 0));
209 #if !MRPT_HAS_WXWIDGETS 210 SHOW_PROGRESS_3D_REAL_TIME =
false;
217 actOdom2D_params.
modelSelection = CActionRobotMovement2D::mmGaussian;
219 cfg.read_double(
"DummyOdometryParams",
"minStdXY", 0.04);
221 DEG2RAD(cfg.read_double(
"DummyOdometryParams",
"minStdPHI", 2.0));
225 cfg.read_double(
"DummyOdometryParams",
"additional_std_XYZ", 0.01);
226 actOdom3D_params.mm6DOFModel.additional_std_angle =
DEG2RAD(
227 cfg.read_double(
"DummyOdometryParams",
"additional_std_angle", 0.1));
246 <<
"MAP_FILE : " << MAP_FILE << endl
247 <<
"GT_FILE : " << GT_FILE << endl
248 <<
"OUT_DIR_PREFIX : " << OUT_DIR_PREFIX << endl
249 <<
"particles_count :" << particles_count << endl);
263 std::stringstream ss;
264 pfOptions.dumpToTextStream(ss);
283 if (!mapExt.compare(
"simplemap"))
293 "Map loaded ok, with " << simpleMap.
size() <<
" frames.");
299 MRPT_LOG_INFO(
"Building metric map(s) from '.simplemap'...");
303 else if (!mapExt.compare(
"gridmap"))
319 "Map file has unknown extension: '%s'", mapExt.c_str());
338 cfg.read_double(
sect,
"init_PDF_min_x", 0),
339 cfg.read_double(
sect,
"init_PDF_min_y", 0),
340 cfg.read_double(
sect,
"init_PDF_min_z", 0),
346 cfg.read_double(
sect,
"init_PDF_max_x", 0),
347 cfg.read_double(
sect,
"init_PDF_max_y", 0),
348 cfg.read_double(
sect,
"init_PDF_max_z", 0),
354 "Initial PDF limits:\n Min=" << init_min.asString()
355 <<
"\n Max=" << init_max.asString());
361 grid->computeEntropy(gridInfo);
363 "The gridmap has %.04fm2 observed area, %u observed cells.",
364 gridInfo.effectiveMappedArea,
365 (
unsigned)gridInfo.effectiveMappedCells);
369 gridInfo.effectiveMappedArea =
370 (init_max.x - init_min.x) * (init_max.y - init_min.y);
373 for (
int PARTICLE_COUNT : particles_count)
376 "Initial PDF: %f particles/m2",
377 PARTICLE_COUNT / gridInfo.effectiveMappedArea);
380 int nConvergenceTests = 0, nConvergenceOK = 0;
382 std::mutex convergenceErrors_mtx;
389 std::vector<unsigned int> rep_indices(NUM_REPS);
390 std::iota(rep_indices.begin(), rep_indices.end(), 0);
398 auto run_localization_code = [&](
const size_t repetition) {
399 CVectorDouble indivConvergenceErrors, executionTimes, odoError;
401 "====== RUNNING FOR " << PARTICLE_COUNT
402 <<
" INITIAL PARTICLES - Repetition " 403 << 1 + repetition <<
" / " << NUM_REPS);
407 if (SHOW_PROGRESS_3D_REAL_TIME)
409 win3D = std::make_shared<CDisplayWindow3D>(
410 "pf-localization - The MRPT project", 1000, 600);
411 win3D->setCameraAzimuthDeg(-45);
417 if (SCENE3D_FREQ > 0 || SHOW_PROGRESS_3D_REAL_TIME)
422 pts->boundingBox(bbox_min, bbox_max);
426 bbox_min.
x, bbox_max.x, bbox_min.
y, bbox_max.y, 0, 5));
429 win3D->setCameraZoom(
432 bbox_max.x - bbox_min.
x, bbox_max.y - bbox_min.
y));
440 string sOUT_DIR_PARTS, sOUT_DIR_3D;
441 const auto sOUT_DIR =
format(
442 "%s_%03u_%07i", OUT_DIR_PREFIX.c_str(), repetition,
449 if (!SAVE_STATS_ONLY)
451 sOUT_DIR_PARTS =
format(
"%s/particles", sOUT_DIR.c_str());
452 sOUT_DIR_3D =
format(
"%s/3D", sOUT_DIR.c_str());
455 "Creating directory: %s", sOUT_DIR_PARTS.c_str());
461 "Creating directory: %s", sOUT_DIR_3D.c_str());
470 int M = PARTICLE_COUNT;
475 pdf.options = pdfPredictionOptions;
484 size_t rawlogEntry = 0;
490 sect,
"init_PDF_mode",
false,
495 pdf, metricMap, PARTICLE_COUNT, init_min, init_max);
501 pdf, PARTICLE_COUNT, init_min, init_max);
505 "PDF of %u particles initialized in %.03fms", M,
506 1000 * tictac.
Tac());
509 format(
"%s/particles_0_initial.txt", sOUT_DIR_PARTS.c_str()));
514 CPose2D odometryEstimation = initial_odo;
516 using PDF_MEAN_TYPE =
typename MONTECARLO_TYPE::type_value;
518 PDF_MEAN_TYPE pdfEstimation;
525 if (!SAVE_STATS_ONLY)
527 f_cov_est.
open(sOUT_DIR.c_str() + string(
"/cov_est.txt"));
528 f_pf_stats.
open(sOUT_DIR.c_str() + string(
"/PF_stats.txt"));
529 f_odo_est.
open(sOUT_DIR.c_str() + string(
"/odo_est.txt"));
533 CPose2D last_used_abs_odo(0, 0, 0),
534 pending_most_recent_odo(0, 0, 0);
539 if (allow_quit_on_esc_key &&
os::kbhit())
552 if (!impl_get_next_observations(action, observations, obs))
577 pending_most_recent_odo = obs_odo->odometry;
578 static bool is_1st_odo =
true;
582 last_used_abs_odo = pending_most_recent_odo;
590 observations = std::make_shared<CSensoryFrame>();
591 observations->insert(obs);
596 action = std::make_shared<CActionCollection>();
603 pending_most_recent_odo - last_used_abs_odo);
604 last_used_abs_odo = pending_most_recent_odo;
607 odo_incr, actOdom3D_params);
608 action->insert(actOdom3D);
615 pending_most_recent_odo - last_used_abs_odo;
616 last_used_abs_odo = pending_most_recent_odo;
619 odo_incr, actOdom2D_params);
620 action->insert(actOdom2D);
631 if (observations->size() > 0)
633 observations->getObservationByIndex(0)->timestamp;
635 cur_obs_timestamp = obs->timestamp;
637 if (step >= rawlog_offset)
641 if (step > rawlog_offset)
644 if (SHOW_PROGRESS_3D_REAL_TIME)
646 const auto [
cov, meanPose] =
647 pdf.getCovarianceAndMean();
649 if (rawlogEntry >= 2)
651 expectedPose, rawlogEntry - 2, GT,
662 auto el = CEllipsoid3D::Create();
668 el->enableDrawSolid3D(
false);
672 auto el = CEllipsoid2D::Create();
678 el->enableDrawSolid3D(
false);
680 ellip->setName(
"parts_cov");
681 ellip->setColor(1, 0, 0, 0.6);
691 cov.template blockCopy<3, 3>());
698 cov.template blockCopy<2, 2>());
705 meanPose.x(), meanPose.y(), ellipse_z);
709 win3D->get3DSceneAndLock();
711 win3D->setCameraPointingToPoint(
712 meanPose.x(), meanPose.y(), 0);
714 win3D->addTextMessage(
723 win3D->addTextMessage(
727 static_cast<unsigned int>(pdf.size())),
730 win3D->addTextMessage(
733 "mean pose (x y phi_deg)= %s",
734 meanPose.asString().c_str()),
737 *ptrSceneWin = scene;
738 win3D->unlockAccess3DScene();
741 win3D->forceRepaint();
743 std::this_thread::sleep_for(
744 std::chrono::milliseconds(
745 SHOW_PROGRESS_3D_REAL_TIME_DELAY_MS));
752 if (!SAVE_STATS_ONLY)
756 << step <<
". Executing ParticleFilter on " 757 << pdf.particlesCount() <<
" particles...");
767 double run_time = tictac.
Tac();
769 if (!SAVE_STATS_ONLY)
772 "Done in %.03fms, ESS=%f", 1e3 * run_time,
780 action->getBestMovementEstimation();
785 best_mov_estim->poseChange->getMeanVal();
788 pdf.getMean(pdfEstimation);
792 fill_out_estimated_path)
794 out_estimated_path.insert(
800 expectedPose, rawlogEntry, GT, cur_obs_timestamp);
802 if (expectedPose.
x() != 0 || expectedPose.
y() != 0 ||
803 expectedPose.
phi() != 0)
807 for (
size_t k = 0; k < pdf.size(); k++)
808 sumW += exp(pdf.getW(k));
809 for (
size_t k = 0; k < pdf.size(); k++)
811 const auto pk = pdf.getParticlePose(k);
813 expectedPose.
x() - pk.x,
814 expectedPose.
y() - pk.y) *
815 exp(pdf.getW(k)) / sumW;
817 convergenceErrors_mtx.lock();
819 convergenceErrors_mtx.unlock();
821 indivConvergenceErrors.
push_back(locErr);
826 const auto [C, M] = pdf.getCovarianceAndMean();
827 const auto current_pdf_gaussian =
832 if (!SAVE_STATS_ONLY)
835 "Odometry estimation: " << odometryEstimation);
838 << pdfEstimation <<
", ESS (B.R.)= " 840 << std::sqrt(current_pdf_gaussian.cov.trace()));
844 "Ground truth: " << expectedPose);
849 double obs_reliability_estim = .0;
850 if (DO_RELIABILITY_ESTIMATE)
855 obs_scan = observations->getObservationByClass<
862 if (obs_scan && gridmap)
870 COccupancyGridMap2D::sumUnscented;
877 ssu_params.
aperture = obs_scan->aperture;
879 ssu_params.
nRays = obs_scan->getScanSize();
882 ssu_params.
maxRange = obs_scan->maxRange;
884 gridmap->laserScanSimulatorWithUncertainty(
885 ssu_params, ssu_out);
892 obs_reliability_estim =
894 *obs_scan, evalParams);
896 if (DO_SCAN_LIKELIHOOD_DEBUG)
900 std::vector<float> ranges_mean, ranges_obs;
901 for (
size_t i = 0; i < obs_scan->getScanSize();
904 ranges_mean.push_back(
907 ranges_obs.push_back(
908 obs_scan->getScanRange(i));
911 win.plot(ranges_mean,
"3k-",
"mean");
912 win.plot(ranges_obs,
"r-",
"obs");
914 Eigen::VectorXd ci1 =
923 Eigen::VectorXd ci2 =
932 win.plot(ci1,
"k-",
"CI+");
933 win.plot(ci2,
"k-",
"CI-");
936 "obs_reliability_estim: %f",
937 obs_reliability_estim));
942 "Reliability measure [0-1]: " 943 << obs_reliability_estim);
946 if (!SAVE_STATS_ONLY)
950 "%u %e %e %f %f\n", (
unsigned int)pdf.size(),
953 obs_reliability_estim,
954 sqrt(current_pdf_gaussian.cov.det()));
956 "%f %f %f\n", odometryEstimation.
x(),
957 odometryEstimation.
y(), odometryEstimation.
phi());
960 const auto [
cov, meanPose] = pdf.getCovarianceAndMean();
962 if ((!SAVE_STATS_ONLY && SCENE3D_FREQ > 0) ||
963 SHOW_PROGRESS_3D_REAL_TIME)
974 GTpt = std::make_shared<CDisk>();
975 GTpt = std::make_shared<CDisk>();
977 GTpt->setColor(0, 0, 0, 0.9);
980 ->setDiskRadius(0.04f);
984 GTpt->setPose(expectedPose);
993 auto p = pdf.template getAs3DObject<
995 p->setName(
"particles");
1005 scanPts = std::make_shared<CPointCloud>();
1006 scanPts->setName(
"scan");
1007 scanPts->setColor(1, 0, 0, 0.9);
1009 ->enableColorFromZ(
false);
1017 CPose3D robotPose3D(meanPose);
1020 observations->insertObservationsInto(&map);
1023 ->loadFromPointsMap(&map);
1034 CCamera& cam = view1->getCamera();
1043 if (!SAVE_STATS_ONLY && SCENE3D_FREQ != -1 &&
1044 ((step + 1) % SCENE3D_FREQ) == 0)
1048 "%s/progress_%05u.3Dscene", sOUT_DIR_3D.c_str(),
1054 pdf.saveToTextFile(
format(
1055 "%s/particles_%05u.txt", sOUT_DIR_PARTS.c_str(),
1064 if (step == testConvergenceAt)
1066 nConvergenceTests++;
1071 if (pdfEstimation.distanceTo(expectedPose) < 2)
1078 indivConvergenceErrors.
saveToTextFile(sOUT_DIR +
"/GT_error.txt");
1088 const auto max_num_threads = std::thread::hardware_concurrency();
1089 size_t runs_per_thread = NUM_REPS;
1090 if (max_num_threads > 1)
1091 runs_per_thread =
static_cast<size_t>(
1092 std::ceil((NUM_REPS) / static_cast<double>(max_num_threads)));
1095 "Running " << NUM_REPS <<
" repetitions, on max " << max_num_threads
1096 <<
" parallel threads: " << runs_per_thread
1097 <<
" runs/thread.");
1099 std::vector<std::thread> running_tasks;
1100 for (
size_t r = 0; r < NUM_REPS; r += runs_per_thread)
1102 auto runner = [&](
size_t i_start,
size_t i_end) {
1103 if (i_end > NUM_REPS) i_end = NUM_REPS;
1104 for (
size_t i = i_start; i < i_end; i++)
1105 run_localization_code(i);
1108 running_tasks.emplace_back(runner, r, r + runs_per_thread);
1109 std::this_thread::sleep_for(std::chrono::milliseconds(100));
1113 for (
auto& t : running_tasks)
1114 if (t.joinable()) t.join();
1116 double repetitionTime = tictacGlobal.
Tac();
1119 double covergenceErrorMean = 0, convergenceErrorsMin = 0,
1120 convergenceErrorsMax = 0;
1121 if (!convergenceErrors.
empty())
1123 convergenceErrors, covergenceErrorMean, convergenceErrorsMin,
1124 convergenceErrorsMax, STATS_CONF_INTERVAL);
1129 format(
"%s_SUMMARY.txt", OUT_DIR_PREFIX.c_str()),
1133 "%% Ratio_covergence_success #particles " 1134 "average_time_per_execution convergence_mean_error " 1135 "convergence_error_conf_int_inf " 1136 "convergence_error_conf_int_sup " 1138 if (!nConvergenceTests) nConvergenceTests = 1;
1140 "%f %u %f %f %f %f\n",
1141 ((
double)nConvergenceOK) / nConvergenceTests, PARTICLE_COUNT,
1142 repetitionTime / NUM_REPS, covergenceErrorMean,
1143 convergenceErrorsMin, convergenceErrorsMax);
1160 if (GT.
cols() == 4 || GT.
cols() == 7)
1162 bool GT_index_is_time;
1169 floor(GT(0, 0)) != GT(0, 0) && floor(GT(1, 0)) != GT(1, 0);
1173 GT_index_is_time =
false;
1176 if (GT_index_is_time)
1179 using namespace std::chrono_literals;
1181 bool interp_ok =
false;
1182 GT_path.interpolate(cur_time, expectedPose, interp_ok);
1195 size_t k, N = GT.
rows();
1196 for (k = 0; k < N; k++)
1198 if (GT(k, 0) == rawlogEntry)
break;
1203 expectedPose.
x(GT(k, 1));
1204 expectedPose.
y(GT(k, 2));
1205 expectedPose.
phi(GT(k, 3));
1209 else if (GT.
cols() == 3)
1211 if ((
int)rawlogEntry < GT.
rows())
1213 expectedPose.
x(GT(rawlogEntry, 0));
1214 expectedPose.
y(GT(rawlogEntry, 1));
1215 expectedPose.
phi(GT(rawlogEntry, 2));
1218 else if (GT.
cols() > 0)
1228 if (GT.
cols() == 4 || GT.
cols() == 7)
1230 const bool GT_is_3D = (GT.
cols() == 7);
1231 bool GT_index_is_time =
false;
1238 floor(GT(0, 0)) != GT(0, 0) && floor(GT(1, 0)) != GT(1, 0);
1241 if (GT_index_is_time)
1244 using namespace std::chrono_literals;
1245 GT_path.setMaxTimeInterpolation(200ms);
1247 for (
int i = 0; i < GT.
rows(); i++)
1251 TPose2D(GT(i, 1), GT(i, 2), GT(i, GT_is_3D ? 4 : 3)));
1262 const bool is_3D =
params.read_bool(
sect,
"use_3D_poses",
false);
1267 do_pf_localization<CMonteCarloLocalization3D>();
1272 do_pf_localization<CMonteCarloLocalization2D>();
1283 setLoggerName(
"MonteCarloLocalization_Rawlog");
1291 m_rawlogFileName = std::string(
argv[2]);
1293 m_rawlogFileName =
params.read_string(
1294 sect,
"rawlog_file", std::string(
"log.rawlog"),
true);
1296 m_rawlog_offset =
params.read_int(
sect,
"rawlog_offset", 0);
mrpt::poses::CPosePDFGaussian robotPose
The robot pose Gaussian, in map coordinates.
void clear()
Erase all the contents of the map.
A namespace of pseudo-random numbers generators of diferent distributions.
void resetUniform(const double x_min, const double x_max, const double y_min, const double y_max, const double phi_min=-M_PI, const double phi_max=M_PI, const int particlesCount=-1)
Reset the PDF to an uniformly distributed one, inside of the defined 2D area [x_min,x_max]x[y_min,y_max] (in meters) and for orientations [phi_min, phi_max] (in radians).
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
virtual int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
double Tac() noexcept
Stops the stopwatch.
double minStdPHI
Additional uncertainty: [degrees].
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
bool createDirectory(const std::string &dirName)
Creates a directory.
static time_point fromDouble(const double t) noexcept
Create a timestamp from its double representation.
The struct for passing extra simulation parameters to the prediction stage when running a particle fi...
void prepareGT(const mrpt::math::CMatrixDouble >)
mrpt::config::CConfigFileMemory params
Populated in initialize().
void run()
Runs with the current parameter set.
void resetUniformFreeSpace(mrpt::maps::COccupancyGridMap2D *theMap, const double freeCellsThreshold=0.7, const int particlesCount=-1, const double x_min=-1e10f, const double x_max=1e10f, const double y_min=-1e10f, const double y_max=1e10f, const double phi_min=-M_PI, const double phi_max=M_PI)
Reset the PDF to an uniformly distributed one, but only in the free-space of a given 2D occupancy-gri...
void setOrthogonal(bool v=true)
Enable/Disable orthogonal mode (vs.
std::chrono::time_point< Clock > time_point
void loadFromProbabilisticPosesAndObservations(const mrpt::maps::CSimpleMap &Map)
Load the map contents from a CSimpleMap object, erasing all previous content of the map...
mrpt::obs::CObservation2DRangeScanWithUncertainty scanWithUncert
The scan + its uncertainty.
#define THROW_EXCEPTION(msg)
Create a GUI window and display plots with MATLAB-like interfaces and commands.
int getch() noexcept
An OS-independent version of getch, which waits until a key is pushed.
std::string std::string format(std::string_view fmt, ARGS &&... args)
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
mrpt::poses::CPose3D sensorPose
(Default: at origin) The 6D pose of the sensor on the robot at the moment of starting the scan...
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
Output params for laserScanSimulatorWithUncertainty()
float rangeNoiseStd
(Default: 0) The standard deviation of measurement noise.
void randomize(const uint32_t seed)
Initialize the PRNG from the given random seed.
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
A high-performance stopwatch, with typical resolution of nanoseconds.
static void resetUniform(CMonteCarloLocalization3D &pdf, size_t PARTICLE_COUNT, const mrpt::math::TPose3D &init_min, const mrpt::math::TPose3D &init_max)
static void resetOnFreeSpace(CMonteCarloLocalization3D &pdf, mrpt::maps::CMultiMetricMap &metricMap, size_t PARTICLE_COUNT, const mrpt::math::TPose3D &init_min, const mrpt::math::TPose3D &init_max)
double minStdXY
Additional uncertainty: [meters].
mrpt::vision::TStereoCalibParams params
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
void computeFromOdometry(const mrpt::poses::CPose2D &odometryIncrement, const TMotionModelOptions &options)
Computes the PDF of the pose increment from an odometry reading and according to the given motion mod...
static void resetOnFreeSpace(CMonteCarloLocalization2D &pdf, mrpt::maps::CMultiMetricMap &metricMap, size_t PARTICLE_COUNT, const mrpt::math::TPose3D &init_min, const mrpt::math::TPose3D &init_max)
std::string MRPT_getCompilationDate()
Returns the MRPT source code timestamp, according to the Reproducible-Builds specifications: https://...
CObservation2DRangeScan rangeScan
The observation with the mean ranges in the scan field.
The parameter to be passed to "computeFromOdometry".
T::Ptr mapByClass(size_t ith=0) const
Returns the i'th map of a given class (or of a derived class), or empty smart pointer if there is no ...
float additional_std_XYZ
An additional noise added to the 6DOF model (std.
double yaw
Yaw coordinate (rotation angle over Z axis).
bool rightToLeft
(Default: true) The scanning direction: true=counterclockwise; false=clockwise
Statistics for being returned from the "execute" method.
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
mrpt::maps::CMetricMap * metricMap
[update stage] Must be set to a metric map used to estimate the likelihood of observations ...
void saveToTextFile(const std::string &file, mrpt::math::TMatrixTextFileFormat fileFormat=mrpt::math::MATRIX_FORMAT_ENG, bool appendMRPTHeader=false, const std::string &userHeader=std::string()) const
Saves the vector/matrix to a file compatible with MATLAB/Octave text format.
double weightsVariance_beforeResample
virtual std::string impl_get_usage() const =0
void push_back(const T &val)
void setZoomDistance(float z)
double distanceTo(const CPoseOrPoint< OTHERCLASS, DIM2 > &b) const
Returns the Euclidean distance to another pose/point:
void computeFromOdometry(const mrpt::poses::CPose3D &odometryIncrement, const TMotionModelOptions &options)
Computes the PDF of the pose increment from an odometry reading and according to the given motion mod...
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT's CStream, std::istream, std::ostream, std::stringstream.
void setAzimuthDegrees(float ang)
The parameter to be passed to "computeFromOdometry".
#define ASSERT_(f)
Defines an assertion mechanism.
Represents a probabilistic 3D (6D) movement.
Represents a probabilistic 2D movement of the robot mobile base.
double ESS_beforeResample
mrpt::math::CVectorDouble rangesMean
The same ranges than in rangeScan.getScanRange(), for convenience as a math vector container...
This base provides a set of functions for maths stuff.
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
void confidenceIntervals(const CONTAINER &data, T &out_mean, T &out_lower_conf_interval, T &out_upper_conf_interval, const double confidenceInterval=0.1, const size_t histogramNumBins=1000)
Return the mean and the 10%-90% confidence points (or with any other confidence value) of a set of sa...
std::string lowerCase(const std::string &str)
Returns an lower-case version of a string.
static void resetUniform(CMonteCarloLocalization2D &pdf, size_t PARTICLE_COUNT, const mrpt::math::TPose3D &init_min, const mrpt::math::TPose3D &init_max)
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ionName) override
Loads the configuration for the set of internal maps from a textual definition in an INI-like file...
double phi() const
Get the phi angle of the 2D pose (in radians)
constexpr double DEG2RAD(const double x)
Degrees to radians.
void enableFollowCamera(bool enabled)
If disabled (default), the SceneViewer application will ignore the camera of the "main" viewport and ...
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
void initialize(int argc, const char **argv)
Initializes the application from CLI parameters.
float aperture
(Default: M_PI) The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180...
void setLoggerName(const std::string &name)
Set the name of the COutputLogger instance.
This namespace contains representation of robot actions and observations.
Scalar det() const
Determinant of matrix.
void dumpToTextStream(std::ostream &out) const override
This method dumps the options of the multi-metric map AND those of every internal map...
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
double evaluateScanLikelihood(const CObservation2DRangeScan &otherScan, const TEvalParams ¶ms) const
Returns a measure of the likelihood of a given scan, compared to this scan variances.
std::string extractFileExtension(const std::string &filePath, bool ignore_gz=false)
Extract the extension of a filename.
double x() const
Common members of all points & poses classes.
T hypot_fast(const T x, const T y)
Faster version of std::hypot(), to use when overflow is not an issue and we prefer fast code...
size_t size() const
Returns the count of pairs (pose,sensory data)
This class acts as a common interface to the different interfaces (see CParticleFilter::TParticleFilt...
CMatrixDouble cov(const MATRIX &v)
Computes the covariance matrix from a list of samples in an NxM matrix, where each row is a sample...
This CStream derived class allow using a file as a write-only, binary stream.
mrpt::gui::CDisplayWindow3D::Ptr win
size_type rows() const
Number of rows in the matrix.
size_type cols() const
Number of columns in the matrix.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
TDrawSampleMotionModel modelSelection
The model to be used.
Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x...
void pause(const std::string &msg=std::string("Press any key to continue...")) noexcept
Shows the message "Press any key to continue" (or other custom message) to the current standard outpu...
bool open(const std::string &fileName, bool append=false)
Open the given file for write.
Declares a class that represents a Probability Density Function (PDF) over a 3D pose (x...
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
A class for storing an occupancy grid map.
void do_pf_localization()
const_iterator end() const
#define ASSERT_DIRECTORY_EXISTS_(DIR)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void executeOn(CParticleFilterCapable &obj, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, TParticleFilterStats *stats=nullptr)
Executes a complete prediction + update step of the selected particle filtering algorithm.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
void setElevationDegrees(float ang)
COpenGLViewport::Ptr getViewport(const std::string &viewportName=std::string("main")) const
Returns the viewport with the given name, or nullptr if it does not exist; note that the default view...
TOptions_GaussianModel gaussianModel
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const override
If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points ...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Input params for laserScanSimulatorWithUncertainty()
CRenderizable::Ptr getByName(const std::string &str, const std::string &viewportName=std::string("main"))
Returns the first object with a given name, or nullptr (an empty smart pointer) if not found...
void setContent(const std::vector< std::string > &stringList)
Changes the contents of the virtual "config file".
MonteCarloLocalization_Rawlog()
The configuration of a particle filter.
const float & getScanRange(const size_t i) const
The range values of the scan, in meters.
mrpt::math::CMatrixDouble rangesCovar
The covariance matrix for all the ranges in rangeScan.getScanRange()
TLaserSimulUncertaintyMethod method
(Default: sumMonteCarlo) Select the method to do the uncertainty propagation
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
The namespace for 3D scene representation and rendering.
bool kbhit() noexcept
An OS-independent version of kbhit, which returns true if a key has been pushed.
std::string file_get_contents(const std::string &fileName)
Loads an entire text file and return its contents as a single std::string.
MonteCarloLocalization_Base()
This class allows the user to create, load, save, and render 3D scenes using OpenGL primitives...
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
static CAST_TO::Ptr from(const CAST_FROM_PTR &ptr)
bool deleteFilesInDirectory(const std::string &s, bool deleteDirectoryAsWell=false)
Delete all the files in a given directory (nothing done if directory does not exists, or path is a file).
void resetUniform(const mrpt::math::TPose3D &corner_min, const mrpt::math::TPose3D &corner_max, const int particlesCount=-1)
Reset the PDF to an uniformly distributed one, inside of the defined "cube".
Classes for creating GUI windows for 2D and 3D visualization.
TOptions_6DOFModel mm6DOFModel
float maxRange
(Default: 80) The maximum range allowed by the device, in meters (e.g.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
std::string MRPT_getVersion()
Returns a string describing the MRPT version.
An observation of the current (cumulative) odometry for a wheeled robot.
Saves data to a file and transparently compress the data using the given compression level...
void Tic() noexcept
Starts the stopwatch.
This class stores any customizable set of metric maps.
std::string dateTimeLocalToString(const mrpt::system::TTimeStamp t)
Convert a timestamp into this textual form (in local time): YEAR/MONTH/DAY,HH:MM:SS.MMM.
#define ASSERT_FILE_EXISTS_(FIL)
A camera: if added to a scene, the viewpoint defined by this camera will be used instead of the camer...
void impl_initialize(int argc, const char **argv) override
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
CParticleFilter::TParticleFilterOptions m_options
The options to be used in the PF, must be set before executing any step of the particle filter...
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
void insert(const CRenderizable::Ptr &newObject, const std::string &viewportName=std::string("main"))
Insert a new object into the scene, in the given viewport (by default, into the "main" viewport)...
Used for returning entropy related information.
static Ptr Create(Args &&... args)
#define MRPT_LOG_INFO_FMT(_FMT_STRING,...)
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
void removeObject(const CRenderizable::Ptr &obj, const std::string &viewportName=std::string("main"))
Removes the given object from the scene (it also deletes the object to free its memory).
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
TKLDParams KLD_params
Parameters for dynamic sample size, KLD method.
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers &init)
Sets the list of internal map according to the passed list of map initializers (current maps will be ...
virtual void impl_initialize(int argc, const char **argv)=0
#define MRPT_LOG_INFO(_STRING)
void setPointingAt(float x, float y, float z)
void loadFromTextFile(std::istream &f)
Loads a vector/matrix from a text file, compatible with MATLAB text format.
void getGroundTruth(mrpt::poses::CPose2D &expectedPose, size_t rawlogEntry, const mrpt::math::CMatrixDouble >, const Clock::time_point &cur_time)