image_geometry::PinholeCameraModel Class Reference

Simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo. More...

#include <pinhole_camera_model.h>

List of all members.

Classes

struct  Cache

Public Member Functions

uint32_t binningX () const
 Returns the number of columns in each bin.
uint32_t binningY () const
 Returns the number of rows in each bin.
double cx () const
 Returns the x coordinate of the optical center.
double cy () const
 Returns the y coordinate of the optical center.
const cv::Mat_< double > & distortionCoeffs () const
 Returns the distortion coefficients.
bool fromCameraInfo (const sensor_msgs::CameraInfoConstPtr &msg)
 Set the camera parameters from the sensor_msgs/CameraInfo message.
bool fromCameraInfo (const sensor_msgs::CameraInfo &msg)
 Set the camera parameters from the sensor_msgs/CameraInfo message.
const cv::Mat_< double > & fullIntrinsicMatrix () const
 Returns the original camera matrix for full resolution.
const cv::Mat_< double > & fullProjectionMatrix () const
 Returns the projection matrix for full resolution.
cv::Size fullResolution () const
 The resolution at which the camera was calibrated.
double fx () const
 Returns the focal length (pixels) in x direction of the rectified image.
double fy () const
 Returns the focal length (pixels) in y direction of the rectified image.
double getDeltaU (double deltaX, double Z) const
 Compute delta u, given Z and delta X in Cartesian space.
double getDeltaV (double deltaY, double Z) const
 Compute delta v, given Z and delta Y in Cartesian space.
double getDeltaX (double deltaU, double Z) const
 Compute delta X, given Z in Cartesian space and delta u in pixels.
double getDeltaY (double deltaV, double Z) const
 Compute delta Y, given Z in Cartesian space and delta v in pixels.
uint32_t height () const ROS_DEPRECATED
 Returns the image height.
const cv::Mat_< double > & intrinsicMatrix () const
 Returns the original camera matrix.
 PinholeCameraModel (const PinholeCameraModel &other)
 PinholeCameraModel ()
cv::Point2d project3dToPixel (const cv::Point3d &xyz) const
 Project a 3d point to rectified pixel coordinates.
void project3dToPixel (const cv::Point3d &xyz, cv::Point2d &uv_rect) const ROS_DEPRECATED
const cv::Mat_< double > & projectionMatrix () const
 Returns the projection matrix.
cv::Point3d projectPixelTo3dRay (const cv::Point2d &uv_rect) const
 Project a rectified pixel to a 3d ray.
void projectPixelTo3dRay (const cv::Point2d &uv_rect, cv::Point3d &ray) const ROS_DEPRECATED
cv::Rect rawRoi () const
 The current raw ROI, as used for capture by the camera driver.
cv::Rect rectifiedRoi () const
 The current rectified ROI, which best fits the raw ROI.
void rectifyImage (const cv::Mat &raw, cv::Mat &rectified, int interpolation=CV_INTER_LINEAR) const
 Rectify a raw camera image.
cv::Point2d rectifyPoint (const cv::Point2d &uv_raw) const
 Compute the rectified image coordinates of a pixel in the raw image.
void rectifyPoint (const cv::Point2d &uv_raw, cv::Point2d &uv_rect) const ROS_DEPRECATED
cv::Rect rectifyRoi (const cv::Rect &roi_raw) const
 Compute the rectified ROI best fitting a raw ROI.
cv::Size reducedResolution () const
 The resolution of the current rectified image.
const cv::Mat_< double > & rotationMatrix () const
 Returns the rotation matrix.
ros::Time stamp () const
 Get the time stamp associated with this camera model.
std::string tfFrame () const
 Get the name of the camera coordinate frame in tf.
cv::Rect toFullResolution (const cv::Rect &roi_reduced) const
cv::Point2d toFullResolution (const cv::Point2d &uv_reduced) const
cv::Rect toReducedResolution (const cv::Rect &roi_full) const
cv::Point2d toReducedResolution (const cv::Point2d &uv_full) const
double Tx () const
 Returns the x-translation term of the projection matrix.
double Ty () const
 Returns the y-translation term of the projection matrix.
void unrectifyImage (const cv::Mat &rectified, cv::Mat &raw, int interpolation=CV_INTER_LINEAR) const
 Apply camera distortion to a rectified image.
cv::Point2d unrectifyPoint (const cv::Point2d &uv_rect) const
 Compute the raw image coordinates of a pixel in the rectified image.
void unrectifyPoint (const cv::Point2d &uv_rect, cv::Point2d &uv_raw) const ROS_DEPRECATED
cv::Rect unrectifyRoi (const cv::Rect &roi_rect) const
 Compute the raw ROI best fitting a rectified ROI.
