Class Map
Defined in File map.hpp
Class Documentation
-
class Map
Thread-safe 3D map representation for SLAM state.
Owns keyframes, points, cell indexing, and helper operations for insertion, updates, retrieval, and visualization buffering.
Public Types
Shared pointer type for Map.
Public Functions
Acquire shared lock on the map-level mutex.
Release shared lock on the map-level mutex.
-
inline void lock() const
Acquire exclusive lock on the map-level mutex.
-
inline void unlock() const
Release exclusive lock on the map-level mutex.
-
~Map()
Destroy map instance and stop internal resources.
-
inline std::tuple<size_t, size_t, size_t, size_t, size_t> size() const
Get current map cardinality counters.
- Returns:
Tuple
(numKeyframes, numPoints, numberQueryCells, numberClosestCells, totalNumberCells).
-
inline bool exists(const keyframe_id_t &keyframeId_) const
Check whether a keyframe ID exists in the map.
- Parameters:
keyframeId_ – Keyframe identifier to query.
- Returns:
trueif the keyframe exists, otherwisefalse.
-
inline bool exists(const point_id_t &pointId_) const
Check whether a point ID exists in the map.
- Parameters:
pointId_ – Point identifier to query.
- Returns:
trueif the point exists, otherwisefalse.
-
bool exists(const cell_id_t &cellId_) const
Check whether a cell ID exists in the map.
- Parameters:
cellId_ – Cell identifier to query.
- Returns:
trueif the cell exists, otherwisefalse.
-
inline const output_t<keyframe_t::weak_ptr> operator[](const keyframe_id_t &keyframeId_) const
Retrieve a keyframe pointer by keyframe ID.
- Parameters:
keyframeId_ – Keyframe identifier.
- Returns:
Weak pointer wrapped in output_t on success.
-
inline output_t<keyframe_t::weak_ptr> at(const keyframe_id_t &keyframeId_) const
Retrieve a keyframe pointer by keyframe ID.
- Parameters:
keyframeId_ – Keyframe identifier.
- Returns:
Weak pointer wrapped in output_t on success.
-
inline output_t<pose_t> get(const keyframe_id_t &keyframeId_) const
Retrieve pose value associated with a keyframe ID.
-
inline output_t<point3d_t::weak_ptr> operator[](const point_id_t &pointId_) const
Retrieve a map point pointer by point ID.
-
inline output_t<point3d_t::weak_ptr> at(const point_id_t pointId_) const
Retrieve a map point pointer by point ID.
-
inline output_t<point3d_t> get(const point_id_t &pointId_) const
Retrieve map point value associated with a point ID.
-
output_t<pair_t<point_id_t, cell_id_t>> insert(const point3d_t &point_)
Insert a new 3D point into the map.
- Parameters:
point_ – Point data to insert.
- Returns:
Inserted
(pointId, cellId)wrapped in output_t.
-
output_t<keyframe_id_t> insert(const pose_t &pose_, const keyframe_t &keyframeData_)
Insert a keyframe into the map.
- Parameters:
pose_ – Pose associated with the keyframe.
keyframeData_ – Keyframe payload to insert.
- Returns:
Inserted keyframe ID wrapped in output_t.
-
inline fail_t update(const point_id_t &pointId_, const point3d_t &point_)
Update point coordinates using a point object.
- Parameters:
pointId_ – Point identifier to update.
point_ – Point object containing the updated position.
- Returns:
fail_t::NO_FAIL on success, otherwise a fail_t error.
-
inline fail_t update(const point_id_t &pointId_, const point3d_t::weak_ptr &pointPtr_)
Update point coordinates using a weak point pointer.
- Parameters:
pointId_ – Point identifier to update.
pointPtr_ – Weak pointer to point data.
- Returns:
fail_t::NO_FAIL on success, otherwise a fail_t error.
-
fail_t update(const point_id_t &pointId_, const array3D_t &point_)
Update point coordinates using a 3D array value.
- Parameters:
pointId_ – Point identifier to update.
point_ – New point coordinates.
- Returns:
fail_t::NO_FAIL on success, otherwise a fail_t error.
-
inline fail_t update(const keyframe_id_t &keyframeId_, const pose_t::weak_ptr &posePtr_)
Update keyframe pose using a weak pose pointer.
- Parameters:
keyframeId_ – Keyframe identifier to update.
posePtr_ – Weak pointer to the new pose.
- Returns:
fail_t::NO_FAIL on success, otherwise a fail_t error.
-
fail_t update(const keyframe_id_t &keyframeId_, const pose_t &pose_)
Update keyframe pose using a pose value.
- Parameters:
keyframeId_ – Keyframe identifier to update.
pose_ – New pose value.
- Returns:
fail_t::NO_FAIL on success, otherwise a fail_t error.
-
fail_t remove(const point_id_t &pointId_)
Remove a point from the map.
- Parameters:
pointId_ – Point identifier to remove.
- Returns:
fail_t::NO_FAIL on success, otherwise a fail_t error.
-
inline dictionary_t<keyframe_id_t, pair_t<pose_t, time_stamp_t>> get_timestamp_and_poses() const
Get timestamp and pose for every keyframe currently in the map.
- Returns:
Map of keyframe IDs to pose and timestamp pairs.
-
inline keyframe_t::weak_ptr get_keyframe_data_x(const keyframe_id_t keyframeId_) const
Get keyframe data pointer for a keyframe ID.
- Parameters:
keyframeId_ – Keyframe identifier.
- Returns:
Weak pointer to keyframe data.
-
inline const neighbor_t::vector &get_mappoints_neighboors_x(point_id_t pointId_) const
Get point neighbors for a point ID.
- Parameters:
pointId_ – Point identifier.
- Returns:
Const reference to neighbor list for the input point.
-
inline point_id_t::vector get_points_in_cell_x(const cell_id_t cellId_) const
Get all point IDs that belong to a specific 3D cell.
- Parameters:
cellId_ – Cell identifier.
- Returns:
Vector of point IDs contained in the cell.
-
inline pose_t::weak_ptr get_camera_world_pose() const
Get current camera world pose pointer.
- Returns:
Weak pointer to camera pose in world coordinates.
-
inline void set_camera_world_pose(const rotation_t &rotation_, const translation_t &translation_)
Sets the current estimated camera pose_.
- Parameters:
rotation_ – Rotation of the camera.
translation_ – Translation of the camera.
-
inline void set_camera_world_pose(const pose_t &newPose_)
Sets the current estimated camera pose_.
- Parameters:
newPose_ – New current camera pose_ in world coordinates.
-
inline void add_new_covisibility_connections_map(keyframe_id_t::pair pair_)
Add a covisibility edge between two keyframes.
- Parameters:
pair_ – Pair of keyframe IDs that define the edge.
-
cell_id_t::set get_visible_cells(size_t nCells_, const intrinsics_t intrinsics_, const array2Size_t imageSize_, const pose_t cameraToWorldTransformation_)
Compute visible cells for the current camera view.
- Parameters:
nCells_ – Number of cells to retrieve.
intrinsics_ – Camera intrinsics.
imageSize_ – Size of the image.
cameraToWorldTransformation_ – Transformation from camera to world.
- Returns:
Set of visible cell IDs.
-
inline void aux_buffer_for_visualization(const dictionary_t<keyframe_id_t, int> &keyframesInBuffer_)
Store current keyframe visualization-buffer membership.
- Parameters:
keyframesInBuffer_ – Map from keyframe IDs to buffer slots.
-
inline void aux_keyframe_criteria_visualization(const dictionary_t<uint8_t, int> &keyframeCreationCriteria_)
Store keyframe creation metrics for visualization.
- Parameters:
keyframeCreationCriteria_ – Map of metric identifiers and values.
-
inline hash_t<point_id_t, neighbor_t::vector> &get_all_neighbors()
Get mutable access to the full point-neighbor lookup table.
Note
This structure can be large; avoid unnecessary copies.
- Returns:
Reference to all point neighbors.
-
keyframe_id_t::ordered find_recent_keyframes(const keyframe_id_t startingKeyframe_) const
Find keyframes with IDs greater than the given starting keyframe.
- Parameters:
startingKeyframe_ – Starting keyframe identifier.
- Returns:
Ordered set of keyframe IDs greater than
startingKeyframe_.
-
void set_localization_buffer_keyframes(const keyframe_id_t::ordered &keyframesInBuffer_)
Update the set of keyframes used by the localization buffer.
- Parameters:
keyframesInBuffer_ – Ordered keyframes to keep in the buffer.
- Returns:
Final set of keyframes stored in the localization buffer.
-
keyframe_id_t::set get_localization_buffer_keyframes() const
Get current set of keyframes used by the localization buffer.
- Returns:
Set of keyframe IDs in the localization buffer.
Public Static Functions
Construct a shared map instance and start internal worker threads.
- Returns:
Shared pointer to initialized Map instance.
Private Functions
-
Map()
Construct an empty map instance.
-
void __start_threads()
Start internal worker threads used by the map.
-
output_t<cell3d_t> __get(const cell_id_t &cellId_) const
Retrieve cell data associated with a cell ID.
-
inline pair_t<size_t, size_t> __size() const
Get map size counters without additional locking.
- Returns:
Pair
(numKeyframes, numPoints).
-
bool __exists(const cell_id_t &cellId_) const
Check whether a cell exists without external locking.
- Parameters:
cellId_ – Cell identifier.
- Returns:
trueif cell exists, otherwisefalse.
-
std::tuple<size_t, size_t, size_t> __get_number_cells() const
Retrieve current number of allocated cells.
- Returns:
Number of cells in the map {numberQueryCells, numberClosestCells, totalNumberCells}.
-
inline point_id_t __get_next_point_id()
Get next point ID and increment the point counter.
- Returns:
Newly assigned point ID.
-
inline keyframe_id_t __get_next_keyframe_id()
Get next keyframe ID and increment the keyframe counter.
- Returns:
Newly assigned keyframe ID.
-
inline void __sanity_sync(const point_id_t &pointId_) const
Validate internal point-neighbor synchronization.
- Parameters:
pointId_ – Point identifier to validate.
-
inline fail_t __exists(const point_id_t &pointId_) const
Return failure status if a point ID does not exist.
- Parameters:
pointId_ – Point identifier to validate.
- Returns:
fail_t::NO_FAIL if valid, otherwise a fail_t error.
-
inline fail_t __exists(const keyframe_id_t &keyframeId_) const
Return failure status if a keyframe ID does not exist.
- Parameters:
keyframeId_ – Keyframe identifier to validate.
- Returns:
fail_t::NO_FAIL if valid, otherwise a fail_t error.
-
inline void __sanity_exists(const point_id_t &pointId_) const
Throw if a point ID does not exist.
- Parameters:
pointId_ – Point identifier to validate.
-
inline void __sanity_exists(const keyframe_id_t &keyframeId_) const
Throw if a keyframe ID does not exist.
- Parameters:
keyframeId_ – Keyframe identifier to validate.
-
void __sanity_exists(const cell_id_t &cellId_) const
Throw if a cell ID does not exist.
- Parameters:
cellId_ – Cell identifier to validate.
-
inline void __lock_points() const
Acquire exclusive locks for point and neighbor containers.
-
inline void __unlock_points() const
Release exclusive locks for point and neighbor containers.
-
inline void __read_lock_points() const
Acquire shared locks for point and neighbor containers.
-
inline void __read_unlock_points() const
Release shared locks for point and neighbor containers.
-
inline void __lock_keyframes() const
Acquire exclusive lock for keyframe container.
-
inline void __unlock_keyframes() const
Release exclusive lock for keyframe container.
-
inline void __read_lock_keyframes() const
Acquire shared lock for keyframe container.
-
inline void __read_unlock_keyframes() const
Release shared lock for keyframe container.
-
void __sort_cells(std::stop_token token_)
Worker thread routine that reorders visible cells by distance.
- Parameters:
token_ – Stop token used to interrupt the worker thread.
-
inline const neighbor_t::vector &__get_mappoints_neighboors_x(point_id_t pointId_) const
Retrieve point neighbors without taking additional locks.
- Parameters:
pointId_ – Point identifier.
- Returns:
Const reference to neighbor list, or an empty static list.
-
point_id_t::vector __get_points_in_cell_x(const cell_id_t &cellId_) const
Retrieve point IDs contained in a 3D cell.
- Parameters:
cellId_ – Cell identifier.
- Returns:
Vector of point IDs in the requested cell.
-
time_stamp_t __get_timestamp(const keyframe_id_t keyframeId_) const
Retrieve timestamp associated with a keyframe ID.
- Parameters:
keyframeId_ – Keyframe identifier.
- Returns:
Timestamp value for the requested keyframe.
Private Members
-
mutable std::shared_mutex _mutex
Mutex to stop multiple changes of the map attributes at once.
-
pose_t::shared_ptr _cameraPose
Current position of the camera in world coordinates.
-
dictionary_t<keyframe_id_t, keyframe_t::shared_ptr> _keyframes
-
hash_t<point_id_t, point3d_t::shared_ptr> _points
All the 3D _points in the map.
-
hash_t<point_id_t, neighbor_t::vector> _neighbors
All the neighboors of the _points.
-
hash_t<point_id_t, point3d_t::vector> _pointNeighbors
All the _neighbors for the 3D _points in the map.
-
std::jthread _sortCellsThread
Private Static Attributes
-
static point_id_t _nextPointId = point_id_t(0)
Next point ID to be assigned.
-
static keyframe_id_t _nextKeyframeId = keyframe_id_t(0)
Next keyframe ID to be assigned.