svo
Semi-Direct Visual Odometry
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes
svo::Point Class Reference

A 3D point on the surface of the scene. More...

#include <point.h>

List of all members.

Public Types

enum  PointType { TYPE_DELETED, TYPE_CANDIDATE, TYPE_UNKNOWN, TYPE_GOOD }

Public Member Functions

 Point (const Vector3d &pos)
 Point (const Vector3d &pos, Feature *ftr)
 ~Point ()
void addFrameRef (Feature *ftr)
 Add a reference to a frame.
bool deleteFrameRef (Frame *frame)
 Remove reference to a frame.
void initNormal ()
 Initialize point normal. The inital estimate will point towards the frame.
FeaturefindFrameRef (Frame *frame)
 Check whether mappoint has reference to a frame.
bool getCloseViewObs (const Vector3d &pos, Feature *&obs) const
 Get Frame with similar viewpoint.
size_t nRefs () const
 Get number of observations.
void optimize (const size_t n_iter)
 Optimize point position through minimizing the reprojection error.

Static Public Member Functions

static void jacobian_xyz2uv (const Vector3d &p_in_f, const Matrix3d &R_f_w, Matrix23d &point_jac)
 Jacobian of point projection on unit plane (focal length = 1) in frame (f).

Public Attributes

int id_
 Unique ID of the point.
Vector3d pos_
 3d pos of the point in the world coordinate frame.
Vector3d normal_
 Surface normal at point.
Matrix3d normal_information_
 Inverse covariance matrix of normal estimation.
bool normal_set_
 Flag whether the surface normal was estimated or not.
list< Feature * > obs_
 References to keyframes which observe the point.
size_t n_obs_
 Number of obervations: Keyframes AND successful reprojections in intermediate frames.
g2oPointv_pt_
 Temporary pointer to the point-vertex in g2o during bundle adjustment.
int last_published_ts_
 Timestamp of last publishing.
int last_projected_kf_id_
 Flag for the reprojection: don't reproject a pt twice.
PointType type_
 Quality of the point.
int n_failed_reproj_
 Number of failed reprojections. Used to assess the quality of the point.
int n_succeeded_reproj_
 Number of succeeded reprojections. Used to assess the quality of the point.
int last_structure_optim_
 Timestamp of last point optimization.

Static Public Attributes

static int point_counter_
 Counts the number of created points. Used to set the unique id.

Detailed Description

A 3D point on the surface of the scene.


Member Enumeration Documentation

Enumerator:
TYPE_DELETED 
TYPE_CANDIDATE 
TYPE_UNKNOWN 
TYPE_GOOD 

Constructor & Destructor Documentation

svo::Point::Point ( const Vector3d &  pos)
svo::Point::Point ( const Vector3d &  pos,
Feature ftr 
)

Member Function Documentation

Add a reference to a frame.

bool svo::Point::deleteFrameRef ( Frame frame)

Remove reference to a frame.

Check whether mappoint has reference to a frame.

bool svo::Point::getCloseViewObs ( const Vector3d &  pos,
Feature *&  obs 
) const

Get Frame with similar viewpoint.

Initialize point normal. The inital estimate will point towards the frame.

static void svo::Point::jacobian_xyz2uv ( const Vector3d &  p_in_f,
const Matrix3d &  R_f_w,
Matrix23d point_jac 
) [inline, static]

Jacobian of point projection on unit plane (focal length = 1) in frame (f).

size_t svo::Point::nRefs ( ) const [inline]

Get number of observations.

void svo::Point::optimize ( const size_t  n_iter)

Optimize point position through minimizing the reprojection error.


Member Data Documentation

Unique ID of the point.

Flag for the reprojection: don't reproject a pt twice.

Timestamp of last publishing.

Timestamp of last point optimization.

Number of failed reprojections. Used to assess the quality of the point.

Number of obervations: Keyframes AND successful reprojections in intermediate frames.

Number of succeeded reprojections. Used to assess the quality of the point.

Surface normal at point.

Inverse covariance matrix of normal estimation.

Flag whether the surface normal was estimated or not.

References to keyframes which observe the point.

Counts the number of created points. Used to set the unique id.

Vector3d svo::Point::pos_

3d pos of the point in the world coordinate frame.

Quality of the point.

Temporary pointer to the point-vertex in g2o during bundle adjustment.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines