NDEVR
API Documentation
Frame

Represents a single image frame with extracted features and pose information. More...

Inheritance diagram for Frame:
[legend]
Collaboration diagram for Frame:
[legend]

Public Member Functions

 Frame ()=default
 Default constructor.
 Frame (const Frame &frame)
 Copy constructor.
 Frame (Frame &&frame) noexcept
 Move constructor.
 Frame (FrameInfo *frame_info, const cv::Mat &imGray, const cv::Mat &imDepth, fltp08 timeStamp, ORBextractor *extractor, ORBVocabulary *voc, const IMU::Calib &ImuCalib=IMU::Calib())
 Constructor for RGB-D cameras.
 Frame (FrameInfo *frame_info, const cv::Mat &imGray, fltp08 timeStamp, ORBextractor *extractor, ORBVocabulary *voc, const IMU::Calib &ImuCalib=IMU::Calib())
 Constructor for monocular cameras.
 Frame (FrameInfo *frame_info, const cv::Mat &imLeft, const cv::Mat &imRight, fltp08 timeStamp, ORBextractor *extractorLeft, ORBextractor *extractorRight, ORBVocabulary *voc, const IMU::Calib &ImuCalib=IMU::Calib())
 Constructor for stereo cameras.
 Frame (FrameInfo *frame_info, const cv::Mat &imLeft, const cv::Mat &imRight, fltp08 timeStamp, ORBextractor *extractorLeft, ORBextractor *extractorRight, ORBVocabulary *voc, GeometricCamera *pCamera2, Sophus::SE3< g_type > &Tlr, const IMU::Calib &ImuCalib=IMU::Calib())
 Constructor for stereo cameras with a second camera model.
 ~Frame ()
 Destructor.
const BowVector & bow () const
 Returns the Bag of Words vector.
const Eigen::Vector3< g_type > & cameraCenter () const
 Returns the camera center in world coordinates.
Eigen::Matrix3< g_type > cameraRotation () const
 Returns the world-to-camera rotation (inverse rotation).
void clearBoW ()
 Clears the Bag of Words data.
void clearMapPoints ()
 Clears all map point associations.
void computeBoW ()
 Computes the Bag of Words representation for this frame.
void ComputeStereoFishEyeMatches ()
 Computes stereo matches for fisheye cameras.
void computeStereoFromRGBD (const cv::Mat &imDepth)
 Associates depth-derived right coordinates to keypoints from an RGB-D depthmap.
void computeStereoMatches ()
 Searches stereo matches between left and right keypoints.
fltp04 depth (uint04 idx) const
 Returns the depth at the given keypoint index.
Vector< 2, uint04discardOutliers ()
 Discards outlier map point associations.
void eraseMapPointMatch (uint04)
 Removes a map point association at the given index.
void extractORB (uint01 flag, const cv::Mat &im, uint04 x0, uint04 x1)
 Extracts ORB features from the image.
const Dictionary< uint04, Buffer< uint04 > > & featureIndices () const
 Returns the feature index map (word ID to keypoint indices).
void getFeaturesInArea (Buffer< uint04 > &indices, fltp04 x, fltp04 y, fltp04 r, uint04 min_level=0U, uint04 max_level=Constant< uint04 >::Max, const bool bRight=false) const
 Finds features within a circular area in the image.
virtual Eigen::Matrix< g_type, 3, 1 > GetImuPosition () const
 Returns the IMU position in world coordinates.
virtual Eigen::Matrix< g_type, 3, 3 > GetImuRotation () const
 Returns the IMU rotation matrix.
Sophus::SE3< g_type > GetRelativePoseTlr () const
 Returns the relative pose from left to right camera.
Eigen::Matrix3< g_type > GetRelativePoseTlr_rotation () const
 Returns the rotation component of the left-to-right relative pose.
Eigen::Vector3< g_type > GetRelativePoseTlr_translation () const
 Returns the translation component of the left-to-right relative pose.
Sophus::SE3< g_type > GetRelativePoseTrl () const
 Returns the relative pose from right to left camera.
virtual Eigen::Matrix3< g_type > GetRotation () const
 Returns the camera rotation matrix (camera-to-world).
virtual Eigen::Vector3< g_type > GetTranslation () const
 Returns the camera translation vector (camera-to-world).
bool hasCamera (uint01 index) const
 Checks whether a camera at the given index is available.
bool HasPose () const
 Checks whether a valid pose has been set.
