1 #ifndef IMAGE_GEOMETRY_STEREO_CAMERA_MODEL_H 2 #define IMAGE_GEOMETRY_STEREO_CAMERA_MODEL_H 25 bool fromCameraInfo(
const sensor_msgs::CameraInfo& left,
26 const sensor_msgs::CameraInfo& right);
31 bool fromCameraInfo(
const sensor_msgs::CameraInfoConstPtr& left,
32 const sensor_msgs::CameraInfoConstPtr& right);
50 std::string tfFrame()
const;
55 void projectDisparityTo3d(
const cv::Point2d& left_uv_rect,
float disparity, cv::Point3d& xyz)
const;
63 void projectDisparityImageTo3d(
const cv::Mat& disparity, cv::Mat& point_cloud,
64 bool handleMissingValues =
false)
const;
70 const cv::Matx44d& reprojectionMatrix()
const;
75 double baseline()
const;
82 double getZ(
double disparity)
const;
89 double getDisparity(
double Z)
const;
94 bool initialized()
const {
return left_.initialized() && right_.initialized(); }
114 return -right_.Tx() / right_.fx();
119 assert( initialized() );
120 return -right_.Tx() / (disparity - (left().cx() - right().cx()));
125 assert( initialized() );
126 return -right_.Tx() / Z + (left().cx() - right().cx()); ;
PinholeCameraModel right_
double getZ(double disparity) const
Returns the depth at which a point is observed with a given disparity.
static const double MISSING_Z
std::string tfFrame() const
Get the name of the camera coordinate frame in tf.
const PinholeCameraModel & right() const
Get the right monocular camera model.
double getDisparity(double Z) const
Returns the disparity observed for a point at depth Z.
Simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo.
const cv::Matx44d & reprojectionMatrix() const
Returns the disparity reprojection matrix.
#define IMAGE_GEOMETRY_DECL
const PinholeCameraModel & left() const
Get the left monocular camera model.
bool initialized() const
Returns true if the camera has been initialized.
double baseline() const
Returns the horizontal baseline in world coordinates.
Simplifies interpreting stereo image pairs geometrically using the parameters from the left and right...