NDEVR
API Documentation
LocalMapping

Manages local map building, keyframe processing, and local bundle adjustment. More...

Collaboration diagram for LocalMapping:
[legend]

Public Member Functions

 LocalMapping (OrbSLAM *pSys, Atlas *pAtlas, bool bMonocular, bool bInertial, LogPtr log)
 Constructs the local mapper.
bool AcceptKeyFrames ()
 Checks whether the local mapper is accepting keyframes.
void EmptyQueue ()
 Processes all queued keyframes without blocking.
Buffer< std::pair< Eigen::Vector3f, Vector< 2, uint04 > > > FindSharedPoints (KeyFrame *a, KeyFrame *b)
 Finds shared 3D points between two keyframes.
fltp04 inertialPercent () const
 Returns the IMU initialization progress as a percentage.
void InsertKeyFrame (KeyFrame *pKF)
 Inserts a new keyframe into the processing queue.
void InterruptBA ()
 Interrupts any running bundle adjustment.
bool isFinished ()
 Checks whether the local mapper has finished.
bool isStopped ()
 Checks whether the local mapper is stopped.
void Release ()
 Releases the local mapper from a stopped state.
void RequestFinish ()
 Requests the local mapper to finish.
void RequestReset ()
 Requests a full reset of the local mapper.
void RequestResetActiveMap ()
 Requests a reset of the active map only.
void RequestStop ()
 Requests the local mapper to stop.
void Run ()
 Main local mapping loop.
void SetAcceptKeyFrames (bool flag)
 Sets whether the local mapper accepts keyframes.
void setCameraSettings (bool bMonocular, bool bInertial)
 Updates the camera mode settings.
void SetLoopCloser (LoopClosing *pLoopCloser)
 Sets the loop closer reference.
bool SetNotStop (bool flag)
 Sets whether the local mapper can be stopped.
void SetTracker (Tracking *pTracker)
 Sets the tracker reference.
bool Stop ()
 Attempts to stop the local mapper.
bool stopRequested ()
 Checks whether a stop has been requested.

Detailed Description

Manages local map building, keyframe processing, and local bundle adjustment.

Runs in its own thread, receiving new keyframes from the tracker, creating new map points, culling redundant keyframes, and performing local BA.

Definition at line 23 of file LocalMapping.h.

Constructor & Destructor Documentation

◆ LocalMapping()

LocalMapping::LocalMapping ( OrbSLAM * pSys,
Atlas * pAtlas,
bool bMonocular,
bool bInertial,
LogPtr log )

Constructs the local mapper.

Parameters
[in]pSysPointer to the OrbSLAM system.
[in]pAtlasPointer to the Atlas.
[in]bMonocularTrue if using monocular mode.
[in]bInertialTrue if using inertial mode.
[in]logLogger for diagnostic output.

Member Function Documentation

◆ AcceptKeyFrames()

bool LocalMapping::AcceptKeyFrames ( )

Checks whether the local mapper is accepting keyframes.

Returns
True if accepting keyframes.

◆ FindSharedPoints()

Buffer< std::pair< Eigen::Vector3f, Vector< 2, uint04 > > > LocalMapping::FindSharedPoints ( KeyFrame * a,
KeyFrame * b )

Finds shared 3D points between two keyframes.

Parameters
[in]aFirst keyframe.
[in]bSecond keyframe.
Returns
Buffer of (3D point, observation index pair) pairs.

◆ inertialPercent()

fltp04 LocalMapping::inertialPercent ( ) const

Returns the IMU initialization progress as a percentage.

Returns
Inertial initialization percent (0-1).

◆ InsertKeyFrame()

void LocalMapping::InsertKeyFrame ( KeyFrame * pKF)

Inserts a new keyframe into the processing queue.

Parameters
[in]pKFKeyframe to insert.

◆ isFinished()

bool LocalMapping::isFinished ( )

Checks whether the local mapper has finished.

Returns
True if finished.

◆ isStopped()

bool LocalMapping::isStopped ( )

Checks whether the local mapper is stopped.

Returns
True if stopped.

◆ Run()

void LocalMapping::Run ( )

Main local mapping loop.

Processes keyframes and performs local BA.

◆ SetAcceptKeyFrames()

void LocalMapping::SetAcceptKeyFrames ( bool flag)

Sets whether the local mapper accepts keyframes.

Parameters
[in]flagTrue to accept keyframes.

◆ setCameraSettings()

void LocalMapping::setCameraSettings ( bool bMonocular,
bool bInertial )

Updates the camera mode settings.

Parameters
[in]bMonocularTrue for monocular.
[in]bInertialTrue for inertial.

◆ SetLoopCloser()

void LocalMapping::SetLoopCloser ( LoopClosing * pLoopCloser)

Sets the loop closer reference.

Parameters
[in]pLoopCloserPointer to the loop closer.

◆ SetNotStop()

bool LocalMapping::SetNotStop ( bool flag)

Sets whether the local mapper can be stopped.

Parameters
[in]flagTrue to prevent stopping.
Returns
True if the flag was set.

◆ SetTracker()

void LocalMapping::SetTracker ( Tracking * pTracker)

Sets the tracker reference.

Parameters
[in]pTrackerPointer to the tracker.

◆ Stop()

bool LocalMapping::Stop ( )

Attempts to stop the local mapper.

Returns
True if successfully stopped.

◆ stopRequested()

bool LocalMapping::stopRequested ( )

Checks whether a stop has been requested.

Returns
True if a stop was requested.

The documentation for this class was generated from the following file: