Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | List of all members
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>

Public Member Functions

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

Static Public Attributes

static const double MISSING_Z = 10000.
 

Protected Member Functions

void updateQ ()
 

Protected Attributes

PinholeCameraModel left_
 
cv::Matx44d 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 13 of file stereo_camera_model.h.

Constructor & Destructor Documentation

◆ StereoCameraModel() [1/2]

image_geometry::StereoCameraModel::StereoCameraModel ( )

Definition at line 6 of file stereo_camera_model.cpp.

◆ StereoCameraModel() [2/2]

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

Definition at line 12 of file stereo_camera_model.cpp.

Member Function Documentation

◆ baseline()

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

Returns the horizontal baseline in world coordinates.

Todo:
Currently assuming horizontal baseline

Definition at line 111 of file stereo_camera_model.h.

◆ fromCameraInfo() [1/2]

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 28 of file stereo_camera_model.cpp.

◆ fromCameraInfo() [2/2]

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 48 of file stereo_camera_model.cpp.

◆ getDisparity()

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 123 of file stereo_camera_model.h.

◆ getZ()

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 117 of file stereo_camera_model.h.

◆ initialized()

bool image_geometry::StereoCameraModel::initialized ( ) const
inline

Returns true if the camera has been initialized.

Definition at line 94 of file stereo_camera_model.h.

◆ left()

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

Get the left monocular camera model.

Definition at line 104 of file stereo_camera_model.h.

◆ operator=()

StereoCameraModel & image_geometry::StereoCameraModel::operator= ( const StereoCameraModel other)

Definition at line 21 of file stereo_camera_model.cpp.

◆ projectDisparityImageTo3d()

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 133 of file stereo_camera_model.cpp.

◆ projectDisparityTo3d()

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 116 of file stereo_camera_model.cpp.

◆ reprojectionMatrix()

const cv::Matx44d & image_geometry::StereoCameraModel::reprojectionMatrix ( ) const
inline

Returns the disparity reprojection matrix.

Definition at line 109 of file stereo_camera_model.h.

◆ right()

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

Get the right monocular camera model.

Definition at line 105 of file stereo_camera_model.h.

◆ tfFrame()

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 107 of file stereo_camera_model.h.

◆ updateQ()

void image_geometry::StereoCameraModel::updateQ ( )
protected

Definition at line 54 of file stereo_camera_model.cpp.

Member Data Documentation

◆ left_

PinholeCameraModel image_geometry::StereoCameraModel::left_
protected

Definition at line 96 of file stereo_camera_model.h.

◆ MISSING_Z

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

Definition at line 65 of file stereo_camera_model.h.

◆ Q_

cv::Matx44d image_geometry::StereoCameraModel::Q_
protected

Definition at line 97 of file stereo_camera_model.h.

◆ right_

PinholeCameraModel image_geometry::StereoCameraModel::right_
protected

Definition at line 96 of file stereo_camera_model.h.


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


image_geometry
Author(s): Patrick Mihelich
autogenerated on Mon Oct 3 2022 02:45:59