37 class CLSLAMAlgorithmBase;
38 class CLSLAM_RBPF_2DLASER;
324 const std::string& name,
417 std::map<THypothesisID, CLocalMetricHypothesis>
m_LMHs;
441 const std::string& section)
override;
443 std::ostream&
out)
const override;
644 const void* action,
const void* observation);
int findTPathBinIntoSet(TPathBin &desiredBin, std::deque< TPathBin > &theSet)
Checks if a given "TPathBin" element is already into a set of them, and return its index (first one i...
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...
CLSLAM_RBPF_2DLASER(CHMTSLAM *parent)
Constructor.
void perform_TLC(CLocalMetricHypothesis &LMH, const CHMHMapNode::TNodeID areaInLMH, const CHMHMapNode::TNodeID areaLoopClosure, const mrpt::poses::CPose3DPDFGaussian &pose1wrt2)
Topological Loop Closure: Performs all the required operations to close a loop between two areas whic...
void pushObservation(const mrpt::obs::CObservation::Ptr &obs)
Here the user can enter an observation into the system (will go to the SLAM process).
Implements a 2D local SLAM method based on a RBPF over an occupancy grid map.
void thread_LSLAM()
The function for the "Local SLAM" thread.
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
std::map< CHMHMapNode::TNodeID, TBI_info > loopClosureData
The meat is here: only feasible loop closures from "cur_area" are included here, with associated data...
Template for column vectors of dynamic size, compatible with Eigen.
#define THROW_EXCEPTION(msg)
std::vector< std::string > TLC_detectors
A list of topological loop-closure detectors to use: can be one or more from this list: 'gridmaps': O...
int LOG_FREQUENCY
[LOGGING] One SLAM iteration out of "LOGGING_logFrequency", a log file will be generated.
mrpt::graphs::TNodeID TNodeID
The type of the IDs of nodes.
CTopLCDetector_FabMap::TOptions TLC_fabmap_options
Options passed to this TLC constructor.
CTopLCDetectorBase *(*)(CHMTSLAM *) TLopLCDetectorFactory
Classes related to the implementation of Hybrid Metric Topological (HMT) SLAM.
static TPoseID generatePoseID()
Generates a new and unique pose ID.
static TMessageLSLAMfromTBI::Ptr TBI_main_method(CLocalMetricHypothesis *LMH, const CHMHMapNode::TNodeID &areaID)
The entry point for Topological Bayesian Inference (TBI) engines, invoked from LSLAM.
std::thread m_hThread_TBI
std::atomic_bool m_terminationFlag_3D_viewer
Declares a class that represents a Probability Density function (PDF) of a 3D(6D) pose ...
static TMessageLSLAMfromAA::Ptr areaAbstraction(CLocalMetricHypothesis *LMH, const TPoseIDList &newPoseIDs)
The Area Abstraction (AA) method, invoked from LSLAM.
static TPoseID m_nextPoseID
uint64_t TPoseID
An integer number uniquely identifying each robot pose stored in HMT-SLAM.
void generateLogFiles(unsigned int nIteration)
Called from LSLAM thread when log files must be created.
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.
std::map< std::string, TLopLCDetectorFactory > m_registeredLCDetectors
std::atomic_bool m_terminationFlag_TBI
Option set for KLD algorithm.
THypothesisID hypothesisID
The hypothesis ID (LMH) for these results.
bool saveState(mrpt::serialization::CArchive &out) const
Save the state of the whole HMT-SLAM framework to some binary stream (e.g.
std::mutex m_map_cs
Critical section for accessing m_map.
CTopLCDetector_GridMatching::TOptions TLC_grid_options
Options passed to this TLC constructor.
static THypothesisID m_nextHypID
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
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...
Virtual base for local SLAM methods, used in mrpt::slam::CHMTSLAM.
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).
static double particlesEvaluator_AuxPFOptimal(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const mrpt::bayes::CParticleFilterCapable *obj, size_t index, const void *action, const void *observation)
Auxiliary function used in "prediction_and_update_pfAuxiliaryPFOptimal".
Declares a class for storing a collection of robot actions.
bool loadState(mrpt::serialization::CArchive &in)
Load the state of the whole HMT-SLAM framework from some binary stream (e.g.
std::vector< TPoseID > TPoseIDList
Configuration parameters.
CLSLAMAlgorithmBase(CHMTSLAM *parent)
Constructor.
CHMTSLAM(const CHMTSLAM &)
void dumpToStdOut() const
For debugging purposes!
mrpt::serialization::CSerializable::Ptr getNextObjectFromInputQueue()
Used from the LSLAM thread to retrieve the next object from the queue.
~CLSLAM_RBPF_2DLASER() override
Destructor.
CHMHMapNode::TNodeID cur_area
The area for who the loop-closure has been computed.
void loadTPathBinFromPath(TPathBin &outBin, TMapPoseID2Pose3D *path=nullptr, mrpt::poses::CPose2D *newPose=nullptr)
Fills out a "TPathBin" variable, given a path hypotesis and (if not set to nullptr) a new pose append...
mrpt::slam::TKLDParams KLD_params
This class allows loading and storing values and vectors of different types from a configuration text...
std::atomic_bool m_terminationFlag_LSLAM
Threads termination flags:
std::string LOG_OUTPUT_DIR
[LOGGING] If it is not an empty string (""), a directory with that name will be created and log files...
std::mutex m_LMHs_cs
Critical section for accessing m_LMHs.
std::mutex m_topLCdets_cs
The critical section for accessing m_topLCdets.
CMessageQueue m_LSLAM_queue
mrpt::maps::TSetOfMetricMapInitializers defaultMapsInitializers
The default set of maps to be created in each particle.
Versatile class for consistent logging and management of output messages.
mrpt::safe_ptr< CHMTSLAM > m_parent
std::map< TPoseID, mrpt::poses::CPose3D > TMapPoseID2Pose3D
std::queue< mrpt::serialization::CSerializable::Ptr > m_inputQueue
The queue of pending actions/observations supplied by the user waiting for being processed.
std::vector< TPoseIDList > partitions
std::map< THypothesisID, CLocalMetricHypothesis > m_LMHs
The list of LMHs at each instant.
std::deque< CTopLCDetectorBase * > m_topLCdets
The list of LC modules in operation - initialized by "initializeEmptyMap" or "loadState".
virtual ~CLSLAMAlgorithmBase()=default
Destructor.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
std::thread m_hThread_3D_viewer
This virtual class defines the interface that any particles based PDF class must implement in order t...
CHierarchicalMHMap m_map
The hiearchical, multi-hypothesis graph-based map.
THypothesisID hypothesisID
The hypothesis ID (LMH) for these results.
mrpt::hmtslam::CHMTSLAM::TOptions m_options
void processOneLMH(CLocalMetricHypothesis *LMH, const mrpt::obs::CActionCollection::Ptr &act, const mrpt::obs::CSensoryFrame::Ptr &sf) override
Main entry point from HMT-SLAM: process some actions & observations.
void thread_TBI()
The function for the "TBI" thread.
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 wrapper class for pointers that can be safely copied with "=" operator without problems.
void prediction_and_update_pfAuxiliaryPFOptimal(CLocalMetricHypothesis *LMH, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
The PF algorithm implementation.
std::atomic_bool m_terminateThreads
Termination flag for signaling all threads to terminate.
void getAs3DScene(mrpt::opengl::COpenGLScene &outScene)
Gets a 3D representation of the current state of the whole mapping framework.
TLSlamMethod SLAM_METHOD
[LSLAM] The method to use for local SLAM
~CHMTSLAM() override
Destructor.
virtual void prediction_and_update_pfAuxiliaryPFOptimal(CLocalMetricHypothesis *LMH, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)=0
The PF algorithm implementation.
bayes::CParticleFilter::TParticleFilterOptions pf_options
These params are used from every LMH object.
size_t inputQueueSize()
Returns the number of objects waiting for processing in the input queue.
mrpt::math::CVectorFloat stds_Q_no_odo
A 3-length vector with the std.
A variety of options and configuration params (private, use loadOptions).
TOptions()
Initialization of default params.
void loadOptions(const std::string &configFile)
Loads the options from a config file.
double log_lik
Log likelihood for this loop-closure.
int64_t THypothesisID
An integer number uniquely identifying each of the concurrent hypotheses for the robot topological pa...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Virtual base class for "archives": classes abstracting I/O streams.
A class that contain generic messages, that can be sent and received from a "CClientTCPSocket" object...
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...
const CHMTSLAM & operator=(const CHMTSLAM &)
mrpt::vision::TStereoCalibResults out
void LSLAM_process_message_from_TBI(const TMessageLSLAMfromTBI &myMsg)
No critical section locks are assumed at the entrance of this method.
void clearInputQueue()
Empty the input queue.
void registerLoopClosureDetector(const std::string &name, CTopLCDetectorBase *(*ptrCreateObject)(CHMTSLAM *))
Must be invoked before calling initializeEmptyMap, so LC objects can be created.
The configuration of a particle filter.
COutputLogger()
Default class constructor.
float VIEW3D_AREA_SPHERES_RADIUS
[VIEW3D] The radius of the areas' spheres.
static double auxiliarComputeObservationLikelihood(const mrpt::bayes::CParticleFilter::TParticleFilterOptions &PF_options, const mrpt::bayes::CParticleFilterCapable *obj, size_t particleIndexForMap, const mrpt::obs::CSensoryFrame *observation, const mrpt::poses::CPose2D *x)
Auxiliary function that evaluates the likelihood of an observation, given a robot pose...
void pushAction(const mrpt::obs::CActionCollection::Ptr &acts)
Here the user can enter an action into the system (will go to the SLAM process).
The most high level class for storing hybrid, multi-hypothesis maps in a graph-based model...
This class allows the user to create, load, save, and render 3D scenes using OpenGL primitives...
The virtual base class which provides a unified interface for all persistent objects in MRPT...
TNodeIDList areaIDs
The areas to consider.
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
static std::string generateUniqueAreaLabel()
Generates a new and unique area textual label (currently this generates "0","1",...)
virtual void prediction_and_update_pfOptimalProposal(CLocalMetricHypothesis *LMH, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options)=0
The PF algorithm implementation.
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
void thread_3D_viewer()
The function for the "3D viewer" thread.
CLocalMetricHypothesis * LMH
The LMH.
void LSLAM_process_message(const mrpt::serialization::CMessage &msg)
Auxiliary method within thread_LSLAM.
bool m_insertNewRobotPose
For use within PF callback methods.
std::thread m_hThread_LSLAM
Threads handles.
float SLAM_MIN_DIST_BETWEEN_OBS
[LSLAM] Minimum distance (and heading) difference between observations inserted in the map...
float SLAM_MIN_HEADING_BETWEEN_OBS
virtual void processOneLMH(CLocalMetricHypothesis *LMH, const mrpt::obs::CActionCollection::Ptr &act, const mrpt::obs::CSensoryFrame::Ptr &sf)=0
Main entry point from HMT-SLAM: process some actions & observations.
CTopLCDetectorBase * loopClosureDetector_factory(const std::string &name)
The class factory for topological loop closure detectors.
bool isInputQueueEmpty()
Returns true if the input queue is empty (Note that the queue must not be empty to the user to enqueu...
CHMTSLAM()
Default constructor.
void prediction_and_update_pfOptimalProposal(CLocalMetricHypothesis *LMH, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
The PF algorithm implementation.
void pushObservations(const mrpt::obs::CSensoryFrame::Ptr &sf)
Here the user can enter observations into the system (will go to the SLAM process).
static THypothesisID generateHypothesisID()
Generates a new and unique hypothesis ID.
void LSLAM_process_message_from_AA(const TMessageLSLAMfromAA &myMsg)
No critical section locks are assumed at the entrance of this method.
void dumpToConsole() const
for debugging only
std::mutex m_inputQueue_cs
Critical section for accessing m_inputQueue.
void initializeEmptyMap()
Initializes the whole HMT-SLAM framework, reseting to an empty map (It also clears the logs directory...
bool abortedDueToErrors()
Return true if an exception has been caught in any thread leading to the end of the mapping applicati...