bool HasVelocity () const
 Checks whether a valid velocity has been set.
bool imuIsPreintegrated () const
 Checks whether the IMU preintegration is complete.
virtual Sophus::SE3< g_type > imuPose () const
 Returns the IMU pose as an SE3 transform.
const FrameInfoinfo () const
 Returns the shared frame info.
void init (FrameInfo *info, const cv::Mat &imGray, const cv::Mat &imDepth, fltp08 timeStamp, ORBextractor *extractor, ORBVocabulary *voc, const IMU::Calib &ImuCalib=IMU::Calib())
 Initializes a frame from RGB-D data.
Eigen::Vector3< g_type > inRefCoordinates (Eigen::Vector3< g_type > pCw) const
 Transforms a world-coordinate point into this frame's camera coordinates.
virtual Sophus::SE3< g_type > inversePose () const
 Returns the inverse camera pose (camera-to-world transform).
const Buffer< float > & invLevelSigma2 () const
 Returns the inverse sigma squared values per pyramid level.
const Buffer< float > & invScaleFactors () const
 Returns the inverse ORB scale factors per pyramid level.
bool isKeyFrame ()
 Checks whether this frame is a keyframe.
bool isMono () const
 Checks whether this frame is monocular (single camera).
bool isOutlier (uint04 idx) const
 Checks whether the map point at the given index is an outlier.
bool isSet () const
 Checks whether this frame has been initialized.
const cv::KeyPoint & keypoint (uint04 i) const
 Returns the keypoint at the given index.
const cv::KeyPoint & keypoint (uint04 i, bool is_right) const
 Returns the keypoint at the given index from left or right view.
uint04 levelCount () const
 Returns the number of pyramid levels.
const Buffer< float > & levelSigma2 () const
 Returns the sigma squared values per pyramid level.
virtual Eigen::Vector3< g_type > linearVelocity () const
 Returns the linear velocity of the frame.
LogPtr log ()
 Returns the logger for this frame.
MapPointmapPoint (uint04 idx)
 Returns the map point at the given index (non-const).
MapPointmapPoint (uint04 idx) const
 Returns the map point at the given index.
uint04 mapPointCount () const
 Returns the number of map points associated with this frame.
const Buffer< MapPoint * > & mapPointMatches ()
 Returns the map point matches buffer.
const Buffer< MapPoint * > & mapPoints () const
 Returns all map point associations.
RWLockmapPointsLockPtr () const
 Returns the read-write lock for map point access.
fltp04 nearFarThreshold () const
 Returns the near/far depth threshold.
uint04 observationCount (uint04 idx) const
 Returns the observation count for a map point at the given index.
Frameoperator= (const Frame &frame) noexcept
 Copy assignment operator.
Frameoperator= (Frame &&frame) noexcept
 Move assignment operator.
const Buffer< bool > & outliers () const
 Returns the outlier flags buffer.
virtual Sophus::SE3< g_type > pose () const
 Returns the camera pose (world-to-camera transform).
fltp04 right (uint04 idx) const
 Returns the right stereo coordinate at the given keypoint index.
fltp04 scaleFactor () const
 Returns the ORB scale factor.
const Buffer< float > & scaleFactors () const
 Returns the ORB scale factors per pyramid level.
void setImuPoseVelocity (const Eigen::Matrix3< g_type > &Rwb, const Eigen::Vector3< g_type > &twb, const Eigen::Vector3< g_type > &Vwb)
 Sets IMU pose and velocity, implicitly updating the camera pose.
void setIntegrated ()
 Marks the IMU preintegration as complete.
virtual void setLinearVelocity (const Eigen::Vector3< g_type > &Vw)
 Sets the IMU linear velocity.
void setMapPointMatch (uint04, MapPoint *pMP)
 Sets a map point association at the given index.
void setMapPoints (const Buffer< MapPoint * > &map_points)
 Sets all map point associations.
void SetNewBias (const IMU::Bias &b)
 Updates the IMU bias.
void setOutlier (uint04 idx, bool outlier)
 Sets the outlier flag at the given index.
void setOutliers (const Buffer< bool > &map_points)
 Sets the outlier flags buffer.
virtual void setPose (const Sophus::SE3< g_type > &Tcw)
 Sets the camera pose (does not modify IMU pose).
Eigen::Vector3< g_type > stereo3DPoint (uint04 idx) const
 Returns the triangulated 3D stereo point at the given index.
