36 class CLSLAMAlgorithmBase;
95 void dumpToConsole( )
const;
173 void clearInputQueue();
178 bool isInputQueueEmpty();
183 size_t inputQueueSize();
189 void pushAction(
const mrpt::obs::CActionCollectionPtr &acts );
195 void pushObservations(
const mrpt::obs::CSensoryFramePtr &sf );
201 void pushObservation(
const mrpt::obs::CObservationPtr &obs );
212 mrpt::utils::CSerializablePtr getNextObjectFromInputQueue();
232 void thread_LSLAM( );
238 void thread_3D_viewer( );
295 void registerLoopClosureDetector(
317 bool m_terminationFlag_LSLAM,
319 m_terminationFlag_3D_viewer;
325 static TPoseID generatePoseID();
350 bool abortedDueToErrors();
362 void initializeEmptyMap();
385 void generateLogFiles(
unsigned int nIteration);
485 virtual void processOneLMH(
487 const mrpt::obs::CActionCollectionPtr &act,
488 const mrpt::obs::CSensoryFramePtr &sf ) = 0;
493 virtual void prediction_and_update_pfAuxiliaryPFOptimal(
500 virtual void prediction_and_update_pfOptimalProposal(
536 const mrpt::obs::CActionCollectionPtr &act,
537 const mrpt::obs::CSensoryFramePtr &sf );
540 void prediction_and_update_pfAuxiliaryPFOptimal(
547 void prediction_and_update_pfOptimalProposal(
567 void dumpToStdOut()
const;
573 void loadTPathBinFromPath(
580 int findTPathBinIntoSet(
582 std::deque<TPathBin> &theSet
587 static double particlesEvaluator_AuxPFOptimal(
592 const void *observation );
596 static double auxiliarComputeObservationLikelihood(
599 size_t particleIndexForMap,
float MIN_ODOMETRY_STD_PHI
[LSLAM] Minimum uncertainty (1 sigma, rads) in phi for odometry increments (Default=0) ...
int random_seed
0 means randomize, use any other value to have repetitive experiments.
float MIN_ODOMETRY_STD_XY
[LSLAM] Minimum uncertainty (1 sigma, meters) in x and y for odometry increments (Default=0) ...
CLSLAMAlgorithmBase * m_LSLAM_method
An instance of a local SLAM method, to be applied to each LMH - initialized by "initializeEmptyMap" o...
This class provides simple critical sections functionality.
synch::CCriticalSection m_map_cs
Critical section for accessing m_map.
Implements a 2D local SLAM method based on a RBPF over an occupancy grid map.
int LOG_FREQUENCY
[LOGGING] One SLAM iteration out of "LOGGING_logFrequency", a log file will be generated.
CTopLCDetector_FabMap::TOptions TLC_fabmap_options
Options passed to this TLC constructor.
The virtual base class which provides a unified interface for all persistent objects in MRPT...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
mrpt::system::TThreadHandle m_hThread_TBI
#define THROW_EXCEPTION(msg)
Declares a class that represents a Probability Density function (PDF) of a 3D(6D) pose ...
static TPoseID m_nextPoseID
vector_string TLC_detectors
A list of topological loop-closure detectors to use: can be one or more from this list: 'gridmaps': O...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Option set for KLD algorithm.
std::map< TYPE1, TYPE2, std::less< TYPE1 >, Eigen::aligned_allocator< std::pair< const TYPE1, TYPE2 > > > map_t
THypothesisID hypothesisID
The hypothesis ID (LMH) for these results.
std::shared_ptr< TMessageLSLAMfromAA > TMessageLSLAMfromAAPtr
CTopLCDetector_GridMatching::TOptions TLC_grid_options
Options passed to this TLC constructor.
uint64_t TPoseID
An integer number uniquely identifying each robot pose stored in HMT-SLAM.
aligned_containers< THypothesisID, CLocalMetricHypothesis >::map_t m_LMHs
The list of LMHs at each instant.
static THypothesisID m_nextHypID
bool m_terminateThreads
Termination flag for signaling all threads to terminate.
std::shared_ptr< TMessageLSLAMtoTBI > TMessageLSLAMtoTBIPtr
mrpt::poses::CPose3DPDFSOG delta_new_cur
Depending on the loop-closure engine, an guess of the relative pose of "area_new" relative to "cur_ar...
utils::CMessageQueue m_LSLAM_queue
LSLAM thread input queue, messages of type CHMTSLAM::TMessageLSLAMfromAA.
Virtual base for local SLAM methods, used in mrpt::slam::CHMTSLAM.
GLsizei GLsizei GLuint * obj
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
static int64_t m_nextAreaLabel
An implementation of Hybrid Metric Topological SLAM (HMT-SLAM).
Declares a class for storing a collection of robot actions.
mrpt::utils::safe_ptr< CHMTSLAM > m_parent
Configuration of the algorithm:
This class allows loading and storing values and vectors of different types from a configuration text...
int64_t THypothesisID
An integer number uniquely identifying each of the concurrent hypotheses for the robot topological pa...
std::queue< mrpt::utils::CSerializablePtr > m_inputQueue
The queue of pending actions/observations supplied by the user waiting for being processed.
CLSLAMAlgorithmBase(CHMTSLAM *parent)
Constructor.
CHMTSLAM(const CHMTSLAM &)
CHMHMapNode::TNodeID cur_area
The area for who the loop-closure has been computed.
bool m_terminationFlag_TBI
std::vector< std::string > vector_string
A type for passing a vector of strings.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
mrpt::slam::TKLDParams KLD_params
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
std::string LOG_OUTPUT_DIR
[LOGGING] If it is not an empty string (""), a directory with that name will be created and log files...
mrpt::maps::TSetOfMetricMapInitializers defaultMapsInitializers
The default set of maps to be created in each particle.
std::deque< CTopLCDetectorBase * > m_topLCdets
The list of LC modules in operation - initialized by "initializeEmptyMap" or "loadState".
virtual ~CLSLAMAlgorithmBase()
Destructor.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
This virtual class defines the interface that any particles based PDF class must implement in order t...
class HMTSLAM_IMPEXP CHMTSLAM
CHierarchicalMHMap m_map
The hiearchical, multi-hypothesis graph-based map.
THypothesisID hypothesisID
The hypothesis ID (LMH) for these results.
The virtual base class for Topological Loop-closure Detectors; used in HMT-SLAM.
This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).
A thread-safe template queue for object passing between threads; for a template argument of T...
std::vector< TPoseIDList > partitions
GLsizei const GLchar ** string
TLSlamMethod SLAM_METHOD
[LSLAM] The method to use for local SLAM
std::vector< TPoseID > TPoseIDList
bayes::CParticleFilter::TParticleFilterOptions pf_options
These params are used from every LMH object.
mrpt::math::CVectorFloat stds_Q_no_odo
A 3-length vector with the std.
std::map< CHMHMapNode::TNodeID, TBI_info > loopClosureData
The meat is here: only feasible loop closures from "cur_area" are included here, with associated data...
mrpt::aligned_containers< TPoseID, mrpt::poses::CPose3D >::map_t TMapPoseID2Pose3D
A variety of options and configuration params (private, use loadOptions).
double log_lik
Log likelihood for this loop-closure.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
Options for a TLC-detector of type FabMap, used from CHMTSLAM.
Options for a TLC-detector of type gridmap-matching, used from CHMTSLAM.
mrpt::slam::CIncrementalMapPartitioner::TOptions AA_options
[AA] The options for the partitioning algorithm
float VIEW3D_AREA_SPHERES_HEIGHT
[VIEW3D] The height of the areas' spheres.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
std::map< std::string, TLopLCDetectorFactory > m_registeredLCDetectors
The configuration of a particle filter.
float VIEW3D_AREA_SPHERES_RADIUS
[VIEW3D] The radius of the areas' spheres.
The most high level class for storing hybrid, multi-hypothesis maps in a graph-based model...
GLuint const GLchar * name
This class allows the user to create, load, save, and render 3D scenes using OpenGL primitives...
GLsizei GLsizei GLchar * source
class HMTSLAM_IMPEXP CLSLAM_RBPF_2DLASER
TNodeIDList areaIDs
The areas to consider.
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
std::shared_ptr< TMessageLSLAMfromTBI > TMessageLSLAMfromTBIPtr
synch::CCriticalSection m_topLCdets_cs
The critical section for accessing m_topLCdets.
std::vector< int32_t > vector_int
synch::CCriticalSection m_LMHs_cs
Critical section for accessing m_LMHs.
CLocalMetricHypothesis * LMH
The LMH.
bool m_insertNewRobotPose
For use within PF callback methods.
float SLAM_MIN_HEADING_BETWEEN_OBS
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
A class that contain generic messages, that can be sent and received from a "CClientTCPSocket" object...
synch::CCriticalSection m_inputQueue_cs
Critical section for accessing m_inputQueue.
A wrapper class for pointers that can be safely copied with "=" operator without problems.
mrpt::utils::TNodeID TNodeID
The type of the IDs of nodes.