pinhole_camera_model.h
Go to the documentation of this file.
1 #ifndef IMAGE_GEOMETRY_PINHOLE_CAMERA_MODEL_H
2 #define IMAGE_GEOMETRY_PINHOLE_CAMERA_MODEL_H
3 
4 #include <sensor_msgs/CameraInfo.h>
5 #include <opencv2/core/core.hpp>
6 #include <opencv2/imgproc/imgproc.hpp>
7 #include <opencv2/calib3d/calib3d.hpp>
8 #include <stdexcept>
9 #include <string>
10 #include "exports.h"
11 
12 namespace image_geometry {
13 
14 class Exception : public std::runtime_error
15 {
16 public:
17  Exception(const std::string& description) : std::runtime_error(description) {}
18 };
19 
25 {
26 public:
27 
29 
31 
32  PinholeCameraModel& operator=(const PinholeCameraModel& other);
33 
37  bool fromCameraInfo(const sensor_msgs::CameraInfo& msg);
38 
42  bool fromCameraInfo(const sensor_msgs::CameraInfoConstPtr& msg);
43 
47  std::string tfFrame() const;
48 
52  ros::Time stamp() const;
53 
60  cv::Size fullResolution() const;
61 
69  cv::Size reducedResolution() const;
70 
71  cv::Point2d toFullResolution(const cv::Point2d& uv_reduced) const;
72 
73  cv::Rect toFullResolution(const cv::Rect& roi_reduced) const;
74 
75  cv::Point2d toReducedResolution(const cv::Point2d& uv_full) const;
76 
77  cv::Rect toReducedResolution(const cv::Rect& roi_full) const;
78 
82  cv::Rect rawRoi() const;
83 
87  cv::Rect rectifiedRoi() const;
88 
97  cv::Point2d project3dToPixel(const cv::Point3d& xyz) const;
98 
110  cv::Point3d projectPixelTo3dRay(const cv::Point2d& uv_rect) const;
111 
115  void rectifyImage(const cv::Mat& raw, cv::Mat& rectified,
116  int interpolation = cv::INTER_LINEAR) const;
117 
121  void unrectifyImage(const cv::Mat& rectified, cv::Mat& raw,
122  int interpolation = cv::INTER_LINEAR) const;
123 
127  cv::Point2d rectifyPoint(const cv::Point2d& uv_raw) const;
128 
132  cv::Point2d unrectifyPoint(const cv::Point2d& uv_rect) const;
133 
137  cv::Rect rectifyRoi(const cv::Rect& roi_raw) const;
138 
142  cv::Rect unrectifyRoi(const cv::Rect& roi_rect) const;
143 
147  const sensor_msgs::CameraInfo& cameraInfo() const;
148 
152  const cv::Matx33d& intrinsicMatrix() const;
153 
157  const cv::Mat_<double>& distortionCoeffs() const;
158 
162  const cv::Matx33d& rotationMatrix() const;
163 
167  const cv::Matx34d& projectionMatrix() const;
168 
172  const cv::Matx33d& fullIntrinsicMatrix() const;
173 
177  const cv::Matx34d& fullProjectionMatrix() const;
178 
182  double fx() const;
183 
187  double fy() const;
188 
192  double cx() const;
193 
197  double cy() const;
198 
202  double Tx() const;
203 
207  double Ty() const;
208 
212  uint32_t binningX() const;
213 
217  uint32_t binningY() const;
218 
227  double getDeltaU(double deltaX, double Z) const;
228 
237  double getDeltaV(double deltaY, double Z) const;
238 
247  double getDeltaX(double deltaU, double Z) const;
248 
257  double getDeltaY(double deltaV, double Z) const;
258 
262  bool initialized() const { return (bool)cache_; }
263 
264 protected:
265  sensor_msgs::CameraInfo cam_info_;
266  cv::Mat_<double> D_; // Unaffected by binning, ROI
267  cv::Matx33d R_; // Unaffected by binning, ROI
268  cv::Matx33d K_; // Describe current image (includes binning, ROI)
269  cv::Matx34d P_; // Describe current image (includes binning, ROI)
270  cv::Matx33d K_full_; // Describe full-res image, needed for full maps
271  cv::Matx34d P_full_; // Describe full-res image, needed for full maps
272 
273  // Use PIMPL here so we can change internals in patch updates if needed
274  struct Cache;
275 #ifdef BOOST_SHARED_PTR_HPP_INCLUDED
276  boost::shared_ptr<Cache> cache_; // Holds cached data for internal use
277 #else
278  std::shared_ptr<Cache> cache_; // Holds cached data for internal use
279 #endif
280 
281  void initRectificationMaps() const;
282 
283  friend class StereoCameraModel;
284 };
285 
286 
287 /* Trivial inline functions */
288 inline std::string PinholeCameraModel::tfFrame() const
289 {
290  assert( initialized() );
291  return cam_info_.header.frame_id;
292 }
293 
295 {
296  assert( initialized() );
297  return cam_info_.header.stamp;
298 }
299 
300 inline const sensor_msgs::CameraInfo& PinholeCameraModel::cameraInfo() const { return cam_info_; }
301 inline const cv::Matx33d& PinholeCameraModel::intrinsicMatrix() const { return K_; }
302 inline const cv::Mat_<double>& PinholeCameraModel::distortionCoeffs() const { return D_; }
303 inline const cv::Matx33d& PinholeCameraModel::rotationMatrix() const { return R_; }
304 inline const cv::Matx34d& PinholeCameraModel::projectionMatrix() const { return P_; }
305 inline const cv::Matx33d& PinholeCameraModel::fullIntrinsicMatrix() const { return K_full_; }
306 inline const cv::Matx34d& PinholeCameraModel::fullProjectionMatrix() const { return P_full_; }
307 
308 inline double PinholeCameraModel::fx() const { return P_(0,0); }
309 inline double PinholeCameraModel::fy() const { return P_(1,1); }
310 inline double PinholeCameraModel::cx() const { return P_(0,2); }
311 inline double PinholeCameraModel::cy() const { return P_(1,2); }
312 inline double PinholeCameraModel::Tx() const { return P_(0,3); }
313 inline double PinholeCameraModel::Ty() const { return P_(1,3); }
314 
315 inline uint32_t PinholeCameraModel::binningX() const { return cam_info_.binning_x; }
316 inline uint32_t PinholeCameraModel::binningY() const { return cam_info_.binning_y; }
317 
318 inline double PinholeCameraModel::getDeltaU(double deltaX, double Z) const
319 {
320  assert( initialized() );
321  return fx() * deltaX / Z;
322 }
323 
324 inline double PinholeCameraModel::getDeltaV(double deltaY, double Z) const
325 {
326  assert( initialized() );
327  return fy() * deltaY / Z;
328 }
329 
330 inline double PinholeCameraModel::getDeltaX(double deltaU, double Z) const
331 {
332  assert( initialized() );
333  return Z * deltaU / fx();
334 }
335 
336 inline double PinholeCameraModel::getDeltaY(double deltaV, double Z) const
337 {
338  assert( initialized() );
339  return Z * deltaV / fy();
340 }
341 
342 } //namespace image_geometry
343 
344 #endif
double getDeltaY(double deltaV, double Z) const
Compute delta Y, given Z in Cartesian space and delta v in pixels.
double getDeltaU(double deltaX, double Z) const
Compute delta u, given Z and delta X in Cartesian space.
const cv::Matx34d & fullProjectionMatrix() const
Returns the projection matrix for full resolution.
bool initialized() const
Returns true if the camera has been initialized.
double getDeltaX(double deltaU, double Z) const
Compute delta X, given Z in Cartesian space and delta u in pixels.
double cy() const
Returns the y coordinate of the optical center.
uint32_t binningX() const
Returns the number of columns in each bin.
const cv::Mat_< double > & distortionCoeffs() const
Returns the distortion coefficients.
double Ty() const
Returns the y-translation term of the projection matrix.
double getDeltaV(double deltaY, double Z) const
Compute delta v, given Z and delta Y in Cartesian space.
double fx() const
Returns the focal length (pixels) in x direction of the rectified image.
Simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo.
const cv::Matx33d & fullIntrinsicMatrix() const
Returns the original camera matrix for full resolution.
#define IMAGE_GEOMETRY_DECL
Definition: exports.h:15
std::string tfFrame() const
Get the name of the camera coordinate frame in tf.
double cx() const
Returns the x coordinate of the optical center.
const cv::Matx33d & intrinsicMatrix() const
Returns the original camera matrix.
ros::Time stamp() const
Get the time stamp associated with this camera model.
const cv::Matx34d & projectionMatrix() const
Returns the projection matrix.
const sensor_msgs::CameraInfo & cameraInfo() const
Returns the camera info message held internally.
double Tx() const
Returns the x-translation term of the projection matrix.
Exception(const std::string &description)
double fy() const
Returns the focal length (pixels) in y direction of the rectified image.
uint32_t binningY() const
Returns the number of rows in each bin.
const cv::Matx33d & rotationMatrix() const
Returns the rotation matrix.
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