Class StereoCameraModel
Defined in File stereo_camera_model.h
Class Documentation
-
class StereoCameraModel
Simplifies interpreting stereo image pairs geometrically using the parameters from the left and right sensor_msgs/CameraInfo.
Public Functions
-
IMAGE_GEOMETRY_PUBLIC StereoCameraModel()
-
IMAGE_GEOMETRY_PUBLIC StereoCameraModel(const StereoCameraModel &other)
- IMAGE_GEOMETRY_PUBLIC StereoCameraModel & operator= (const StereoCameraModel &other)
- IMAGE_GEOMETRY_PUBLIC bool fromCameraInfo (const sensor_msgs::msg::CameraInfo &left, const sensor_msgs::msg::CameraInfo &right)
Set the camera parameters from the sensor_msgs/CameraInfo messages.
- IMAGE_GEOMETRY_PUBLIC bool fromCameraInfo (const sensor_msgs::msg::CameraInfo::ConstSharedPtr &left, const sensor_msgs::msg::CameraInfo::ConstSharedPtr &right)
Set the camera parameters from the sensor_msgs/CameraInfo messages.
- inline IMAGE_GEOMETRY_PUBLIC const PinholeCameraModel & left () const
Get the left monocular camera model.
- inline IMAGE_GEOMETRY_PUBLIC const PinholeCameraModel & right () const
Get the right monocular camera model.
- inline IMAGE_GEOMETRY_PUBLIC std::string tfFrame () const
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.
- IMAGE_GEOMETRY_PUBLIC void projectDisparityTo3d (const cv::Point2d &left_uv_rect, float disparity, cv::Point3d &xyz) const
Project a rectified pixel with disparity to a 3d point.
- IMAGE_GEOMETRY_PUBLIC void 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).
- inline IMAGE_GEOMETRY_PUBLIC const cv::Matx44d & reprojectionMatrix () const
Returns the disparity reprojection matrix.
- inline IMAGE_GEOMETRY_PUBLIC double baseline () const
Returns the horizontal baseline in world coordinates.
- inline IMAGE_GEOMETRY_PUBLIC double getZ (double disparity) const
Returns the depth at which a point is observed with a given disparity.
This is the inverse of getDisparity().
- inline IMAGE_GEOMETRY_PUBLIC double getDisparity (double Z) const
Returns the disparity observed for a point at depth Z.
This is the inverse of getZ().
- inline IMAGE_GEOMETRY_PUBLIC bool initialized () const
Returns true if the camera has been initialized.
Public Static Attributes
-
static const double MISSING_Z
Protected Functions
- IMAGE_GEOMETRY_PUBLIC void updateQ ()
-
IMAGE_GEOMETRY_PUBLIC StereoCameraModel()