Go to the documentation of this file.
9 #ifndef CMetricMapBuilderICP_H
10 #define CMetricMapBuilderICP_H
78 mrpt::poses::CPose3DPDFPtr getCurrentPoseEstimation()
const;
82 void setCurrentMapFile(
const char *mapFile );
90 void processActionObservation(
99 void processObservation(
const mrpt::obs::CObservationPtr &obs);
109 void getCurrentMapPoints( std::vector<float> &x, std::vector<float> &y);
117 unsigned int getCurrentlyBuiltMapSize();
123 void saveCurrentEstimationToImage(
const std::string &file,
bool formatEMF_BMP =
true);
mrpt::maps::CSimpleMap SF_Poses_seq
The set of observations that leads to current map:
mrpt::maps::TSetOfMetricMapInitializers mapInitializers
What maps to create (at least one points map and/or a grid map are needed).
bool m_there_has_been_an_odometry
The ICP algorithm configuration data.
mrpt::math::CMatrixDouble33 m_lastPoseEst_cov
Last pose estimation (covariance)
CICP::TConfigParams ICP_params
Options for the ICP algorithm itself.
A class for very simple 2D SLAM based on ICP.
mrpt::poses::CRobot2DPoseEstimator m_lastPoseEst
The pose estimation by the alignment algorithm (ICP).
std::string currentMapFile
Current map file.
Declares a class for storing a collection of robot actions.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool matchAgainstTheGrid
(default:false) Match against the occupancy grid or the points map? The former is quicker but less pr...
std::deque< mrpt::math::TPose2D > m_estRobotPath
The estimated robot path:
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
double minICPgoodnessToAccept
Minimum ICP goodness (0,1) to accept the resulting corrected position (default: 0....
std::map< TYPE1, TYPE2, std::less< TYPE1 >, Eigen::aligned_allocator< std::pair< const TYPE1, TYPE2 > > > map_t
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
This class allows loading and storing values and vectors of different types from a configuration text...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
A class used to store a 2D pose.
This class stores any customizable set of metric maps.
Traveled distances from last map update / ICP-based localization.
mrpt::aligned_containers< std::string, TDist >::map_t m_distSinceLastInsertion
Indexed by sensor label.
A numeric matrix of compile-time fixed size.
double insertionLinDistance
Minimum robot linear (m) displacement for a new observation to be inserted in the map.
A simple filter to estimate and extrapolate the robot 2D (x,y,phi) pose from asynchronous odometry an...
Declares a class that represents a probability density function (pdf) of a 2D pose (x,...
double localizationLinDistance
Minimum robot linear (m) displacement for a new observation to be used to do ICP-based localization (...
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
Algorithm configuration params.
mrpt::poses::CPose2D m_auxAccumOdometry
mrpt::maps::CMultiMetricMap metricMap
The metric map representation as a points map:
double insertionAngDistance
Minimum robot angular (rad, deg when loaded from the .ini) displacement for a new observation to be i...
TConfigParams ICP_options
Options for the ICP-SLAM application.
This virtual class is the base for SLAM implementations.
mrpt::poses::CPose2D last_update
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
double localizationAngDistance
Minimum robot angular (rad, deg when loaded from the .ini) displacement for a new observation to be u...
Page generated by Doxygen 1.8.16 for MRPT 1.4.0 SVN: at Mon Oct 14 22:32:58 UTC 2019 | | |