Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes | Static Private Attributes
KeyFrame Class Reference

#include <keyframe.h>

List of all members.

Public Member Functions

void addPoints (pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr &pointcloud, std::vector< int > &map_idx_points)
void addPoints (pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr &pointcloud)
void convertDescriptors ()
 Method to get convert keypoints descriptors in the OpenCV format.
void getDescriptors (cv::Mat &descriptors)
int getID ()
 Method to get current KeyFrame ID number.
ucl_drone::Pose3D getPose ()
 Method to get the pose of the drone from which the keypoints were observed.
 KeyFrame ()
 Empty Contructor.
 KeyFrame (ucl_drone::Pose3D &pose)
void matchWithFrame (Frame &frame, std::vector< std::vector< int > > &idx_matching_points, std::vector< cv::Point3f > &keyframe_matching_points, std::vector< cv::Point2f > &frame_matching_points)
int size ()
 Method to get the number of keypoints in the current Keyframe.
 ~KeyFrame ()
 Destructor.

Static Public Member Functions

static KeyFramegetKeyFrame (const int ID)
 Function to get a Keyframe by its ID.
static void resetList ()
 Function to remove all previous KeyFrames taken.

Public Attributes

pcl::PointCloud
< pcl::PointXYZRGBSIFT >::Ptr 
cloud

Private Attributes

cv::Mat descriptors
 descriptors in opencv format
int ID
 Identification number of the keyframe.
cv::FlannBasedMatcher matcher
 object for descriptiors comparison
std::vector< int > points
 indexes of points in the pointcloud (the map)
ucl_drone::Pose3D pose
 pose of the drone from which the keypoints were observed

Static Private Attributes

static std::vector< KeyFrame * > instances_list

Detailed Description

A KeyFrame object stores 3D points seen on a same picture In the future, with triangulation enabled for 3D reconstruction a KeyFrame object will store 3D points seen from some close poses (close to be defined according to the camera observation model) A list of Frames (containing 2D keypoint) will be necessary

Definition at line 40 of file keyframe.h.


Constructor & Destructor Documentation

Empty Contructor.

Definition at line 15 of file keyframe.cpp.

KeyFrame::KeyFrame ( ucl_drone::Pose3D &  pose)

Constructor

Parameters:
[in]posePose of the drone from which the keypoints were observed

Definition at line 19 of file keyframe.cpp.

Destructor.

Definition at line 29 of file keyframe.cpp.


Member Function Documentation

void KeyFrame::addPoints ( pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr &  pointcloud,
std::vector< int > &  map_idx_points 
)

Method to add a list of points to the current Keyframe

Parameters:
[in]pointcloudpoints to add in PCL format [in] map_idx_points indexes of thes points in the map pointcloud

Definition at line 42 of file keyframe.cpp.

void KeyFrame::addPoints ( pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr &  pointcloud)

Method to add a list of points to the current Keyframe

Parameters:
[in]pointcloudpoints to add in PCL format

Definition at line 50 of file keyframe.cpp.

Method to get convert keypoints descriptors in the OpenCV format.

Definition at line 90 of file keyframe.cpp.

void KeyFrame::getDescriptors ( cv::Mat &  descriptors)

Method to get the keypoints descriptors

Parameters:
[out]descriptorsDescriptors in the OpenCV format

Definition at line 81 of file keyframe.cpp.

int KeyFrame::getID ( )

Method to get current KeyFrame ID number.

Definition at line 66 of file keyframe.cpp.

KeyFrame * KeyFrame::getKeyFrame ( const int  ID) [static]

Function to get a Keyframe by its ID.

Definition at line 56 of file keyframe.cpp.

ucl_drone::Pose3D KeyFrame::getPose ( )

Method to get the pose of the drone from which the keypoints were observed.

Definition at line 76 of file keyframe.cpp.

void KeyFrame::matchWithFrame ( Frame frame,
std::vector< std::vector< int > > &  idx_matching_points,
std::vector< cv::Point3f > &  keyframe_matching_points,
std::vector< cv::Point2f > &  frame_matching_points 
)

Method to compare the current KeyFrame to a 2D Frame

Parameters:
[in]frameFrame to compare
[out]idx_matching_pointsVector of pairs of indexes: (i,j) with i the map index, j the frame index
[out]keyframe_matching_pointsVector of matching points (3D) in the Keyframe
[out]frame_matching_pointsVector of matching points (2D) in the Frame

Definition at line 102 of file keyframe.cpp.

void KeyFrame::resetList ( ) [static]

Function to remove all previous KeyFrames taken.

Definition at line 33 of file keyframe.cpp.

int KeyFrame::size ( )

Method to get the number of keypoints in the current Keyframe.

Definition at line 71 of file keyframe.cpp.


Member Data Documentation

pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr KeyFrame::cloud

Definition at line 52 of file keyframe.h.

cv::Mat KeyFrame::descriptors [private]

descriptors in opencv format

Definition at line 49 of file keyframe.h.

int KeyFrame::ID [private]

Identification number of the keyframe.

Definition at line 45 of file keyframe.h.

std::vector< KeyFrame * > KeyFrame::instances_list [static, private]

Definition at line 43 of file keyframe.h.

cv::FlannBasedMatcher KeyFrame::matcher [private]

object for descriptiors comparison

Definition at line 48 of file keyframe.h.

std::vector< int > KeyFrame::points [private]

indexes of points in the pointcloud (the map)

Definition at line 46 of file keyframe.h.

ucl_drone::Pose3D KeyFrame::pose [private]

pose of the drone from which the keypoints were observed

Definition at line 47 of file keyframe.h.


The documentation for this class was generated from the following files:


ucl_drone
Author(s): dronesinma
autogenerated on Sat Jun 8 2019 20:51:53