uint32_t width () const ROS_DEPRECATED
 Returns the image width.

Protected Member Functions

bool initialized () const
void initRectificationMaps () const

Protected Attributes

boost::shared_ptr< Cachecache_
sensor_msgs::CameraInfo cam_info_
cv::Mat_< double > D_
cv::Mat_< double > K_
cv::Mat_< double > K_full_
cv::Mat_< double > P_
cv::Mat_< double > P_full_
cv::Mat_< double > R_

Friends

class StereoCameraModel

Detailed Description

Simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo.

Definition at line 18 of file pinhole_camera_model.h.


Constructor & Destructor Documentation

image_geometry::PinholeCameraModel::PinholeCameraModel (  ) 

Definition at line 30 of file pinhole_camera_model.cpp.

image_geometry::PinholeCameraModel::PinholeCameraModel ( const PinholeCameraModel other  ) 

Definition at line 34 of file pinhole_camera_model.cpp.


Member Function Documentation

uint32_t image_geometry::PinholeCameraModel::binningX (  )  const [inline]

Returns the number of columns in each bin.

Definition at line 312 of file pinhole_camera_model.h.

uint32_t image_geometry::PinholeCameraModel::binningY (  )  const [inline]

Returns the number of rows in each bin.

Definition at line 313 of file pinhole_camera_model.h.

double image_geometry::PinholeCameraModel::cx (  )  const [inline]

Returns the x coordinate of the optical center.

Definition at line 305 of file pinhole_camera_model.h.

double image_geometry::PinholeCameraModel::cy (  )  const [inline]

Returns the y coordinate of the optical center.

Definition at line 306 of file pinhole_camera_model.h.

const cv::Mat_< double > & image_geometry::PinholeCameraModel::distortionCoeffs (  )  const [inline]

Returns the distortion coefficients.

Definition at line 297 of file pinhole_camera_model.h.

bool image_geometry::PinholeCameraModel::fromCameraInfo ( const sensor_msgs::CameraInfoConstPtr &  msg  ) 

Set the camera parameters from the sensor_msgs/CameraInfo message.

Definition at line 159 of file pinhole_camera_model.cpp.

bool image_geometry::PinholeCameraModel::fromCameraInfo ( const sensor_msgs::CameraInfo &  msg  ) 

Set the camera parameters from the sensor_msgs/CameraInfo message.

Todo:
Calculate and use rectified ROI
Todo:
Adjust P by rectified ROI instead

Definition at line 62 of file pinhole_camera_model.cpp.

const cv::Mat_< double > & image_geometry::PinholeCameraModel::fullIntrinsicMatrix (  )  const [inline]

Returns the original camera matrix for full resolution.

Definition at line 300 of file pinhole_camera_model.h.

const cv::Mat_< double > & image_geometry::PinholeCameraModel::fullProjectionMatrix (  )  const [inline]

Returns the projection matrix for full resolution.

Definition at line 301 of file pinhole_camera_model.h.

cv::Size image_geometry::PinholeCameraModel::fullResolution (  )  const

The resolution at which the camera was calibrated.

The maximum resolution at which the camera can be used with the current calibration; normally this is the same as the imager resolution.

Definition at line 169 of file pinhole_camera_model.cpp.

double image_geometry::PinholeCameraModel::fx (  )  const [inline]

Returns the focal length (pixels) in x direction of the rectified image.

Definition at line 303 of file pinhole_camera_model.h.

double image_geometry::PinholeCameraModel::fy (  )  const [inline]

Returns the focal length (pixels) in y direction of the rectified image.

Definition at line 304 of file pinhole_camera_model.h.

double image_geometry::PinholeCameraModel::getDeltaU ( double  deltaX,
double  Z 
) const [inline]

Compute delta u, given Z and delta X in Cartesian space.

For given Z, this is the inverse of getDeltaX().

Parameters:
deltaX Delta X, in Cartesian space
Z Z (depth), in Cartesian space

Definition at line 315 of file pinhole_camera_model.h.

double image_geometry::PinholeCameraModel::getDeltaV ( double  deltaY,
double  Z 
) const [inline]

Compute delta v, given Z and delta Y in Cartesian space.

For given Z, this is the inverse of getDeltaY().

Parameters:
deltaY Delta Y, in Cartesian space
Z Z (depth), in Cartesian space

Definition at line 321 of file pinhole_camera_model.h.

double image_geometry::PinholeCameraModel::getDeltaX ( double  deltaU,
double  Z 
) const [inline]

Compute delta X, given Z in Cartesian space and delta u in pixels.

For given Z, this is the inverse of getDeltaU().

Parameters:
deltaU Delta u, in pixels
Z Z (depth), in Cartesian space

Definition at line 327 of file pinhole_camera_model.h.