const Eigen::Matrix< g_type, 3, 1 > & tcw () const
 Returns the camera-to-world translation.
fltp08 timestamp () const
 Returns the capture timestamp.
fltp04 trackDepth (const Eigen::Vector3< g_type > &global_position) const
 Computes the depth of a 3D point relative to this frame's camera.
uint04 trackedMapPoints (uint04 minObs) const
 Counts map points with at least the given number of observations.
const cv::KeyPoint & undistortedPoint (uint04 idx) const
 Returns the undistorted keypoint at the given index.
uint04 undistortedPointCount () const
 Returns the number of undistorted keypoints.
const PrimitiveAlignedBuffer< cv::KeyPoint, 32 > & undistortedPoints () const
 Returns all undistorted keypoints.
Eigen::Vector3< g_type > unproject (uint04 i)
 Backprojects a keypoint into 3D world coordinates using stereo/depth info.
void updatePoseMatrices ()
 Recomputes derived pose matrices from the current camera pose.

Public Attributes

uint04 id = Constant<uint04>::Invalid
 Unique frame ID.
IMUData imu_data
 IMU calibration and bias data.
ORBextractorm_extractor
 ORB feature extractor.
Dictionary< uint04, Buffer< uint04 > > m_features_indices
 Maps BoW word IDs to keypoint indices.
FrameInfom_frame_info = nullptr
 Shared camera info (intrinsics, bounds).
bool m_is_keyframe = false
 Whether this frame is a keyframe.
fltp08 m_timestamp = 0.0
 Frame capture timestamp.
FrameViewm_view [2] = { nullptr, nullptr }
 Left [0] and right [1] view data.
bool mbHasPose = false
 Whether a valid pose has been set.
bool mbHasVelocity = false
 Whether a valid velocity has been set.
bool mbImuPreintegrated = false
 Whether IMU preintegration is complete.
bool mbIsSet = false
 Whether this frame has been initialized.
Eigen::Vector3< g_type > mOwb
 IMU position in world coordinates.
ConstraintPoseImumpcpi = nullptr
 IMU pose constraint.
IMU::Preintegrated * mpImuPreintegrated = nullptr
 IMU preintegration from last keyframe.
IMU::Preintegrated * mpImuPreintegratedFrame = nullptr
 Frame-level IMU preintegration.
KeyFramempLastKeyFrame = nullptr
 Previous keyframe.
ORBVocabularympORBvocabulary = nullptr
 ORB vocabulary for relocalization.
KeyFramempReferenceKF = nullptr
 Reference keyframe.
uint04 N = 0
 Number of keypoints.
Sophus::SE3< g_type > sensor_pose
 External sensor pose.

Static Public Attributes

static cv::BFMatcher BFmatcher
 Brute-force matcher for stereo fisheye matching.
static volatile uint04 s_next_id
 Global frame ID counter.
static __attribute__((visibility("default"))) static void Set3DCallback(std std::function< Vector< 3, fltp04 >(Frame *frame, Vector< 3, fltp04 >) s_point_to_3d_callback )
 Sets a callback for converting frame points to 3D.

Protected Attributes

BowVector m_bow
 Bag of Words vector for this frame.
Buffer< fltp04m_depth
 Depth per keypoint.
RWLock m_feature_lock
 Read-write lock for map point access.
Eigen::Vector3< g_type > m_linear_velocity = Eigen::Vector3<g_type>(0,0,0)
 IMU linear velocity.
Buffer< MapPoint * > m_map_points
 Map point associations for each keypoint.
Buffer< Vector< 2, fltp04 > > m_original_points
 Original (possibly distorted) keypoint positions.
Buffer< bool > m_outlier
 Outlier flag per keypoint.
Buffer< fltp04m_right
 Right stereo coordinate per keypoint (negative if monocular).
Buffer< Eigen::Vector3< g_type > > m_stereo_3D_points
 Triangulated stereo 3D points from fisheye matching.
PrimitiveAlignedBuffer< cv::KeyPoint, 32 > m_undistorted_points
 Undistorted keypoints used by the system.
Sophus::SE3< g_type > mTcw
 World-to-camera transform.
Sophus::SE3< g_type > mTlr
 Left-to-right camera relative pose.
Sophus::SE3< g_type > mTrl
 Right-to-left camera relative pose.
Sophus::SE3< g_type > mTwc
 Camera-to-world transform (inverse of mTcw).

Detailed Description

Represents a single image frame with extracted features and pose information.

A Frame holds keypoints, descriptors, map point associations, and camera pose for a single captured image. It supports monocular, stereo, and RGB-D configurations.

Definition at line 110 of file Frame.h.

Constructor & Destructor Documentation

◆ Frame() [1/6]

Frame::Frame ( const Frame & frame)

Copy constructor.

Parameters
[in]frameFrame to copy.

References Frame().

◆ Frame() [2/6]

Frame::Frame ( Frame && frame)
noexcept

Move constructor.

Parameters
[in]frameFrame to move from.

References Frame().

◆ Frame() [3/6]

Frame::Frame ( FrameInfo * frame_info,
const cv::Mat & imLeft,
const cv::Mat & imRight,
fltp08 timeStamp,
ORBextractor * extractorLeft,
ORBextractor * extractorRight,
ORBVocabulary * voc,
const IMU::Calib & ImuCalib = IMU::Calib() )

Constructor for stereo cameras.

Parameters
[in]frame_infoShared camera info.
[in]imLeftLeft image (grayscale or RGB).
[in]imRightRight image.
[in]timeStampCapture timestamp.
[in]extractorLeftORB extractor for the left image.
[in]extractorRightORB extractor for the right image.
[in]vocORB vocabulary for BoW.
[in]ImuCalibIMU calibration (optional).

◆ Frame() [4/6]

Frame::Frame ( FrameInfo * frame_info,
const cv::Mat & imLeft,
const cv::Mat & imRight,
fltp08 timeStamp,
ORBextractor * extractorLeft,
ORBextractor * extractorRight,
ORBVocabulary * voc,
GeometricCamera * pCamera2,
Sophus::SE3< g_type > & Tlr,
const IMU::Calib & ImuCalib = IMU::Calib() )

Constructor for stereo cameras with a second camera model.

Parameters
[in]frame_infoShared camera info.
[in]imLeftLeft image.
[in]imRightRight image.
[in]timeStampCapture timestamp.
[in]extractorLeftORB extractor for the left image.
[in]extractorRightORB extractor for the right image.
[in]vocORB vocabulary for BoW.
[in]pCamera2Second camera model for fisheye stereo.
[in]TlrRelative pose from left to right camera.
[in]ImuCalibIMU calibration (optional).

◆ Frame() [5/6]

Frame::Frame ( FrameInfo * frame_info,
const cv::Mat & imGray,
const cv::Mat & imDepth,
fltp08 timeStamp,
ORBextractor * extractor,
ORBVocabulary * voc,
const IMU::Calib & ImuCalib = IMU::Calib() )

Constructor for RGB-D cameras.

Parameters
[in]frame_infoShared camera info.
[in]imGrayGrayscale image.
[in]imDepthDepth image (CV_32F).
[in]timeStampCapture timestamp.
[in]extractorORB feature extractor.
[in]vocORB vocabulary for BoW.
[in]ImuCalibIMU calibration (optional).

◆ Frame() [6/6]

Frame::Frame ( FrameInfo * frame_info,
const cv::Mat & imGray,
fltp08 timeStamp,
ORBextractor * extractor,
ORBVocabulary * voc,
const IMU::Calib & ImuCalib = IMU::Calib() )

Constructor for monocular cameras.

Parameters
[in]frame_infoShared camera info.
[in]imGrayGrayscale image.
[in]timeStampCapture timestamp.
[in]extractorORB feature extractor.
[in]vocORB vocabulary for BoW.
[in]ImuCalibIMU calibration (optional).

Member Function Documentation

◆ bow()

const BowVector & Frame::bow ( ) const
inline

Returns the Bag of Words vector.

Returns
Reference to the BoW vector.

Definition at line 535 of file Frame.h.

References m_bow.

◆ cameraCenter()

const Eigen::Vector3< g_type > & Frame::cameraCenter ( ) const
inline

Returns the camera center in world coordinates.

Returns
The 3D camera center.

Definition at line 379 of file Frame.h.

References mTwc.

Referenced by MapPointProjection::checkInFrustum(), and MapPointProjection::isInFrustumChecks().

◆ cameraRotation()

Eigen::Matrix3< g_type > Frame::cameraRotation ( ) const
inline

Returns the world-to-camera rotation (inverse rotation).

Returns
The 3x3 rotation matrix.

Definition at line 391 of file Frame.h.

References mTwc.

◆ computeStereoFromRGBD()

void Frame::computeStereoFromRGBD ( const cv::Mat & imDepth)

