9 #ifndef CMetricMapBuilderICP_H 10 #define CMetricMapBuilderICP_H 44 TConfigParams (mrpt::utils::VerbosityLevel &parent_verbosity_level);
81 mrpt::poses::CPose3DPDFPtr getCurrentPoseEstimation() const
MRPT_OVERRIDE;
85 void setCurrentMapFile( const
char *mapFile );
93 void processActionObservation(
102 void processObservation(const
mrpt::obs::CObservationPtr &obs);
108 void getCurrentMapPoints(
std::vector<
float> &
x,
std::vector<
float> &
y);
119 void saveCurrentEstimationToImage(const
std::
string &file,
bool formatEMF_BMP = true)
MRPT_OVERRIDE;
129 std::
string currentMapFile;
132 mrpt::poses::CRobot2DPoseEstimator m_lastPoseEst;
137 std::deque<
mrpt::math::TPose2D> m_estRobotPath;
138 mrpt::poses::CPose2D m_auxAccumOdometry;
double localizationAngDistance
Minimum robot angular (rad, deg when loaded from the .ini) displacement for a new observation to be u...
mrpt::maps::TSetOfMetricMapInitializers mapInitializers
What maps to create (at least one points map and/or a grid map are needed).
The ICP algorithm configuration data.
double minICPgoodnessToAccept
Minimum ICP goodness (0,1) to accept the resulting corrected position (default: 0.40)
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
mrpt::poses::CPose2D last_update
mrpt::aligned_containers< std::string, TDist >::map_t m_distSinceLastInsertion
Indexed by sensor label.
std::map< TYPE1, TYPE2, std::less< TYPE1 >, Eigen::aligned_allocator< std::pair< const TYPE1, TYPE2 > > > map_t
TConfigParams ICP_options
Options for the ICP-SLAM application.
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
double insertionAngDistance
Minimum robot angular (rad, deg when loaded from the .ini) displacement for a new observation to be i...
Declares a class for storing a collection of robot actions.
bool matchAgainstTheGrid
(default:false) Match against the occupancy grid or the points map? The former is quicker but less pr...
This class allows loading and storing values and vectors of different types from a configuration text...
mrpt::utils::VerbosityLevel & verbosity_level
CICP::TConfigParams ICP_params
Options for the ICP algorithm itself.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
CMatrixFixedNumeric< double, 3, 3 > CMatrixDouble33
This virtual class is the base for SLAM implementations.
GLsizei const GLchar ** string
Declares a class that represents a probability density function (pdf) of a 2D pose (x...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
GLsizei GLsizei GLchar * source
double localizationLinDistance
Minimum robot linear (m) displacement for a new observation to be used to do ICP-based localization (...
Algorithm configuration params.
A class for very simple 2D SLAM based on ICP.
bool m_there_has_been_an_odometry
This class stores any customizable set of metric maps.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
double insertionLinDistance
Minimum robot linear (m) displacement for a new observation to be inserted in the map...
Traveled distances from last map update / ICP-based localization.