namespace mola
Overview
namespace mola { // typedefs typedef std::variant<std::monostate, SensorCamera, SensorIMU> SensorEntry; typedef uint64_t euroc_timestamp_t; typedef std::multimap<euroc_timestamp_t, SensorEntry> euroc_dataset_t; typedef std::shared_ptr<EntityBase> EntityOther; typedef std::map<std::string, LazyLoadResource> annotations_data_t; typedef std::variant<std::monostate, RefPose3, RelPose3, RelPose3KF, RelDynPose3KF, LandmarkPoint3, EntityOther> Entity; typedef std::variant<std::monostate, FactorRelativePose3, FactorConstVelKinematics, FactorStereoProjectionPose, SmartFactorStereoProjectionPose, SmartFactorIMU, FactorOther> Factor; typedef std::shared_ptr<FactorBase> FactorOther; typedef std::allocator<T> FastAllocator; typedef std::set<T, Compare, FastAllocator<T>> fast_set; typedef std::map<Key, T, Compare, FastAllocator<std::pair<const Key, T>>> fast_map; typedef std::uint64_t id_t; typedef std::uint64_t fid_t; typedef mrpt::system::CTimeLogger Profiler; typedef mrpt::system::CTimeLoggerEntry ProfilerEntry; typedef mrpt::system::CTimeLoggerSaveAtDtor ProfilerSaverAtDtor; typedef mrpt::poses::CPose3DInterpolator trajectory_t; typedef mrpt::obs::CObservation CObservation; typedef std::size_t timestep_t; typedef mola::fast_map<id_t, mola::fast_set<fid_t>> entity_connected_factors_t; typedef mrpt::containers::yaml Yaml; typedef ContainerDeque<Entity, WorldModelData::EntitiesContainer, EntityBase, EntityOther, id_t> EntitiesContainerDeque; typedef ContainerDeque<Factor, WorldModelData::FactorsContainer, FactorBase, FactorOther, fid_t> FactorsContainerDeque; typedef ContainerFastMap<Entity, WorldModelData::EntitiesContainer, EntityBase, EntityOther, id_t, e_str> EntitiesContainerFastMap; typedef ContainerFastMap<Factor, WorldModelData::FactorsContainer, FactorBase, FactorOther, fid_t, f_str> FactorsContainerFastMap; // enums enum Robust; // structs template <class T, class BASE, class Tbase, class Tother, typename ID> struct ContainerDeque; template < class T, class BASE, class Tbase, class Tother, typename ID, const char* Tstr > struct ContainerFastMap; struct NavState; struct RelocalizationICP_SE2; struct RelocalizationLikelihood_SE2; struct SensorCamera; struct SensorIMU; struct StereoObservation; struct YAMLParseOptions; template <typename cell_coord_t = int32_t> struct index3d_hash; template <typename cell_coord_t = int32_t> struct index3d_t; template <typename cell_coord_t = int32_t> struct index_se3_t; template <typename cell_coord_t = int32_t> struct index_se3_t_hash; template <class... Ts> struct overloaded; // classes class BackEndBase; class BridgeROS2; class Dataset_UI; class EntityBase; class EntityRelativeBase; class EurocDataset; class ExecutableBase; class FactorAngularVelocityIntegration; class FactorBase; class FactorConstAngularVelocity; class FactorConstVelKinematics; class FactorRelativePose3; class FactorStereoProjectionPose; class FactorTrapezoidalIntegrator; class FilterBase; template <typename T, size_t SIDE_NUM_BITS, typename inner_coord_t> class FixedDenseGrid3D; class FrontEndBase; class HashedSetSE3; class HashedVoxelPointCloud; class IMUIntegrationParams; class KeyFrameBase; class Kitti360Dataset; class KittiOdometryDataset; class LandmarkPoint3; class LazyLoadResource; class LidarOdometry; class LocalizationSourceBase; class MapServer; class MapSourceBase; class MolaLauncherApp; class MolaViz; class MulranDataset; class NDT; class NavStateFG; class NavStateFGParams; class NavStateFilter; class NavStateFuse; class NavStateFuseParams; class OccGrid; class OfflineDatasetSource; class ParisLucoDataset; class RawDataConsumer; class RawDataSourceBase; class RawlogDataset; class RefPose3; class RelDynPose3KF; class RelPose3; class RelPose3KF; class Relocalization; class Rosbag2Dataset; class RotationIntegrationParams; class RotationIntegrator; class SearchablePoseList; class SmartFactorIMU; class SmartFactorStereoProjectionPose; class SparseTreesPointCloud; class SparseVoxelPointCloud; class VizInterface; class WorldModel; class WorldModelData; // global variables constexpr id_t INVALID_ID = std::numeric_limits<id_t>::max(); constexpr fid_t INVALID_FID = std::numeric_limits<fid_t>::max(); static const char e_str[] = "Entity"; static const char f_str[] = "Factor"; // global functions mrpt::math::CMatrixDouble33 incremental_rotation( const mrpt::math::TVector3D& w, const RotationIntegrationParams& params, double dt, const mrpt::optional_ref<mrpt::math::CMatrixDouble33>& D_incrR_integratedOmega = std::nullopt ); EntityBase& entity_get_base(Entity& e); const EntityBase& entity_get_base(const Entity& e); mrpt::math::TPose3D entity_get_pose(const Entity& e); mrpt::math::TTwist3D entity_get_twist(const mola::Entity& e); void entity_update_pose( Entity& e, const mrpt::math::TPose3D& p ); void entity_update_vel( Entity& e, const std::array<double, 3>& v ); mrpt::Clock::time_point entity_get_timestamp(const Entity& e); FactorBase& factor_get_base(Factor& f); const FactorBase& factor_get_base(const Factor& f); void pretty_print_exception( const std::exception& e, const std::string& headerLine, const bool use_std_cerr = true ); template <class... Ts> overloaded(Ts...); template <typename cell_coord_t> std::ostream& operator << ( std::ostream& o, const index3d_t<cell_coord_t>& idx ); template <typename cell_coord_t> std::ostream& operator << ( std::ostream& o, const index_se3_t<cell_coord_t>& idx ); auto find_best_poses_se2(const mrpt::poses::CPosePDFGrid& grid, const double percentile = 0.99); std::string parse_yaml(const std::string& text, const YAMLParseOptions& opts = YAMLParseOptions()); mrpt::containers::yaml parse_yaml( const mrpt::containers::yaml& input, const YAMLParseOptions& opts = YAMLParseOptions() ); mrpt::containers::yaml load_yaml_file(const std::string& fileName, const YAMLParseOptions& opts = YAMLParseOptions()); std::string yaml_to_string(const mrpt::containers::yaml& cfg); } // namespace mola
Typedefs
typedef std::shared_ptr<EntityBase> EntityOther
Placeholder for generic entity of user-defined types
typedef std::shared_ptr<FactorBase> FactorOther
Placeholder for a generic factor of user-defined types
typedef mrpt::poses::CPose3DInterpolator trajectory_t
We reuse mrpt::poses::CPose3DInterpolator as a time-indexed map of SE(3) poses
typedef std::size_t timestep_t
0-based indices of observations in a dataset
typedef mrpt::containers::yaml Yaml
Convenient typedef to save typing in the MOLA project.
Global Functions
mrpt::math::CMatrixDouble33 incremental_rotation( const mrpt::math::TVector3D& w, const RotationIntegrationParams& params, double dt, const mrpt::optional_ref<mrpt::math::CMatrixDouble33>& D_incrR_integratedOmega = std::nullopt )
This takes a gyroscope measurement of the angular velocity (ω) and integrates it forward in time for a period dt [s] as:
Rot = Exp((ω-ω_{bias})·dt)
FactorBase& factor_get_base(Factor& f)
Return a reference to the FactorBase associated to the variant f
const FactorBase& factor_get_base(const Factor& f)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
template <class... Ts> overloaded(Ts...)
Based on https://en.cppreference.com/w/cpp/utility/variant/visit