Public Member Functions | Public Attributes
frame_common::Frame Class Reference

The frame class hold image frames, and features found and matched within those frames. Optional image itself using OpenCV format. Camera params contain intrinsic params. Projection matrix is formed from cam params. More...

#include <frame.h>

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

List of all members.

Public Member Functions

Eigen::Vector3d cam2pix (const Eigen::Vector3d &cam_coord) const
Eigen::Vector3d pix2cam (const Eigen::Vector3d &pix_coord) const
Eigen::Vector3d pix2cam (const cv::KeyPoint &pix_coord, double disp) const
void setCamParams (const CamParams &c)
 Set the camera parameters of the frame.
void setTKpts (Eigen::Vector4d trans, Eigen::Quaterniond rot)
 transform keypoints by a 6DOF transformation of the frame

Public Attributes

CamParams cam
 Camera parameters.
Eigen::Matrix4d cart_to_disp
 Transformation from cartesian to disparity.
pcl::PointCloud< pcl::PointXYZRGB > dense_pointcloud
 Dense pointcloud storage, optional.
Eigen::Matrix4d disp_to_cart
 Transformation from disparity to cartesian.
std::vector< double > disps
 disparities
cv::Mat dtors
 Translated keypoints for initial pose estimate.
int frameId
 Internal ID of the frame.
std::vector< char > goodPts
 whether the points are good or not
cv::Mat img
 Image itself, if needed; can be empty.
cv::Mat imgRight
 Descriptors for the keypoints.
Eigen::Matrix3d iproj
 Camera projection matrix.
std::vector< int > ipts
 index into SBA system points; -1 if not present
bool isStereo
 True if the frame contains a stereo image pair.
std::vector< cv::KeyPoint > kpts
std::vector< int > pl_ipts
 Index into SBA system points; -1 if not present.
std::vector< Eigen::Vector3d,
Eigen::aligned_allocator
< Eigen::Vector3d > > 
pl_kpts
 Keypoints for pointcloud points as u, v, u-d.
std::vector< Eigen::Vector4d,
Eigen::aligned_allocator
< Eigen::Vector4d > > 
pl_normals
 Normals for point-plane matches.
std::vector< Eigen::Vector4d,
Eigen::aligned_allocator
< Eigen::Vector4d > > 
pl_pts
 Points for point-plane matches.
pcl::PointCloud
< pcl::PointXYZRGBNormal > 
pointcloud
 Pointcloud storage.
std::vector< Eigen::Vector4d,
Eigen::aligned_allocator
< Eigen::Vector4d > > 
pts
 3d points, linked to keypoints and SBA points for point-to-point matches.
std::vector< cv::KeyPoint > tkpts
 Keypoints detected in the image.

Detailed Description

The frame class hold image frames, and features found and matched within those frames. Optional image itself using OpenCV format. Camera params contain intrinsic params. Projection matrix is formed from cam params.

Definition at line 83 of file frame.h.


Member Function Documentation

Eigen::Vector3d frame_common::Frame::cam2pix ( const Eigen::Vector3d &  cam_coord) const

Definition at line 93 of file frame.cpp.

Eigen::Vector3d frame_common::Frame::pix2cam ( const Eigen::Vector3d &  pix_coord) const

Definition at line 105 of file frame.cpp.

Eigen::Vector3d frame_common::Frame::pix2cam ( const cv::KeyPoint &  pix_coord,
double  disp 
) const

Set the camera parameters of the frame.

Definition at line 58 of file frame.cpp.

void frame_common::Frame::setTKpts ( Eigen::Vector4d  trans,
Eigen::Quaterniond  rot 
)

transform keypoints by a 6DOF transformation of the frame

Definition at line 116 of file frame.cpp.


Member Data Documentation

Camera parameters.

Definition at line 91 of file frame.h.

Transformation from cartesian to disparity.

Definition at line 102 of file frame.h.

Dense pointcloud storage, optional.

Definition at line 124 of file frame.h.

Transformation from disparity to cartesian.

Definition at line 101 of file frame.h.

std::vector<double> frame_common::Frame::disps

disparities

Definition at line 116 of file frame.h.

Translated keypoints for initial pose estimate.

Definition at line 97 of file frame.h.

Internal ID of the frame.

Definition at line 86 of file frame.h.

std::vector<char> frame_common::Frame::goodPts

whether the points are good or not

Definition at line 115 of file frame.h.

Image itself, if needed; can be empty.

Definition at line 90 of file frame.h.

Descriptors for the keypoints.

Right or disparity image (if stereo pair), can be empty.

Definition at line 100 of file frame.h.

Eigen::Matrix3d frame_common::Frame::iproj

Camera projection matrix.

Definition at line 92 of file frame.h.

std::vector<int> frame_common::Frame::ipts

index into SBA system points; -1 if not present

Definition at line 117 of file frame.h.

True if the frame contains a stereo image pair.

Definition at line 89 of file frame.h.

std::vector<cv::KeyPoint> frame_common::Frame::kpts

Definition at line 95 of file frame.h.

std::vector<int> frame_common::Frame::pl_ipts

Index into SBA system points; -1 if not present.

Definition at line 132 of file frame.h.

std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > frame_common::Frame::pl_kpts

Keypoints for pointcloud points as u, v, u-d.

Definition at line 127 of file frame.h.

std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > frame_common::Frame::pl_normals

Normals for point-plane matches.

Definition at line 131 of file frame.h.

std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > frame_common::Frame::pl_pts

Points for point-plane matches.

Definition at line 129 of file frame.h.

Pointcloud storage.

Definition at line 121 of file frame.h.

std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > frame_common::Frame::pts

3d points, linked to keypoints and SBA points for point-to-point matches.

Definition at line 114 of file frame.h.

std::vector<cv::KeyPoint> frame_common::Frame::tkpts

Keypoints detected in the image.

Definition at line 96 of file frame.h.


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


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