Image feature used for motion estimation. More...
#include <keypoint.hpp>
Public Member Functions | |
void | copyFrom (const KeypointData &src) |
KeypointData () | |
Public Attributes | |
Eigen::Vector2d | base_uv |
float | disparity |
bool | has_depth |
int | keypoint_index |
KeyPoint | kp |
uint8_t | pyramid_level |
Eigen::Vector2d | rect_base_uv |
int | track_id |
Eigen::Vector3d | xyz |
Eigen::Vector4d | xyzw |
Image feature used for motion estimation.
Corresponds to a KeyPoint object as well as additional information used and stored during the visual odometry estimation process.
Definition at line 49 of file keypoint.hpp.
fovis::KeypointData::KeypointData | ( | ) | [inline] |
Default constructor.
Definition at line 118 of file keypoint.hpp.
void fovis::KeypointData::copyFrom | ( | const KeypointData & | src | ) | [inline] |
populates this keypoint to be identical to the src
keypoint.
Definition at line 134 of file keypoint.hpp.
Eigen::Vector2d fovis::KeypointData::base_uv |
Keypoint pixel coordinates in the base pyramid level
Definition at line 80 of file keypoint.hpp.
Pixel disparity, if applicable. If not applicable (e.g., the depth source is not a stereo camera), this value is NAN
Note that the meaning of this value depends on the DepthSource used to compute it. For StereoDepth, this corresponds directly to stereo disparity. For PrimeSenseDepth, this corresponds to the "disparity" values reported by the PrimeSense sensor, which are not the same as stereo disparity. See the PrimeSenseDepth class documentation for more details.
Definition at line 98 of file keypoint.hpp.
Indicates whether or not depth data is available for this keypoint.
Definition at line 68 of file keypoint.hpp.
Not used.
Definition at line 108 of file keypoint.hpp.
Pixel coordinates of keypoint in its pyramid level
Definition at line 58 of file keypoint.hpp.
Which pyramid level was this feature computed on
Definition at line 103 of file keypoint.hpp.
Eigen::Vector2d fovis::KeypointData::rect_base_uv |
rectified keypoint pixel coordinates in the base pyramid level
Definition at line 85 of file keypoint.hpp.
to identify unique feature track externally
Definition at line 113 of file keypoint.hpp.
Eigen::Vector3d fovis::KeypointData::xyz |
Inhomogeneous coordinates of the feature in the camera frame. Convenience variable, computed from xyzw. These coordinates may be infinite.
Definition at line 75 of file keypoint.hpp.
Eigen::Vector4d fovis::KeypointData::xyzw |
Homogeneous coordinates of the feature in the camera frame
Definition at line 63 of file keypoint.hpp.