Class BackEndBase
Defined in File BackEndBase.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public mola::ExecutableBase
(Class ExecutableBase)
Class Documentation
-
class BackEndBase : public mola::ExecutableBase
Virtual interface for SLAM back-ends. All calls to
onXXX()
methods are enqueued and executed in a separate thread.User interface for a SLAM back-end
{
-
inline std::future<ProposeKF_Output> addKeyFrame(const ProposeKF_Input &i)
Creates a new KeyFrame in the world model.
-
inline std::future<AddFactor_Output> addFactor(Factor &f)
Adds a new constraint factor to the world model. Note that the object is moved, so it will not hold a valid value upon return.
-
inline std::future<void> advertiseUpdatedLocalization(const AdvertiseUpdatedLocalization_Input &l)
Virtual methods to be implemented by SLAM back-end.
doXXX()
run synchronously (blocking) in the same thread than the caller.onXXX()
run asynch in another thread. {-
virtual ProposeKF_Output doAddKeyFrame(const ProposeKF_Input &i) = 0
-
virtual AddFactor_Output doAddFactor(Factor &f) = 0
-
virtual void doAdvertiseUpdatedLocalization(const AdvertiseUpdatedLocalization_Input &l) = 0
Public Functions
-
BackEndBase()
-
virtual ~BackEndBase() = default
-
inline virtual void onSmartFactorChanged([[maybe_unused]] mola::fid_t id, [[maybe_unused]] const mola::FactorBase *f)
-
inline virtual mola::id_t temp_createStereoCamera([[maybe_unused]] const mrpt::img::TCamera &left, [[maybe_unused]] const mrpt::img::TCamera &right, [[maybe_unused]] const double baseline)
TODO: Refactor this!!
-
inline virtual mola::id_t temp_createLandmark([[maybe_unused]] const mrpt::math::TPoint3D &init_value)
-
inline virtual void lock_slam()
-
inline virtual void unlock_slam()
Protected Functions
Protected Attributes
-
WorldModel::Ptr worldmodel_
-
mrpt::WorkerThreadsPool slam_be_threadpool_{2, mrpt::WorkerThreadsPool::POLICY_FIFO, "slam_backend"}
-
struct AddFactor_Output
-
struct AdvertiseUpdatedLocalization_Input
Public Members
-
mrpt::Clock::time_point timestamp = {}
The timestamp associated to the new Key-Frame. Must be valid.
-
mola::id_t reference_kf = {mola::INVALID_ID}
Coordinates are given wrt this frame of reference
-
mrpt::math::TPose3D pose
-
std::optional<mrpt::math::CMatrixDouble66> cov = {std::nullopt}
-
mrpt::Clock::time_point timestamp = {}
-
struct ProposeKF_Input
-
struct ProposeKF_Output
-
inline std::future<ProposeKF_Output> addKeyFrame(const ProposeKF_Input &i)