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...
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.
|
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.