Public Member Functions | Public Attributes | Private Member Functions
frame_common::FrameExtended Class Reference

Extended Frame class. More...

#include <frame_extended.h>

Inheritance diagram for frame_common::FrameExtended:
Inheritance graph
[legend]

List of all members.

Public Member Functions

template<typename PointT , typename PointNT >
void estimateNormals (const pcl::PointCloud< PointT > &input, const pcl::PointIndices &indices, pcl::PointCloud< PointNT > &output)
 Estimates point normals and surface flatness measures for point-to-plane matching.
void match (frame_common::FrameExtended &frame, const Eigen::Vector3d &trans, const Eigen::Quaterniond &rot, std::vector< cv::DMatch > &matches)
 Match points with previous frame, given an initial pose estimate of trans and rot.
void setPointcloud (const pcl::PointCloud< pcl::PointXYZRGB > &input_cloud)
 Add a pointcloud to the frame, doing all the necessary pre-processing (downsampling, computing normals, and filering based on curvature).

Public Attributes

pcl::PointCloud
< pcl::PointXYZRGBNormal > 
cloud
 Point Cloud dataset. Contains: XYZ data + NormalXYZ data + Surface flatness (curvature) measure.
pcl::PointIndices indices
 Set of point indices that correspond to the data that we care about in cloud.

Private Member Functions

void getMatchingIndices (PointCloud< PointXYZRGBNormal > &input, PointCloud< PointXYZRGBNormal > &output, std::vector< int > &input_indices, std::vector< int > &output_indices)
Eigen::Vector3d projectPoint (Eigen::Vector4d &point)
void reduceCloud (const PointCloud< PointXYZRGB > &input, PointCloud< PointXYZRGBNormal > &output)

Detailed Description

Extended Frame class.

Definition at line 65 of file frame_extended.h.


Member Function Documentation

template<typename PointT , typename PointNT >
void frame_common::FrameExtended::estimateNormals ( const pcl::PointCloud< PointT > &  input,
const pcl::PointIndices indices,
pcl::PointCloud< PointNT > &  output 
) [inline]

Estimates point normals and surface flatness measures for point-to-plane matching.

Definition at line 75 of file frame_extended.h.

void frame_common::FrameExtended::getMatchingIndices ( PointCloud< PointXYZRGBNormal > &  input,
PointCloud< PointXYZRGBNormal > &  output,
std::vector< int > &  input_indices,
std::vector< int > &  output_indices 
) [inline, private]

Definition at line 226 of file frame_extended.h.

void frame_common::FrameExtended::match ( frame_common::FrameExtended frame,
const Eigen::Vector3d &  trans,
const Eigen::Quaterniond &  rot,
std::vector< cv::DMatch > &  matches 
) [inline]

Match points with previous frame, given an initial pose estimate of trans and rot.

Definition at line 92 of file frame_extended.h.

Eigen::Vector3d frame_common::FrameExtended::projectPoint ( Eigen::Vector4d &  point) [inline, private]

Definition at line 260 of file frame_extended.h.

void frame_common::FrameExtended::reduceCloud ( const PointCloud< PointXYZRGB > &  input,
PointCloud< PointXYZRGBNormal > &  output 
) [inline, private]

Definition at line 179 of file frame_extended.h.

void frame_common::FrameExtended::setPointcloud ( const pcl::PointCloud< pcl::PointXYZRGB > &  input_cloud) [inline]

Add a pointcloud to the frame, doing all the necessary pre-processing (downsampling, computing normals, and filering based on curvature).

Definition at line 149 of file frame_extended.h.


Member Data Documentation

Point Cloud dataset. Contains: XYZ data + NormalXYZ data + Surface flatness (curvature) measure.

Definition at line 69 of file frame_extended.h.

Set of point indices that correspond to the data that we care about in cloud.

Definition at line 71 of file frame_extended.h.


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


frame_common
Author(s): Kurt Konolige
autogenerated on Thu Jan 2 2014 12:12:04