Associates depth-derived right coordinates to keypoints from an RGB-D depthmap.

Parameters
[in]imDepthThe depth image.

◆ computeStereoMatches()

void Frame::computeStereoMatches ( )

Searches stereo matches between left and right keypoints.

For each matched keypoint, depth and right coordinate are computed and stored.

◆ depth()

fltp04 Frame::depth ( uint04 idx) const
inline

Returns the depth at the given keypoint index.

Parameters
[in]idxKeypoint index.
Returns
The depth value.

Definition at line 437 of file Frame.h.

References m_depth.

◆ discardOutliers()

Vector< 2, uint04 > Frame::discardOutliers ( )

Discards outlier map point associations.

Returns
Vector of (inlier count, outlier count).

◆ eraseMapPointMatch()

void Frame::eraseMapPointMatch ( uint04 )

Removes a map point association at the given index.

Parameters
[in]idxKeypoint index.

◆ extractORB()

void Frame::extractORB ( uint01 flag,
const cv::Mat & im,
uint04 x0,
uint04 x1 )

Extracts ORB features from the image.

Parameters
[in]flag0 for left image, 1 for right image.
[in]imThe image to extract from.
[in]x0Start column for the lapping area.
[in]x1End column for the lapping area.

◆ featureIndices()

const Dictionary< uint04, Buffer< uint04 > > & Frame::featureIndices ( ) const
inline

Returns the feature index map (word ID to keypoint indices).

Returns
Reference to the feature indices dictionary.

Definition at line 539 of file Frame.h.

References m_features_indices.

◆ getFeaturesInArea()

void Frame::getFeaturesInArea ( Buffer< uint04 > & indices,
fltp04 x,
fltp04 y,
fltp04 r,
uint04 min_level = 0U,
uint04 max_level = Constantuint04 >::Max,
const bool bRight = false ) const

Finds features within a circular area in the image.

Parameters
[out]indicesBuffer to fill with matching keypoint indices.
[in]xCenter x coordinate.
[in]yCenter y coordinate.
[in]rSearch radius.
[in]min_levelMinimum pyramid level (default 0).
[in]max_levelMaximum pyramid level (default max).
[in]bRightTrue to search in the right view.

◆ GetImuPosition()

virtual Eigen::Matrix< g_type, 3, 1 > Frame::GetImuPosition ( ) const
virtual

Returns the IMU position in world coordinates.

Returns
The 3D IMU position.

Reimplemented in KeyFrame.

◆ GetImuRotation()

virtual Eigen::Matrix< g_type, 3, 3 > Frame::GetImuRotation ( ) const
virtual

Returns the IMU rotation matrix.

Returns
The 3x3 IMU rotation.

Reimplemented in KeyFrame.

◆ GetRelativePoseTlr()

Sophus::SE3< g_type > Frame::GetRelativePoseTlr ( ) const

Returns the relative pose from left to right camera.

Returns
The SE3 transform Tlr.

◆ GetRelativePoseTlr_rotation()

Eigen::Matrix3< g_type > Frame::GetRelativePoseTlr_rotation ( ) const

Returns the rotation component of the left-to-right relative pose.

Returns
The 3x3 rotation matrix.

◆ GetRelativePoseTlr_translation()

Eigen::Vector3< g_type > Frame::GetRelativePoseTlr_translation ( ) const

Returns the translation component of the left-to-right relative pose.

Returns
The 3D translation vector.

Referenced by MapPointProjection::isInFrustumChecks().

◆ GetRelativePoseTrl()

Sophus::SE3< g_type > Frame::GetRelativePoseTrl ( ) const

Returns the relative pose from right to left camera.

Returns
The SE3 transform Trl.

Referenced by MapPointProjection::isInFrustumChecks().

◆ GetRotation()

virtual Eigen::Matrix3< g_type > Frame::GetRotation ( ) const
virtual

Returns the camera rotation matrix (camera-to-world).

Returns
The 3x3 rotation matrix.

Reimplemented in KeyFrame.

Referenced by MapPointProjection::isInFrustumChecks().

◆ GetTranslation()

virtual Eigen::Vector3< g_type > Frame::GetTranslation ( ) const
virtual

Returns the camera translation vector (camera-to-world).

Returns
The 3D translation vector.

Reimplemented in KeyFrame.

◆ hasCamera()

bool Frame::hasCamera ( uint01 index) const

Checks whether a camera at the given index is available.

Parameters
[in]indexCamera index (0 or 1).
Returns
True if the camera exists.

