#include <frame.h>
Public Member Functions | |
void | convertToPcl (std::vector< int > &idx_points, std::vector< cv::Point3f > points_out, int keyframe_id, pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr &pointcloud) |
void | convertToPcl (std::vector< cv::Point3f > points_out, int keyframe_id, pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr &pointcloud) |
Frame () | |
Contructor for an empty object. | |
Frame (ucl_drone::ProcessedImageMsg::ConstPtr msg) | |
Contructor: msg is used for the initialization. | |
~Frame () | |
Destructor. | |
Public Attributes | |
cv::Mat | descriptors |
descriptors of keypoints in OpenCV format | |
std::vector< cv::Point2f > | imgPoints |
3D coordinates of keypoints in OpenCV format | |
ucl_drone::ProcessedImageMsg | msg |
ProcessedImage Message. | |
ucl_drone::Pose3D | pose_visual_msg |
visual pose estimated (not used in this implementation) |
A Frame object stores ImageProcessed message and posseses facilities to convert 2D points in OpenCV format. There are also facilities to convert 3D points to PCL format. In the future Frame objects can also be useful for Bundle Adjustment
Frame::Frame | ( | ) |
Frame::Frame | ( | ucl_drone::ProcessedImageMsg::ConstPtr | msg | ) |
Frame::~Frame | ( | ) |
void Frame::convertToPcl | ( | std::vector< int > & | idx_points, |
std::vector< cv::Point3f > | points_out, | ||
int | keyframe_id, | ||
pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr & | pointcloud | ||
) |
This function converts points to the PCL format
[in] | idx_points,: | indexes (in this->imgPoints) of points to be converted |
[in] | points_out,: | 3D points in the OpenCV format to be converted in PCL |
[in] | keyframe_id,: | used to fill in the field which correponds in XYZRGBSIFTPoint |
[out] | pointcloud,: | result of the conversion to PCL format |
void Frame::convertToPcl | ( | std::vector< cv::Point3f > | points_out, |
int | keyframe_id, | ||
pcl::PointCloud< pcl::PointXYZRGBSIFT >::Ptr & | pointcloud | ||
) |
This function converts all points to the PCL format
[in] | points_out,: | points to be converted in the OpenCV format |
[in] | keyframe_id,: | used to fill in the field which correponds in XYZRGBSIFTPoint |
[out] | pointcloud,: | result of the conversion to PCL format |
cv::Mat Frame::descriptors |
std::vector< cv::Point2f > Frame::imgPoints |
ucl_drone::ProcessedImageMsg Frame::msg |
ProcessedImage Message.
ucl_drone::Pose3D Frame::pose_visual_msg |