frame_common::PointcloudProc Class Reference
#include <frame.h>
List of all members.
Public Member Functions |
void | match (const Frame &frame0, const Frame &frame1, const Eigen::Vector3d &trans, const Eigen::Quaterniond &rot, std::vector< cv::DMatch > &matches) const |
| Match points with previous frame, given an initial pose estimate.
|
void | setPointcloud (Frame &frame, const pcl::PointCloud< pcl::PointXYZRGB > &input_cloud) const |
| Add a pointcloud to the frame, doing all the necessary pre-processing (downsampling, computing normals, and filering based on curvature).
|
Private Member Functions |
void | getMatchingIndices (const pcl::PointCloud< pcl::PointXYZRGBNormal > &input, const pcl::PointCloud< pcl::PointXYZRGBNormal > &output, std::vector< int > &input_indices, std::vector< int > &output_indices) const |
| Find matches between two pointclouds using nearest neighbor KDtree search.
|
Eigen::Vector3d | projectPoint (Eigen::Vector4d &point, CamParams cam) const |
| Project a 3D point into the image frame.
|
void | reduceCloud (const pcl::PointCloud< pcl::PointXYZRGB > &input, pcl::PointCloud< pcl::PointXYZRGBNormal > &output) const |
| Subsample cloud for faster matching and processing, while filling in normals.
|
Detailed Description
Definition at line 190 of file frame.h.
Member Function Documentation
void frame_common::PointcloudProc::getMatchingIndices |
( |
const pcl::PointCloud< pcl::PointXYZRGBNormal > & |
input, |
|
|
const pcl::PointCloud< pcl::PointXYZRGBNormal > & |
output, |
|
|
std::vector< int > & |
input_indices, |
|
|
std::vector< int > & |
output_indices | |
|
) |
| | const [private] |
Find matches between two pointclouds using nearest neighbor KDtree search.
void frame_common::PointcloudProc::match |
( |
const Frame & |
frame0, |
|
|
const Frame & |
frame1, |
|
|
const Eigen::Vector3d & |
trans, |
|
|
const Eigen::Quaterniond & |
rot, |
|
|
std::vector< cv::DMatch > & |
matches | |
|
) |
| | const |
Match points with previous frame, given an initial pose estimate.
Definition at line 336 of file frame.cpp.
Eigen::Vector3d frame_common::PointcloudProc::projectPoint |
( |
Eigen::Vector4d & |
point, |
|
|
CamParams |
cam | |
|
) |
| | const [private] |
Project a 3D point into the image frame.
Definition at line 490 of file frame.cpp.
void frame_common::PointcloudProc::reduceCloud |
( |
const pcl::PointCloud< pcl::PointXYZRGB > & |
input, |
|
|
pcl::PointCloud< pcl::PointXYZRGBNormal > & |
output | |
|
) |
| | const [private] |
Subsample cloud for faster matching and processing, while filling in normals.
void frame_common::PointcloudProc::setPointcloud |
( |
Frame & |
frame, |
|
|
const pcl::PointCloud< pcl::PointXYZRGB > & |
input_cloud | |
|
) |
| | const |
Add a pointcloud to the frame, doing all the necessary pre-processing (downsampling, computing normals, and filering based on curvature).
Definition at line 306 of file frame.cpp.
The documentation for this class was generated from the following files: