Class BackEndBase

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

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
virtual void initialize(const Yaml &cfg) final override

Loads common parameters for all back-ends.

inline virtual void onSmartFactorChanged(mola::fid_t id, const mola::FactorBase *f)
inline virtual mola::id_t temp_createStereoCamera(const mrpt::img::TCamera &left, const mrpt::img::TCamera &right, const double baseline)

TODO: Refactor this!!

inline virtual mola::id_t temp_createLandmark(const mrpt::math::TPoint3D &init_value)
inline virtual void lock_slam()
inline virtual void unlock_slam()

Protected Functions

virtual void initialize_backend(const Yaml &cfg) = 0

Loads children specific parameters

Protected Attributes

WorldModel::Ptr worldmodel_
mrpt::WorkerThreadsPool slam_be_threadpool_{2, mrpt::WorkerThreadsPool::POLICY_FIFO, "slam_backend"}
struct AddFactor_Output

Public Members

bool success = {false}
std::optional<mola::fid_t> new_factor_id = {std::nullopt}
std::optional<std::string> error_msg = {std::nullopt}
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}
struct ProposeKF_Input

Public Members

mrpt::Clock::time_point timestamp = {}

The timestamp associated to the new Key-Frame. Must be valid.

std::optional<mrpt::obs::CSensoryFrame> observations = {std::nullopt}

Optional set of raw observations seen from this KF.

struct ProposeKF_Output

Public Members

bool success = {false}
std::optional<mola::id_t> new_kf_id = {std::nullopt}
std::optional<std::string> error_msg = {std::nullopt}