◆ HasPose()

bool Frame::HasPose ( ) const
inline

Checks whether a valid pose has been set.

Returns
True if the pose is available.

Definition at line 414 of file Frame.h.

References mbHasPose.

◆ HasVelocity()

bool Frame::HasVelocity ( ) const
inline

Checks whether a valid velocity has been set.

Returns
True if velocity is available.

Definition at line 421 of file Frame.h.

References mbHasVelocity.

◆ imuIsPreintegrated()

bool Frame::imuIsPreintegrated ( ) const

Checks whether the IMU preintegration is complete.

Returns
True if preintegrated.

◆ imuPose()

virtual Sophus::SE3< g_type > Frame::imuPose ( ) const
virtual

Returns the IMU pose as an SE3 transform.

Returns
The IMU pose.

Reimplemented in KeyFrame.

◆ info()

const FrameInfo & Frame::info ( ) const
inline

Returns the shared frame info.

Returns
Reference to the FrameInfo.

Definition at line 527 of file Frame.h.

References m_frame_info.

Referenced by MapPointProjection::checkInFrustum(), init(), and MapPointProjection::isInFrustumChecks().

◆ init()

void Frame::init ( FrameInfo * info,
const cv::Mat & imGray,
const cv::Mat & imDepth,
fltp08 timeStamp,
ORBextractor * extractor,
ORBVocabulary * voc,
const IMU::Calib & ImuCalib = IMU::Calib() )

Initializes a frame from RGB-D data.

Parameters
[in]infoShared camera info.
[in]imGrayGrayscale image.
[in]imDepthDepth image.
[in]timeStampCapture timestamp.
[in]extractorORB feature extractor.
[in]vocORB vocabulary.
[in]ImuCalibIMU calibration (optional).

References info().

◆ inRefCoordinates()

Eigen::Vector3< g_type > Frame::inRefCoordinates ( Eigen::Vector3< g_type > pCw) const

Transforms a world-coordinate point into this frame's camera coordinates.

Parameters
[in]pCwPoint in world coordinates.
Returns
Point in camera coordinates.

Referenced by MapPointProjection::checkInFrustum().

◆ inversePose()

virtual Sophus::SE3< g_type > Frame::inversePose ( ) const
inlinevirtual

Returns the inverse camera pose (camera-to-world transform).

Returns
The SE3 pose Twc.

Reimplemented in KeyFrame.

Definition at line 408 of file Frame.h.

References mTwc.

◆ invLevelSigma2()

const Buffer< float > & Frame::invLevelSigma2 ( ) const

Returns the inverse sigma squared values per pyramid level.

Returns
Reference to the inverse level sigma squared buffer.

◆ invScaleFactors()

const Buffer< float > & Frame::invScaleFactors ( ) const

Returns the inverse ORB scale factors per pyramid level.

Returns
Reference to the inverse scale factor buffer.

◆ isKeyFrame()

bool Frame::isKeyFrame ( )
inline

Checks whether this frame is a keyframe.

Returns
True if this frame is a keyframe.

Definition at line 398 of file Frame.h.

References m_is_keyframe.

◆ isMono()

bool Frame::isMono ( ) const

Checks whether this frame is monocular (single camera).

Returns
True if monocular.

◆ isOutlier()

bool Frame::isOutlier ( uint04 idx) const
inline

Checks whether the map point at the given index is an outlier.

Parameters
[in]idxKeypoint index.
Returns
True if outlier.

Definition at line 470 of file Frame.h.

References m_outlier.

◆ isSet()

bool Frame::isSet ( ) const
inline

Checks whether this frame has been initialized.

Returns
True if set.

Definition at line 371 of file Frame.h.

References mbIsSet.

◆ keypoint() [1/2]

const cv::KeyPoint & Frame::keypoint ( uint04 i) const

Returns the keypoint at the given index.

Parameters
[in]iKeypoint index.
Returns
Reference to the keypoint.

◆ keypoint() [2/2]

const cv::KeyPoint & Frame::keypoint ( uint04 i,
bool is_right ) const

Returns the keypoint at the given index from left or right view.

Parameters
[in]iKeypoint index.
[in]is_rightTrue for right view keypoints.
Returns
Reference to the keypoint.

◆ levelCount()

uint04 Frame::levelCount ( ) const

Returns the number of pyramid levels.

Returns
Level count.

◆ levelSigma2()