double image_geometry::PinholeCameraModel::getDeltaY ( double  deltaV,
double  Z 
) const [inline]

Compute delta Y, given Z in Cartesian space and delta v in pixels.

For given Z, this is the inverse of getDeltaV().

Parameters:
deltaV Delta v, in pixels
Z Z (depth), in Cartesian space

Definition at line 333 of file pinhole_camera_model.h.

uint32_t image_geometry::PinholeCameraModel::height (  )  const [inline]

Returns the image height.

Definition at line 309 of file pinhole_camera_model.h.

bool image_geometry::PinholeCameraModel::initialized (  )  const [inline, protected]

Definition at line 277 of file pinhole_camera_model.h.

void image_geometry::PinholeCameraModel::initRectificationMaps (  )  const [protected]

Todo:
For large binning settings, can drop extra rows/cols at bottom/right boundary. Make sure we're handling that 100% correctly.
Todo:
Should binned resolution, K, P be part of public API?
Todo:
Use rectified ROI

Definition at line 417 of file pinhole_camera_model.cpp.

const cv::Mat_< double > & image_geometry::PinholeCameraModel::intrinsicMatrix (  )  const [inline]

Returns the original camera matrix.

Definition at line 296 of file pinhole_camera_model.h.

cv::Point2d image_geometry::PinholeCameraModel::project3dToPixel ( const cv::Point3d &  xyz  )  const

Project a 3d point to rectified pixel coordinates.

This is the inverse of projectPixelTo3dRay().

Parameters:
xyz 3d point in the camera coordinate frame
Returns:
(u,v) in rectified pixel coordinates

Definition at line 238 of file pinhole_camera_model.cpp.

void image_geometry::PinholeCameraModel::project3dToPixel ( const cv::Point3d &  xyz,
cv::Point2d &  uv_rect 
) const
Todo:
Hide or group deprecated overloads in Doxygen

Definition at line 164 of file pinhole_camera_model.cpp.

const cv::Mat_< double > & image_geometry::PinholeCameraModel::projectionMatrix (  )  const [inline]

Returns the projection matrix.

Definition at line 299 of file pinhole_camera_model.h.

cv::Point3d image_geometry::PinholeCameraModel::projectPixelTo3dRay ( const cv::Point2d &  uv_rect  )  const

Project a rectified pixel to a 3d ray.

Returns the unit vector in the camera coordinate frame in the direction of rectified pixel (u,v) in the image plane. This is the inverse of project3dToPixel().

In 1.4.x, the vector has z = 1.0. Previously, this function returned a unit vector.

Parameters:
uv_rect Rectified pixel coordinates
Returns:
3d ray passing through (u,v)

Definition at line 257 of file pinhole_camera_model.cpp.

void image_geometry::PinholeCameraModel::projectPixelTo3dRay ( const cv::Point2d &  uv_rect,
cv::Point3d &  ray 
) const

Definition at line 252 of file pinhole_camera_model.cpp.

cv::Rect image_geometry::PinholeCameraModel::rawRoi (  )  const

The current raw ROI, as used for capture by the camera driver.

Definition at line 215 of file pinhole_camera_model.cpp.

cv::Rect image_geometry::PinholeCameraModel::rectifiedRoi (  )  const

The current rectified ROI, which best fits the raw ROI.

Definition at line 223 of file pinhole_camera_model.cpp.

void image_geometry::PinholeCameraModel::rectifyImage ( const cv::Mat &  raw,
cv::Mat &  rectified,
int  interpolation = CV_INTER_LINEAR 
) const

Rectify a raw camera image.

Definition at line 268 of file pinhole_camera_model.cpp.

cv::Point2d image_geometry::PinholeCameraModel::rectifyPoint ( const cv::Point2d &  uv_raw  )  const

Compute the rectified image coordinates of a pixel in the raw image.

Todo:
cv::undistortPoints requires the point data to be float, should allow double

Definition at line 305 of file pinhole_camera_model.cpp.

void image_geometry::PinholeCameraModel::rectifyPoint ( const cv::Point2d &  uv_raw,
cv::Point2d &  uv_rect 
) const

Definition at line 300 of file pinhole_camera_model.cpp.

cv::Rect image_geometry::PinholeCameraModel::rectifyRoi ( const cv::Rect &  roi_raw  )  const

Compute the rectified ROI best fitting a raw ROI.

Todo:
Actually implement "best fit" as described by REP 104.

Definition at line 375 of file pinhole_camera_model.cpp.

cv::Size image_geometry::PinholeCameraModel::reducedResolution (  )  const

The resolution of the current rectified image.

The size of the rectified image associated with the latest CameraInfo, as reduced by binning/ROI and affected by distortion. If binning and ROI are not in use, this is the same as fullResolution().

