stereo_camera_model.h
Go to the documentation of this file.
1 #ifndef IMAGE_GEOMETRY_STEREO_CAMERA_MODEL_H
2 #define IMAGE_GEOMETRY_STEREO_CAMERA_MODEL_H
3 
5 #include "exports.h"
6 
7 namespace image_geometry {
8 
14 {
15 public:
17 
19 
20  StereoCameraModel& operator=(const StereoCameraModel& other);
21 
25  bool fromCameraInfo(const sensor_msgs::CameraInfo& left,
26  const sensor_msgs::CameraInfo& right);
27 
31  bool fromCameraInfo(const sensor_msgs::CameraInfoConstPtr& left,
32  const sensor_msgs::CameraInfoConstPtr& right);
33 
37  const PinholeCameraModel& left() const;
38 
42  const PinholeCameraModel& right() const;
43 
50  std::string tfFrame() const;
51 
55  void projectDisparityTo3d(const cv::Point2d& left_uv_rect, float disparity, cv::Point3d& xyz) const;
56 
63  void projectDisparityImageTo3d(const cv::Mat& disparity, cv::Mat& point_cloud,
64  bool handleMissingValues = false) const;
65  static const double MISSING_Z;
66 
70  const cv::Matx44d& reprojectionMatrix() const;
71 
75  double baseline() const;
76 
82  double getZ(double disparity) const;
83 
89  double getDisparity(double Z) const;
90 
94  bool initialized() const { return left_.initialized() && right_.initialized(); }
95 protected:
97  cv::Matx44d Q_;
98 
99  void updateQ();
100 };
101 
102 
103 /* Trivial inline functions */
104 inline const PinholeCameraModel& StereoCameraModel::left() const { return left_; }
105 inline const PinholeCameraModel& StereoCameraModel::right() const { return right_; }
106 
107 inline std::string StereoCameraModel::tfFrame() const { return left_.tfFrame(); }
108 
109 inline const cv::Matx44d& StereoCameraModel::reprojectionMatrix() const { return Q_; }
110 
111 inline double StereoCameraModel::baseline() const
112 {
114  return -right_.Tx() / right_.fx();
115 }
116 
117 inline double StereoCameraModel::getZ(double disparity) const
118 {
119  assert( initialized() );
120  return -right_.Tx() / (disparity - (left().cx() - right().cx()));
121 }
122 
123 inline double StereoCameraModel::getDisparity(double Z) const
124 {
125  assert( initialized() );
126  return -right_.Tx() / Z + (left().cx() - right().cx()); ;
127 }
128 
129 } //namespace image_geometry
130 
131 #endif
double getZ(double disparity) const
Returns the depth at which a point is observed with a given disparity.
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
Definition: exports.h:15
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...


image_geometry
Author(s): Patrick Mihelich
autogenerated on Tue Oct 4 2022 02:19:05