libfovis
|
Image feature used for motion estimation. More...
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.
|
inline |
Default constructor.
|
inline |
populates this keypoint to be identical to the src
keypoint.
KeyPoint kp |
Pixel coordinates of keypoint in its pyramid level
Eigen::Vector4d xyzw |
Homogeneous coordinates of the feature in the camera frame
bool has_depth |
Indicates whether or not depth data is available for this keypoint.
Eigen::Vector3d xyz |
Inhomogeneous coordinates of the feature in the camera frame. Convenience variable, computed from xyzw. These coordinates may be infinite.
Eigen::Vector2d base_uv |
Keypoint pixel coordinates in the base pyramid level
Eigen::Vector2d rect_base_uv |
rectified keypoint pixel coordinates in the base pyramid level
float disparity |
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.
uint8_t pyramid_level |
Which pyramid level was this feature computed on
int keypoint_index |
Not used.
int track_id |
to identify unique feature track externally