image_geometry::StereoCameraModel Class Reference

Simplifies interpreting stereo image pairs geometrically using the parameters from the left and right sensor_msgs/CameraInfo. More...

#include <stereo_camera_model.h>

List of all members.

Public Member Functions

double baseline () const
 Returns the horizontal baseline in world coordinates.
bool fromCameraInfo (const sensor_msgs::CameraInfoConstPtr &left, const sensor_msgs::CameraInfoConstPtr &right)
 Set the camera parameters from the sensor_msgs/CameraInfo messages.
bool fromCameraInfo (const sensor_msgs::CameraInfo &left, const sensor_msgs::CameraInfo &right)
 Set the camera parameters from the sensor_msgs/CameraInfo messages.
double getDisparity (double Z) const
 Returns the disparity observed for a point at depth Z.
double getZ (double disparity) const
 Returns the depth at which a point is observed with a given disparity.
const PinholeCameraModelleft () const
 Get the left monocular camera model.
void projectDisparityImageTo3d (const cv::Mat &disparity, cv::Mat &point_cloud, bool handleMissingValues=false) const
 Project a disparity image to a 3d point cloud.
void projectDisparityTo3d (const cv::Point2d &left_uv_rect, float disparity, cv::Point3d &xyz) const
 Project a rectified pixel with disparity to a 3d point.
const cv::Mat_< double > & reprojectionMatrix () const
 Returns the disparity reprojection matrix.
const PinholeCameraModelright () const
 Get the right monocular camera model.
 StereoCameraModel (const StereoCameraModel &other)
 StereoCameraModel ()
std::string tfFrame () const
 Get the name of the camera coordinate frame in tf.

Static Public Attributes

static const double MISSING_Z = 10000.

Protected Member Functions

bool initialized () const
void updateQ ()

Protected Attributes

PinholeCameraModel left_
cv::Mat_< double > Q_
PinholeCameraModel right_

Detailed Description

Simplifies interpreting stereo image pairs geometrically using the parameters from the left and right sensor_msgs/CameraInfo.

Definition at line 11 of file stereo_camera_model.h.


Constructor & Destructor Documentation

image_geometry::StereoCameraModel::StereoCameraModel (  ) 

Definition at line 4 of file stereo_camera_model.cpp.

image_geometry::StereoCameraModel::StereoCameraModel ( const StereoCameraModel other  ) 

Definition at line 10 of file stereo_camera_model.cpp.


Member Function Documentation

double image_geometry::StereoCameraModel::baseline (  )  const [inline]

Returns the horizontal baseline in world coordinates.

Todo:
Currently assuming horizontal baseline

Definition at line 105 of file stereo_camera_model.h.

bool image_geometry::StereoCameraModel::fromCameraInfo ( const sensor_msgs::CameraInfoConstPtr &  left,
const sensor_msgs::CameraInfoConstPtr &  right 
)

Set the camera parameters from the sensor_msgs/CameraInfo messages.

Definition at line 39 of file stereo_camera_model.cpp.

bool image_geometry::StereoCameraModel::fromCameraInfo ( const sensor_msgs::CameraInfo &  left,
const sensor_msgs::CameraInfo &  right 
)

Set the camera parameters from the sensor_msgs/CameraInfo messages.

Definition at line 19 of file stereo_camera_model.cpp.

double image_geometry::StereoCameraModel::getDisparity ( double  Z  )  const [inline]

Returns the disparity observed for a point at depth Z.

This is the inverse of getZ().

Definition at line 117 of file stereo_camera_model.h.

double image_geometry::StereoCameraModel::getZ ( double  disparity  )  const [inline]

Returns the depth at which a point is observed with a given disparity.

This is the inverse of getDisparity().

Definition at line 111 of file stereo_camera_model.h.

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

Definition at line 86 of file stereo_camera_model.h.

const PinholeCameraModel & image_geometry::StereoCameraModel::left (  )  const [inline]

Get the left monocular camera model.

Definition at line 98 of file stereo_camera_model.h.

void image_geometry::StereoCameraModel::projectDisparityImageTo3d ( const cv::Mat &  disparity,
cv::Mat &  point_cloud,
bool  handleMissingValues = false 
) const

Project a disparity image to a 3d point cloud.

If handleMissingValues = true, all points with minimal disparity (outliers) have Z set to MISSING_Z (currently 10000.0).

Definition at line 87 of file stereo_camera_model.cpp.

void image_geometry::StereoCameraModel::projectDisparityTo3d ( const cv::Point2d &  left_uv_rect,
float  disparity,
cv::Point3d &  xyz 
) const

Project a rectified pixel with disparity to a 3d point.

Definition at line 70 of file stereo_camera_model.cpp.

const cv::Mat_< double > & image_geometry::StereoCameraModel::reprojectionMatrix (  )  const [inline]

Returns the disparity reprojection matrix.

Definition at line 103 of file stereo_camera_model.h.

const PinholeCameraModel & image_geometry::StereoCameraModel::right (  )  const [inline]

Get the right monocular camera model.

Definition at line 99 of file stereo_camera_model.h.

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

Get the name of the camera coordinate frame in tf.

For stereo cameras, both the left and right CameraInfo should be in the left optical frame.

Definition at line 101 of file stereo_camera_model.h.

void image_geometry::StereoCameraModel::updateQ (  )  [protected]

Definition at line 45 of file stereo_camera_model.cpp.


Member Data Documentation

Definition at line 81 of file stereo_camera_model.h.

const double image_geometry::StereoCameraModel::MISSING_Z = 10000. [static]

Definition at line 54 of file stereo_camera_model.h.

cv::Mat_<double> image_geometry::StereoCameraModel::Q_ [protected]

Definition at line 82 of file stereo_camera_model.h.

Definition at line 81 of file stereo_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