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 PinholeCameraModel & | left () const |
Get the left monocular camera model. More... | |
StereoCameraModel & | operator= (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 PinholeCameraModel & | right () 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_ |
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.
image_geometry::StereoCameraModel::StereoCameraModel | ( | ) |
Definition at line 6 of file stereo_camera_model.cpp.
image_geometry::StereoCameraModel::StereoCameraModel | ( | const StereoCameraModel & | other | ) |
Definition at line 12 of file stereo_camera_model.cpp.
|
inline |
Returns the horizontal baseline in world coordinates.
Definition at line 111 of file stereo_camera_model.h.
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.
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.
|
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.
|
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.
|
inline |
Returns true if the camera has been initialized.
Definition at line 94 of file stereo_camera_model.h.
|
inline |
Get the left monocular camera model.
Definition at line 104 of file stereo_camera_model.h.
StereoCameraModel & image_geometry::StereoCameraModel::operator= | ( | const StereoCameraModel & | other | ) |
Definition at line 21 of file stereo_camera_model.cpp.
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.
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.
|
inline |
Returns the disparity reprojection matrix.
Definition at line 109 of file stereo_camera_model.h.
|
inline |
Get the right monocular camera model.
Definition at line 105 of file stereo_camera_model.h.
|
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.
|
protected |
Definition at line 54 of file stereo_camera_model.cpp.
|
protected |
Definition at line 96 of file stereo_camera_model.h.
|
static |
Definition at line 65 of file stereo_camera_model.h.
|
protected |
Definition at line 97 of file stereo_camera_model.h.
|
protected |
Definition at line 96 of file stereo_camera_model.h.