Definition at line 175 of file pinhole_camera_model.cpp.

const cv::Mat_< double > & image_geometry::PinholeCameraModel::rotationMatrix (  )  const [inline]

Returns the rotation matrix.

Definition at line 298 of file pinhole_camera_model.h.

ros::Time image_geometry::PinholeCameraModel::stamp (  )  const [inline]

Get the time stamp associated with this camera model.

Definition at line 290 of file pinhole_camera_model.h.

std::string image_geometry::PinholeCameraModel::tfFrame (  )  const [inline]

Get the name of the camera coordinate frame in tf.

Definition at line 284 of file pinhole_camera_model.h.

cv::Rect image_geometry::PinholeCameraModel::toFullResolution ( const cv::Rect &  roi_reduced  )  const

Definition at line 190 of file pinhole_camera_model.cpp.

cv::Point2d image_geometry::PinholeCameraModel::toFullResolution ( const cv::Point2d &  uv_reduced  )  const

Definition at line 183 of file pinhole_camera_model.cpp.

cv::Rect image_geometry::PinholeCameraModel::toReducedResolution ( const cv::Rect &  roi_full  )  const

Definition at line 206 of file pinhole_camera_model.cpp.

cv::Point2d image_geometry::PinholeCameraModel::toReducedResolution ( const cv::Point2d &  uv_full  )  const

Definition at line 199 of file pinhole_camera_model.cpp.

double image_geometry::PinholeCameraModel::Tx (  )  const [inline]

Returns the x-translation term of the projection matrix.

Definition at line 307 of file pinhole_camera_model.h.

double image_geometry::PinholeCameraModel::Ty (  )  const [inline]

Returns the y-translation term of the projection matrix.

Definition at line 308 of file pinhole_camera_model.h.

void image_geometry::PinholeCameraModel::unrectifyImage ( const cv::Mat &  rectified,
cv::Mat &  raw,
int  interpolation = CV_INTER_LINEAR 
) const

Apply camera distortion to a rectified image.

Todo:
Implement unrectifyImage()

Definition at line 286 of file pinhole_camera_model.cpp.

cv::Point2d image_geometry::PinholeCameraModel::unrectifyPoint ( const cv::Point2d &  uv_rect  )  const

Compute the raw image coordinates of a pixel in the rectified image.

Todo:
Make this just call projectPixelTo3dRay followed by cv::projectPoints. But cv::projectPoints requires 32-bit float, which is annoying.

Definition at line 328 of file pinhole_camera_model.cpp.

void image_geometry::PinholeCameraModel::unrectifyPoint ( const cv::Point2d &  uv_rect,
cv::Point2d &  uv_raw 
) const

Definition at line 323 of file pinhole_camera_model.cpp.

cv::Rect image_geometry::PinholeCameraModel::unrectifyRoi ( const cv::Rect &  roi_rect  )  const

Compute the raw ROI best fitting a rectified ROI.

Todo:
Actually implement "best fit" as described by REP 104.

Definition at line 396 of file pinhole_camera_model.cpp.

uint32_t image_geometry::PinholeCameraModel::width (  )  const [inline]

Returns the image width.

Definition at line 310 of file pinhole_camera_model.h.


Friends And Related Function Documentation

friend class StereoCameraModel [friend]

Definition at line 279 of file pinhole_camera_model.h.


Member Data Documentation

boost::shared_ptr<Cache> image_geometry::PinholeCameraModel::cache_ [protected]

Definition at line 272 of file pinhole_camera_model.h.

sensor_msgs::CameraInfo image_geometry::PinholeCameraModel::cam_info_ [protected]

Definition at line 266 of file pinhole_camera_model.h.

cv::Mat_<double> image_geometry::PinholeCameraModel::D_ [protected]

Definition at line 267 of file pinhole_camera_model.h.

cv::Mat_<double> image_geometry::PinholeCameraModel::K_ [protected]

Definition at line 268 of file pinhole_camera_model.h.

cv::Mat_<double> image_geometry::PinholeCameraModel::K_full_ [protected]

Definition at line 269 of file pinhole_camera_model.h.

cv::Mat_<double> image_geometry::PinholeCameraModel::P_ [protected]

Definition at line 268 of file pinhole_camera_model.h.

cv::Mat_<double> image_geometry::PinholeCameraModel::P_full_ [protected]

Definition at line 269 of file pinhole_camera_model.h.

cv::Mat_<double> image_geometry::PinholeCameraModel::R_ [protected]

Definition at line 267 of file pinhole_camera_model.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Enumerations Enumerator Friends


image_geometry
Author(s): Patrick Mihelich
autogenerated on Fri Jan 11 09:59:22 2013