const Buffer< float > & Frame::levelSigma2 ( ) const

Returns the sigma squared values per pyramid level.

Returns
Reference to the level sigma squared buffer.

◆ linearVelocity()

virtual Eigen::Vector3< g_type > Frame::linearVelocity ( ) const
virtual

Returns the linear velocity of the frame.

Returns
The 3D velocity vector.

Reimplemented in KeyFrame.

◆ log()

LogPtr Frame::log ( )
inline

Returns the logger for this frame.

Returns
Logger pointer.

Definition at line 446 of file Frame.h.

References m_frame_info.

◆ mapPoint() [1/2]

MapPoint * Frame::mapPoint ( uint04 idx)

Returns the map point at the given index (non-const).

Parameters
[in]idxKeypoint index.
Returns
Pointer to the map point.

◆ mapPoint() [2/2]

MapPoint * Frame::mapPoint ( uint04 idx) const
inline

Returns the map point at the given index.

Parameters
[in]idxMap point index.
Returns
Pointer to the map point.

Definition at line 267 of file Frame.h.

References m_map_points.

◆ mapPointCount()

uint04 Frame::mapPointCount ( ) const
inline

Returns the number of map points associated with this frame.

Returns
Map point count.

Definition at line 262 of file Frame.h.

References m_map_points.

◆ mapPointMatches()

const Buffer< MapPoint * > & Frame::mapPointMatches ( )

Returns the map point matches buffer.

Returns
Reference to the map point matches.

◆ mapPoints()

const Buffer< MapPoint * > & Frame::mapPoints ( ) const
inline

Returns all map point associations.

Returns
Reference to the map points buffer.

Definition at line 453 of file Frame.h.

References m_map_points.

◆ mapPointsLockPtr()

RWLock & Frame::mapPointsLockPtr ( ) const
inline

Returns the read-write lock for map point access.

Returns
Reference to the feature lock.

Definition at line 427 of file Frame.h.

References m_feature_lock.

◆ nearFarThreshold()

fltp04 Frame::nearFarThreshold ( ) const
inline

Returns the near/far depth threshold.

Returns
The depth threshold.

Definition at line 523 of file Frame.h.

References m_frame_info.

◆ observationCount()

uint04 Frame::observationCount ( uint04 idx) const

Returns the observation count for a map point at the given index.

Parameters
[in]idxMap point index.
Returns
Number of observations.

◆ operator=() [1/2]

Frame & Frame::operator= ( const Frame & frame)
noexcept

Copy assignment operator.

Parameters
[in]frameFrame to copy.
Returns
Reference to this frame.

References Frame().

◆ operator=() [2/2]

Frame & Frame::operator= ( Frame && frame)
noexcept

Move assignment operator.

Parameters
[in]frameFrame to move from.
Returns
Reference to this frame.

References Frame().

◆ outliers()

const Buffer< bool > & Frame::outliers ( ) const
inline

Returns the outlier flags buffer.

Returns
Reference to the outlier buffer.

Definition at line 461 of file Frame.h.

References m_outlier.

◆ pose()

virtual Sophus::SE3< g_type > Frame::pose ( ) const
inlinevirtual

Returns the camera pose (world-to-camera transform).

Returns
The SE3 pose Tcw.

Reimplemented in KeyFrame.

Definition at line 402 of file Frame.h.

References mTcw.

◆ right()

fltp04 Frame::right ( uint04 idx) const
inline

Returns the right stereo coordinate at the given keypoint index.

Parameters
[in]idxKeypoint index.
Returns
The right coordinate (negative if monocular).

Definition at line 442 of file Frame.h.

References m_right.

◆ scaleFactor()

fltp04 Frame::scaleFactor ( ) const

Returns the ORB scale factor.

Returns
The scale factor.

◆ scaleFactors()

const Buffer< float > & Frame::scaleFactors ( ) const

Returns the ORB scale factors per pyramid level.

Returns
Reference to the scale factor buffer.

◆ setImuPoseVelocity()

void Frame::setImuPoseVelocity ( const Eigen::Matrix3< g_type > & Rwb,
const Eigen::Vector3< g_type > & twb,
const Eigen::Vector3< g_type > & Vwb )

Sets IMU pose and velocity, implicitly updating the camera pose.

Parameters
[in]RwbRotation from body to world.
[in]twbTranslation from body to world.
[in]VwbVelocity in world coordinates.

◆ setLinearVelocity()

