![]() |
NDEVR
API Documentation
|
Represents a single image frame with extracted features and pose information. More...
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, uint04 > | discardOutliers () |
| 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 FrameInfo & | info () 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. | |
| MapPoint * | mapPoint (uint04 idx) |
| Returns the map point at the given index (non-const). | |
| MapPoint * | mapPoint (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. | |
| RWLock & | mapPointsLockPtr () 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. | |
| Frame & | operator= (const Frame &frame) noexcept |
| Copy assignment operator. | |
| Frame & | operator= (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. | |
| ORBextractor * | m_extractor |
| ORB feature extractor. | |
| Dictionary< uint04, Buffer< uint04 > > | m_features_indices |
| Maps BoW word IDs to keypoint indices. | |
| FrameInfo * | m_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. | |
| FrameView * | m_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. | |
| ConstraintPoseImu * | mpcpi = nullptr |
| IMU pose constraint. | |
| IMU::Preintegrated * | mpImuPreintegrated = nullptr |
| IMU preintegration from last keyframe. | |
| IMU::Preintegrated * | mpImuPreintegratedFrame = nullptr |
| Frame-level IMU preintegration. | |
| KeyFrame * | mpLastKeyFrame = nullptr |
| Previous keyframe. | |
| ORBVocabulary * | mpORBvocabulary = nullptr |
| ORB vocabulary for relocalization. | |
| KeyFrame * | mpReferenceKF = 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< fltp04 > | m_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< fltp04 > | m_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). | |
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.
| Frame::Frame | ( | const Frame & | frame | ) |
|
noexcept |
| 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.
| [in] | frame_info | Shared camera info. |
| [in] | imLeft | Left image (grayscale or RGB). |
| [in] | imRight | Right image. |
| [in] | timeStamp | Capture timestamp. |
| [in] | extractorLeft | ORB extractor for the left image. |
| [in] | extractorRight | ORB extractor for the right image. |
| [in] | voc | ORB vocabulary for BoW. |
| [in] | ImuCalib | IMU calibration (optional). |
| 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.
| [in] | frame_info | Shared camera info. |
| [in] | imLeft | Left image. |
| [in] | imRight | Right image. |
| [in] | timeStamp | Capture timestamp. |
| [in] | extractorLeft | ORB extractor for the left image. |
| [in] | extractorRight | ORB extractor for the right image. |
| [in] | voc | ORB vocabulary for BoW. |
| [in] | pCamera2 | Second camera model for fisheye stereo. |
| [in] | Tlr | Relative pose from left to right camera. |
| [in] | ImuCalib | IMU calibration (optional). |
| 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.
| [in] | frame_info | Shared camera info. |
| [in] | imGray | Grayscale image. |
| [in] | imDepth | Depth image (CV_32F). |
| [in] | timeStamp | Capture timestamp. |
| [in] | extractor | ORB feature extractor. |
| [in] | voc | ORB vocabulary for BoW. |
| [in] | ImuCalib | IMU calibration (optional). |
| 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.
| [in] | frame_info | Shared camera info. |
| [in] | imGray | Grayscale image. |
| [in] | timeStamp | Capture timestamp. |
| [in] | extractor | ORB feature extractor. |
| [in] | voc | ORB vocabulary for BoW. |
| [in] | ImuCalib | IMU calibration (optional). |
|
inline |
|
inline |
Returns the camera center in world coordinates.
Definition at line 379 of file Frame.h.
References mTwc.
Referenced by MapPointProjection::checkInFrustum(), and MapPointProjection::isInFrustumChecks().
|
inline |
| void Frame::computeStereoFromRGBD | ( | const cv::Mat & | imDepth | ) |
Associates depth-derived right coordinates to keypoints from an RGB-D depthmap.
| [in] | imDepth | The depth image. |
| void Frame::computeStereoMatches | ( | ) |
Searches stereo matches between left and right keypoints.
For each matched keypoint, depth and right coordinate are computed and stored.
Discards outlier map point associations.
| void Frame::eraseMapPointMatch | ( | uint04 | ) |
Removes a map point association at the given index.
| [in] | idx | Keypoint index. |
Extracts ORB features from the image.
| [in] | flag | 0 for left image, 1 for right image. |
| [in] | im | The image to extract from. |
| [in] | x0 | Start column for the lapping area. |
| [in] | x1 | End column for the lapping area. |
|
inline |
Returns the feature index map (word ID to keypoint indices).
Definition at line 539 of file Frame.h.
References m_features_indices.
| void Frame::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.
| [out] | indices | Buffer to fill with matching keypoint indices. |
| [in] | x | Center x coordinate. |
| [in] | y | Center y coordinate. |
| [in] | r | Search radius. |
| [in] | min_level | Minimum pyramid level (default 0). |
| [in] | max_level | Maximum pyramid level (default max). |
| [in] | bRight | True to search in the right view. |
|
virtual |
Returns the IMU position in world coordinates.
Reimplemented in KeyFrame.
|
virtual |
| Sophus::SE3< g_type > Frame::GetRelativePoseTlr | ( | ) | const |
Returns the relative pose from left to right camera.
| Eigen::Matrix3< g_type > Frame::GetRelativePoseTlr_rotation | ( | ) | const |
Returns the rotation component of the left-to-right relative pose.
| Eigen::Vector3< g_type > Frame::GetRelativePoseTlr_translation | ( | ) | const |
Returns the translation component of the left-to-right relative pose.
Referenced by MapPointProjection::isInFrustumChecks().
| Sophus::SE3< g_type > Frame::GetRelativePoseTrl | ( | ) | const |
Returns the relative pose from right to left camera.
Referenced by MapPointProjection::isInFrustumChecks().
|
virtual |
Returns the camera rotation matrix (camera-to-world).
Reimplemented in KeyFrame.
Referenced by MapPointProjection::isInFrustumChecks().
|
virtual |
Returns the camera translation vector (camera-to-world).
Reimplemented in KeyFrame.
| bool Frame::hasCamera | ( | uint01 | index | ) | const |
Checks whether a camera at the given index is available.
| [in] | index | Camera index (0 or 1). |
|
inline |
|
inline |
Checks whether a valid velocity has been set.
Definition at line 421 of file Frame.h.
References mbHasVelocity.
| bool Frame::imuIsPreintegrated | ( | ) | const |
Checks whether the IMU preintegration is complete.
|
virtual |
|
inline |
Returns the shared frame info.
Definition at line 527 of file Frame.h.
References m_frame_info.
Referenced by MapPointProjection::checkInFrustum(), init(), and MapPointProjection::isInFrustumChecks().
| 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() ) |
| Eigen::Vector3< g_type > Frame::inRefCoordinates | ( | Eigen::Vector3< g_type > | pCw | ) | const |
Transforms a world-coordinate point into this frame's camera coordinates.
| [in] | pCw | Point in world coordinates. |
Referenced by MapPointProjection::checkInFrustum().
|
inlinevirtual |
| const Buffer< float > & Frame::invLevelSigma2 | ( | ) | const |
Returns the inverse sigma squared values per pyramid level.
| const Buffer< float > & Frame::invScaleFactors | ( | ) | const |
Returns the inverse ORB scale factors per pyramid level.
|
inline |
Checks whether this frame is a keyframe.
Definition at line 398 of file Frame.h.
References m_is_keyframe.
| bool Frame::isMono | ( | ) | const |
Checks whether this frame is monocular (single camera).
|
inline |
|
inline |
| const cv::KeyPoint & Frame::keypoint | ( | uint04 | i | ) | const |
Returns the keypoint at the given index.
| [in] | i | Keypoint index. |
| const cv::KeyPoint & Frame::keypoint | ( | uint04 | i, |
| bool | is_right ) const |
Returns the keypoint at the given index from left or right view.
| [in] | i | Keypoint index. |
| [in] | is_right | True for right view keypoints. |
| uint04 Frame::levelCount | ( | ) | const |
Returns the number of pyramid levels.
| const Buffer< float > & Frame::levelSigma2 | ( | ) | const |
Returns the sigma squared values per pyramid level.
|
virtual |
|
inline |
Returns the logger for this frame.
Definition at line 446 of file Frame.h.
References m_frame_info.
Returns the map point at the given index (non-const).
| [in] | idx | Keypoint index. |
Returns the map point at the given index.
| [in] | idx | Map point index. |
Definition at line 267 of file Frame.h.
References m_map_points.
|
inline |
Returns the number of map points associated with this frame.
Definition at line 262 of file Frame.h.
References m_map_points.
Returns the map point matches buffer.
Returns all map point associations.
Definition at line 453 of file Frame.h.
References m_map_points.
|
inline |
Returns the read-write lock for map point access.
Definition at line 427 of file Frame.h.
References m_feature_lock.
|
inline |
Returns the near/far depth threshold.
Definition at line 523 of file Frame.h.
References m_frame_info.
Returns the observation count for a map point at the given index.
| [in] | idx | Map point index. |
|
inline |
|
inlinevirtual |
| fltp04 Frame::scaleFactor | ( | ) | const |
Returns the ORB scale factor.
| const Buffer< float > & Frame::scaleFactors | ( | ) | const |
Returns the ORB scale factors per pyramid level.
| 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.
| [in] | Rwb | Rotation from body to world. |
| [in] | twb | Translation from body to world. |
| [in] | Vwb | Velocity in world coordinates. |
|
virtual |
Sets the IMU linear velocity.
| [in] | Vw | Velocity vector in world coordinates. |
Reimplemented in KeyFrame.
Sets a map point association at the given index.
| [in] | idx | Keypoint index. |
| [in] | pMP | Pointer to the map point. |
Sets all map point associations.
| [in] | map_points | Buffer of map point pointers. |
Definition at line 457 of file Frame.h.
References m_map_points.
| void Frame::SetNewBias | ( | const IMU::Bias & | b | ) |
Updates the IMU bias.
| [in] | b | New IMU bias. |
| void Frame::setOutlier | ( | uint04 | idx, |
| bool | outlier ) |
Sets the outlier flag at the given index.
| [in] | idx | Keypoint index. |
| [in] | outlier | True to mark as outlier. |
|
inline |
|
virtual |
Sets the camera pose (does not modify IMU pose).
| [in] | Tcw | Camera-to-world transformation. |
Reimplemented in KeyFrame.
| Eigen::Vector3< g_type > Frame::stereo3DPoint | ( | uint04 | idx | ) | const |
Returns the triangulated 3D stereo point at the given index.
| [in] | idx | Keypoint index. |
|
inline |
Returns the camera-to-world translation.
Definition at line 385 of file Frame.h.
References mTcw.
Referenced by MapPointProjection::isInFrustumChecks().
|
inline |
Returns the capture timestamp.
Definition at line 531 of file Frame.h.
References m_timestamp.
| fltp04 Frame::trackDepth | ( | const Eigen::Vector3< g_type > & | global_position | ) | const |
Computes the depth of a 3D point relative to this frame's camera.
| [in] | global_position | The 3D point in world coordinates. |
Counts map points with at least the given number of observations.
| [in] | minObs | Minimum observation count threshold. |
|
inline |
Returns the undistorted keypoint at the given index.
| [in] | idx | Keypoint index. |
Definition at line 345 of file Frame.h.
References m_undistorted_points.
|
inline |
Returns the number of undistorted keypoints.
Definition at line 349 of file Frame.h.
References m_undistorted_points.
|
inline |
Returns all undistorted keypoints.
Definition at line 340 of file Frame.h.
References m_undistorted_points.
| Eigen::Vector3< g_type > Frame::unproject | ( | uint04 | i | ) |
Backprojects a keypoint into 3D world coordinates using stereo/depth info.
| [in] | i | Keypoint index. |