34 #include <mrpt/maps/CLandmarksMap.h>
35 #include <mrpt/maps/COccupancyGridMap2D.h>
40 using namespace mrpt::slam;
41 using namespace mrpt::opengl;
42 using namespace mrpt::math;
43 using namespace mrpt::system;
46 using mrpt::maps::CLandmarksMap;
47 using mrpt::maps::COccupancyGridMap2D;
53 mrpt::math::CMatrixDouble33 cov;
54 cov(0, 0) = 1, cov(1, 1) = 1, cov(2, 2) = 2 * M_PI;
56 mrpt::poses::CPosePDFGaussian(mrpt::poses::CPose2D(0, 0, 0), cov);
60 CActionRobotMovement2D::mmGaussian;
67 const auto [cov, mean_point] =
initial_pose_.getCovarianceAndMean();
70 "InitializeFilter: %4.3fm, %4.3fm, %4.3frad ", mean_point.x(),
71 mean_point.y(), mean_point.phi());
72 float min_x = mean_point.x() - cov(0, 0);
73 float max_x = mean_point.x() + cov(0, 0);
74 float min_y = mean_point.y() - cov(1, 1);
75 float max_y = mean_point.y() + cov(1, 1);
76 float min_phi = mean_point.phi() - cov(2, 2);
77 float max_phi = mean_point.phi() + cov(2, 2);
81 pdf_.resetUniformFreeSpace(
82 metric_map_->mapByClass<COccupancyGridMap2D>().get(), 0.7f,
89 min_x, max_x, min_y, max_y, min_phi, max_phi,
96 CActionCollection::Ptr _action, CSensoryFrame::Ptr _sf)
106 CSensoryFrame::Ptr _sf, CObservationOdometry::Ptr _odometry)
108 auto action = CActionCollection::Create();
109 CActionRobotMovement2D odom_move;
110 odom_move.timestamp = _sf->getObservationByIndex(0)->timestamp;
117 mrpt::poses::CPose2D incOdoPose =
121 action->insert(odom_move);
130 <<
" -> using dummy");
131 odom_move.computeFromOdometry(
133 action->insert(odom_move);
140 <<
" -> skipping observation");