Public Member Functions | Private Member Functions | Private Attributes
fovis::Rectification Class Reference

Maps image coordinates from an input image to image coordinates on a rectified camera. More...

#include <rectification.hpp>

List of all members.

Public Member Functions

const CameraIntrinsicsParametersgetInputCameraParameters () const
const Eigen::Matrix3d & getRectificationRotation () const
const CameraIntrinsicsParametersgetRectifiedCameraParameters () const
RectificationmakeCopy () const
 Rectification (const CameraIntrinsicsParameters &input_camera_params)
 Rectification (const CameraIntrinsicsParameters &input_camera_params, const Eigen::Matrix3d &rotation, const CameraIntrinsicsParameters &rectified_camera_params)
void rectifyBilinearLookup (const Eigen::Vector2d &dist_uv, Eigen::Vector2d *rect_uv) const
void rectifyLookup (int dist_u, int dist_v, Eigen::Vector2d *rect_uv) const
void rectifyLookupByIndex (int pixel_index, Eigen::Vector2d *rect_uv) const
 ~Rectification ()

Private Member Functions

void populateMap ()
 Rectification ()

Private Attributes

CameraIntrinsicsParameters _input_camera
float * _map_x
float * _map_y
CameraIntrinsicsParameters _rectified_camera
Eigen::Matrix3d * _rotation

Detailed Description

Maps image coordinates from an input image to image coordinates on a rectified camera.

A Rectification object represents the computation required to map pixels from an input camera to pixels on a "rectified" virtual camera that shares the same focal point, but may be rotated and have different projection parameters (e.g., focal length, center of projection, etc.)

This class is primary useful with stereo cameras to rectify pixels on both input cameras to rectified cameras that share an image plane and look/up vectors. It can also be used for simple undistortion (e.g., no rotation, and a rectified camera that has the same projection parameters as the input camera, but with no distortion).

For fast rectification, the Rectification object precomputes a mapping from (u, v) image pixel coordinates to u', v' rectified image pixel coordinates. The exact transformation from (u, v) to (u', v') is:

  1. undistort according to a plumb-bob distortion model
  2. rotate points about the origin
  3. reproject onto a rectified image plane.

Rectification of pixels is done by bilinear interpolation on this precomputed mapping.

Definition at line 41 of file rectification.hpp.


Constructor & Destructor Documentation

Convenience constructor to create a Rectification object that simply undistorts. The rotation is set to identity, and the rectified camera parameters are identical to the input camera parameters, but have no distortion.

Definition at line 11 of file rectification.cpp.

fovis::Rectification::Rectification ( const CameraIntrinsicsParameters input_camera_params,
const Eigen::Matrix3d &  rotation,
const CameraIntrinsicsParameters rectified_camera_params 
)

Constructor. The rectified_camera_params are not allowed to have any distortion.

Definition at line 26 of file rectification.cpp.

Definition at line 93 of file rectification.cpp.

fovis::Rectification::Rectification ( ) [inline, private]

Definition at line 167 of file rectification.hpp.


Member Function Documentation

Returns:
the intrisic parameters of the input camera.

Definition at line 66 of file rectification.hpp.

const Eigen::Matrix3d& fovis::Rectification::getRectificationRotation ( ) const [inline]
Returns:
the rotation to apply between the undistorted input camera frame and the output rectified camera frame.

Definition at line 74 of file rectification.hpp.

Returns:
the projection parameters of the rectified camera. The distortion coefficients will always be zero. Note that the focal length and image dimensions of the rectified camera do not have to match those of the input camera.

Definition at line 84 of file rectification.hpp.

Returns:
a deep copy of this object.

Definition at line 103 of file rectification.cpp.

Definition at line 39 of file rectification.cpp.

void fovis::Rectification::rectifyBilinearLookup ( const Eigen::Vector2d &  dist_uv,
Eigen::Vector2d *  rect_uv 
) const [inline]

Computes the undistorted image coordinates of an input pixel via bilinear interpolation of its integer-coordinate 4-neighboors.

Parameters:
dist_uvinput distorted pixel coordinates.
rect_uvoutput parameter.

Definition at line 128 of file rectification.hpp.

void fovis::Rectification::rectifyLookup ( int  dist_u,
int  dist_v,
Eigen::Vector2d *  rect_uv 
) const [inline]

Computes the undistorted image coordinates of the input distorted coordinates (dist_u, dist_v).

Parameters:
dist_uinput distorted pixel u/x coordinate.
dist_vinput distorted pixel v/y coordinate.
rect_uvoutput parameter.

Definition at line 96 of file rectification.hpp.

void fovis::Rectification::rectifyLookupByIndex ( int  pixel_index,
Eigen::Vector2d *  rect_uv 
) const [inline]

Computes the undistorted image coordinates of an input pixel specified by its row-major pixel index.

Parameters:
pixel_indexcorresponds to $ u * width + v $
rect_uvoutput parameter.
See also:
rectifyLookup

Definition at line 114 of file rectification.hpp.


Member Data Documentation

Definition at line 171 of file rectification.hpp.

float* fovis::Rectification::_map_x [private]

Definition at line 178 of file rectification.hpp.

float* fovis::Rectification::_map_y [private]

Definition at line 179 of file rectification.hpp.

Definition at line 176 of file rectification.hpp.

Eigen::Matrix3d* fovis::Rectification::_rotation [private]

Definition at line 173 of file rectification.hpp.


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


libfovis
Author(s): Albert Huang, Maurice Fallon
autogenerated on Thu Jun 6 2019 20:16:12