| svo
   
    Semi-Direct Visual Odometry | 
A frame saves the image, the associated features and the estimated pose. More...
#include <frame.h>
| Public Member Functions | |
| Frame (vk::AbstractCamera *cam, const cv::Mat &img, double timestamp) | |
| ~Frame () | |
| void | initFrame (const cv::Mat &img) | 
| Initialize new frame and create image pyramid. | |
| void | setKeyframe () | 
| Select this frame as keyframe. | |
| void | addFeature (Feature *ftr) | 
| Add a feature to the image. | |
| void | setKeyPoints () | 
| The KeyPoints are those five features which are closest to the 4 image corners and to the center and which have a 3D point assigned. | |
| void | checkKeyPoints (Feature *ftr) | 
| Check if we can select five better key-points. | |
| void | removeKeyPoint (Feature *ftr) | 
| If a point is deleted, we must remove the corresponding key-point. | |
| size_t | nObs () const | 
| Return number of point observations. | |
| bool | isVisible (const Vector3d &xyz_w) const | 
| Check if a point in (w)orld coordinate frame is visible in the image. | |
| const cv::Mat & | img () const | 
| Full resolution image stored in the frame. | |
| bool | isKeyframe () const | 
| Was this frame selected as keyframe? | |
| Vector2d | w2c (const Vector3d &xyz_w) const | 
| Transforms point coordinates in world-frame (w) to camera pixel coordinates (c). | |
| Vector3d | c2f (const Vector2d &px) const | 
| Transforms pixel coordinates (c) to frame unit sphere coordinates (f). | |
| Vector3d | c2f (const double x, const double y) const | 
| Transforms pixel coordinates (c) to frame unit sphere coordinates (f). | |
| Vector3d | w2f (const Vector3d &xyz_w) const | 
| Transforms point coordinates in world-frame (w) to camera-frams (f). | |
| Vector3d | f2w (const Vector3d &f) const | 
| Transforms point from frame unit sphere (f) frame to world coordinate frame (w). | |
| Vector2d | f2c (const Vector3d &f) const | 
| Projects Point from unit sphere (f) in camera pixels (c). | |
| Vector3d | pos () const | 
| Return the pose of the frame in the (w)orld coordinate frame. | |
| Static Public Member Functions | |
| static void | jacobian_xyz2uv (const Vector3d &xyz_in_f, Matrix< double, 2, 6 > &J) | 
| Frame jacobian for projection of 3D point in (f)rame coordinate to unit plane coordinates uv (focal length = 1). | |
| Public Attributes | |
| int | id_ | 
| Unique id of the frame. | |
| double | timestamp_ | 
| Timestamp of when the image was recorded. | |
| vk::AbstractCamera * | cam_ | 
| Camera model. | |
| Sophus::SE3 | T_f_w_ | 
| Transform (f)rame from (w)orld. | |
| Matrix< double, 6, 6 > | Cov_ | 
| Covariance. | |
| ImgPyr | img_pyr_ | 
| Image Pyramid. | |
| Features | fts_ | 
| List of features in the image. | |
| vector< Feature * > | key_pts_ | 
| Five features and associated 3D points which are used to detect if two frames have overlapping field of view. | |
| bool | is_keyframe_ | 
| Was this frames selected as keyframe? | |
| g2oFrameSE3 * | v_kf_ | 
| Temporary pointer to the g2o node object of the keyframe. | |
| int | last_published_ts_ | 
| Timestamp of last publishing. | |
| Static Public Attributes | |
| static EIGEN_MAKE_ALIGNED_OPERATOR_NEW int | frame_counter_ | 
| Counts the number of created frames. Used to set the unique id. | |
A frame saves the image, the associated features and the estimated pose.
| svo::Frame::Frame | ( | vk::AbstractCamera * | cam, | 
| const cv::Mat & | img, | ||
| double | timestamp | ||
| ) | 
| void svo::Frame::addFeature | ( | Feature * | ftr | ) | 
Add a feature to the image.
| Vector3d svo::Frame::c2f | ( | const Vector2d & | px | ) | const  [inline] | 
Transforms pixel coordinates (c) to frame unit sphere coordinates (f).
| Vector3d svo::Frame::c2f | ( | const double | x, | 
| const double | y | ||
| ) | const  [inline] | 
Transforms pixel coordinates (c) to frame unit sphere coordinates (f).
| void svo::Frame::checkKeyPoints | ( | Feature * | ftr | ) | 
Check if we can select five better key-points.
| Vector2d svo::Frame::f2c | ( | const Vector3d & | f | ) | const  [inline] | 
Projects Point from unit sphere (f) in camera pixels (c).
| Vector3d svo::Frame::f2w | ( | const Vector3d & | f | ) | const  [inline] | 
Transforms point from frame unit sphere (f) frame to world coordinate frame (w).
| const cv::Mat& svo::Frame::img | ( | ) | const  [inline] | 
Full resolution image stored in the frame.
| void svo::Frame::initFrame | ( | const cv::Mat & | img | ) | 
Initialize new frame and create image pyramid.
| bool svo::Frame::isKeyframe | ( | ) | const  [inline] | 
Was this frame selected as keyframe?
| bool svo::Frame::isVisible | ( | const Vector3d & | xyz_w | ) | const | 
Check if a point in (w)orld coordinate frame is visible in the image.
| static void svo::Frame::jacobian_xyz2uv | ( | const Vector3d & | xyz_in_f, | 
| Matrix< double, 2, 6 > & | J | ||
| ) |  [inline, static] | 
Frame jacobian for projection of 3D point in (f)rame coordinate to unit plane coordinates uv (focal length = 1).
| size_t svo::Frame::nObs | ( | ) | const  [inline] | 
Return number of point observations.
| Vector3d svo::Frame::pos | ( | ) | const  [inline] | 
Return the pose of the frame in the (w)orld coordinate frame.
| void svo::Frame::removeKeyPoint | ( | Feature * | ftr | ) | 
If a point is deleted, we must remove the corresponding key-point.
| void svo::Frame::setKeyframe | ( | ) | 
Select this frame as keyframe.
| void svo::Frame::setKeyPoints | ( | ) | 
The KeyPoints are those five features which are closest to the 4 image corners and to the center and which have a 3D point assigned.
These points are used to quickly check whether two frames have overlapping field of view.
| Vector2d svo::Frame::w2c | ( | const Vector3d & | xyz_w | ) | const  [inline] | 
Transforms point coordinates in world-frame (w) to camera pixel coordinates (c).
| Vector3d svo::Frame::w2f | ( | const Vector3d & | xyz_w | ) | const  [inline] | 
Transforms point coordinates in world-frame (w) to camera-frams (f).
| vk::AbstractCamera* svo::Frame::cam_ | 
Camera model.
| Matrix<double, 6, 6> svo::Frame::Cov_ | 
Covariance.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW int svo::Frame::frame_counter_  [static] | 
Counts the number of created frames. Used to set the unique id.
List of features in the image.
| int svo::Frame::id_ | 
Unique id of the frame.
Image Pyramid.
Was this frames selected as keyframe?
| vector<Feature*> svo::Frame::key_pts_ | 
Five features and associated 3D points which are used to detect if two frames have overlapping field of view.
Timestamp of last publishing.
| Sophus::SE3 svo::Frame::T_f_w_ | 
Transform (f)rame from (w)orld.
| double svo::Frame::timestamp_ | 
Timestamp of when the image was recorded.
Temporary pointer to the g2o node object of the keyframe.
 1.7.6.1
 1.7.6.1