virtual void Frame::setLinearVelocity ( const Eigen::Vector3< g_type > & Vw)
virtual

Sets the IMU linear velocity.

Parameters
[in]VwVelocity vector in world coordinates.

Reimplemented in KeyFrame.

◆ setMapPointMatch()

void Frame::setMapPointMatch ( uint04 ,
MapPoint * pMP )

Sets a map point association at the given index.

Parameters
[in]idxKeypoint index.
[in]pMPPointer to the map point.

◆ setMapPoints()

void Frame::setMapPoints ( const Buffer< MapPoint * > & map_points)
inline

Sets all map point associations.

Parameters
[in]map_pointsBuffer of map point pointers.

Definition at line 457 of file Frame.h.

References m_map_points.

◆ SetNewBias()

void Frame::SetNewBias ( const IMU::Bias & b)

Updates the IMU bias.

Parameters
[in]bNew IMU bias.

◆ setOutlier()

void Frame::setOutlier ( uint04 idx,
bool outlier )

Sets the outlier flag at the given index.

Parameters
[in]idxKeypoint index.
[in]outlierTrue to mark as outlier.

◆ setOutliers()

void Frame::setOutliers ( const Buffer< bool > & map_points)
inline

Sets the outlier flags buffer.

Parameters
[in]map_pointsBuffer of outlier flags.

Definition at line 465 of file Frame.h.

References m_outlier.

◆ setPose()

virtual void Frame::setPose ( const Sophus::SE3< g_type > & Tcw)
virtual

Sets the camera pose (does not modify IMU pose).

Parameters
[in]TcwCamera-to-world transformation.

Reimplemented in KeyFrame.

◆ stereo3DPoint()

Eigen::Vector3< g_type > Frame::stereo3DPoint ( uint04 idx) const

Returns the triangulated 3D stereo point at the given index.

Parameters
[in]idxKeypoint index.
Returns
The 3D point.

◆ tcw()

const Eigen::Matrix< g_type, 3, 1 > & Frame::tcw ( ) const
inline

Returns the camera-to-world translation.

Returns
The 3D translation vector.

Definition at line 385 of file Frame.h.

References mTcw.

Referenced by MapPointProjection::isInFrustumChecks().

◆ timestamp()

fltp08 Frame::timestamp ( ) const
inline

Returns the capture timestamp.

Returns
The timestamp.

Definition at line 531 of file Frame.h.

References m_timestamp.

◆ trackDepth()

fltp04 Frame::trackDepth ( const Eigen::Vector3< g_type > & global_position) const

Computes the depth of a 3D point relative to this frame's camera.

Parameters
[in]global_positionThe 3D point in world coordinates.
Returns
The depth value.

◆ trackedMapPoints()

uint04 Frame::trackedMapPoints ( uint04 minObs) const

Counts map points with at least the given number of observations.

Parameters
[in]minObsMinimum observation count threshold.
Returns
Number of tracked map points.

◆ undistortedPoint()

const cv::KeyPoint & Frame::undistortedPoint ( uint04 idx) const
inline

Returns the undistorted keypoint at the given index.

Parameters
[in]idxKeypoint index.
Returns
Reference to the keypoint.

Definition at line 345 of file Frame.h.

References m_undistorted_points.

◆ undistortedPointCount()

uint04 Frame::undistortedPointCount ( ) const
inline

Returns the number of undistorted keypoints.

Returns
Keypoint count.

Definition at line 349 of file Frame.h.

References m_undistorted_points.

◆ undistortedPoints()

const PrimitiveAlignedBuffer< cv::KeyPoint, 32 > & Frame::undistortedPoints ( ) const
inline

Returns all undistorted keypoints.

Returns
Reference to the undistorted keypoint buffer.

Definition at line 340 of file Frame.h.

References m_undistorted_points.

◆ unproject()

Eigen::Vector3< g_type > Frame::unproject ( uint04 i)

Backprojects a keypoint into 3D world coordinates using stereo/depth info.

Parameters
[in]iKeypoint index.
Returns
The 3D world coordinate.

Member Data Documentation

◆ s_point_to_3d_callback

__attribute__ ((visibility("default"))) static void Set3DCallback(std std::function<Vector<3, fltp04>(Frame* frame, Vector<3, fltp04>) Frame::s_point_to_3d_callback)
static

Sets a callback for converting frame points to 3D.

Parameters
[in]callbackThe 3D conversion callback function. Static callback for 3D point conversion.

Definition at line 603 of file Frame.h.


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