Go to the documentation of this file.    1 #ifndef IMAGE_GEOMETRY_PINHOLE_CAMERA_MODEL_H 
    2 #define IMAGE_GEOMETRY_PINHOLE_CAMERA_MODEL_H 
    4 #include <sensor_msgs/CameraInfo.h> 
    5 #include <opencv2/core/mat.hpp> 
    6 #include <opencv2/imgproc/imgproc.hpp> 
   17   Exception(
const std::string& description) : 
std::runtime_error(description) {}
 
   37   bool fromCameraInfo(
const sensor_msgs::CameraInfo& msg);
 
   42   bool fromCameraInfo(
const sensor_msgs::CameraInfoConstPtr& msg);
 
   47   std::string tfFrame() 
const;
 
   60   cv::Size fullResolution() 
const;
 
   69   cv::Size reducedResolution() 
const;
 
   71   cv::Point2d toFullResolution(
const cv::Point2d& uv_reduced) 
const;
 
   73   cv::Rect toFullResolution(
const cv::Rect& roi_reduced) 
const;
 
   75   cv::Point2d toReducedResolution(
const cv::Point2d& uv_full) 
const;
 
   77   cv::Rect toReducedResolution(
const cv::Rect& roi_full) 
const;
 
   82   cv::Rect rawRoi() 
const;
 
   87   cv::Rect rectifiedRoi() 
const;
 
   97   cv::Point2d project3dToPixel(
const cv::Point3d& xyz) 
const;
 
  110   cv::Point3d projectPixelTo3dRay(
const cv::Point2d& uv_rect) 
const;
 
  111   cv::Point3d projectPixelTo3dRay(
const cv::Point2d& uv_rect, 
const cv::Matx34d& P) 
const;
 
  116   void rectifyImage(
const cv::Mat& raw, cv::Mat& rectified,
 
  117                     int interpolation = cv::INTER_LINEAR) 
const;
 
  122   void unrectifyImage(
const cv::Mat& rectified, cv::Mat& raw,
 
  123                       int interpolation = cv::INTER_LINEAR) 
const;
 
  128   cv::Point2d rectifyPoint(
const cv::Point2d& uv_raw) 
const;
 
  129   cv::Point2d rectifyPoint(
const cv::Point2d& uv_raw, 
const cv::Matx33d& K, 
const cv::Matx34d& P) 
const;
 
  134   cv::Point2d unrectifyPoint(
const cv::Point2d& uv_rect) 
const;
 
  135   cv::Point2d unrectifyPoint(
const cv::Point2d& uv_rect, 
const cv::Matx33d& K, 
const cv::Matx34d& P) 
const;
 
  140   cv::Rect rectifyRoi(
const cv::Rect& roi_raw) 
const;
 
  145   cv::Rect unrectifyRoi(
const cv::Rect& roi_rect) 
const;
 
  150   const sensor_msgs::CameraInfo& cameraInfo() 
const;
 
  155   const cv::Matx33d& intrinsicMatrix() 
const;
 
  160   const cv::Mat_<double>& distortionCoeffs() 
const;
 
  165   const cv::Matx33d& rotationMatrix() 
const;
 
  170   const cv::Matx34d& projectionMatrix() 
const;
 
  175   const cv::Matx33d& fullIntrinsicMatrix() 
const;
 
  180   const cv::Matx34d& fullProjectionMatrix() 
const;
 
  225   uint32_t binningX() 
const;
 
  230   uint32_t binningY() 
const;
 
  240   double getDeltaU(
double deltaX, 
double Z) 
const;
 
  250   double getDeltaV(
double deltaY, 
double Z) 
const;
 
  260   double getDeltaX(
double deltaU, 
double Z) 
const;
 
  270   double getDeltaY(
double deltaV, 
double Z) 
const;
 
  288 #ifdef BOOST_SHARED_PTR_HPP_INCLUDED 
  291   std::shared_ptr<Cache> 
cache_; 
 
  294   void initRectificationMaps() 
const;
 
  295   void initUnrectificationMaps() 
const;
 
  330         return 2 * atan(
rawRoi().width / (2 * 
fx()));
 
  333         return 2 * atan(
rawRoi().height / (2 * 
fy()));
 
  342   return fx() * deltaX / Z;
 
  348   return fy() * deltaY / Z;
 
  354   return Z * deltaU / 
fx();
 
  360   return Z * deltaV / 
fy();
 
 
double Ty() const
Returns the y-translation term of the projection matrix.
uint32_t binningX() const
Returns the number of columns in each bin.
const cv::Matx33d & intrinsicMatrix() const
Returns the original camera matrix.
sensor_msgs::CameraInfo cam_info_
double fovY() const
Returns the vertical field of view in radians.
uint32_t binningY() const
Returns the number of rows in each bin.
double fovX() const
Returns the horizontal field of view in radians.
Simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo.
const cv::Matx33d & fullIntrinsicMatrix() const
Returns the original camera matrix for full resolution.
std::string tfFrame() const
Get the name of the camera coordinate frame in tf.
double getDeltaX(double deltaU, double Z) const
Compute delta X, given Z in Cartesian space and delta u in pixels.
Exception(const std::string &description)
const sensor_msgs::CameraInfo & cameraInfo() const
Returns the camera info message held internally.
double getDeltaU(double deltaX, double Z) const
Compute delta u, given Z and delta X in Cartesian space.
double Tx() const
Returns the x-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.
std::shared_ptr< Cache > cache_
ros::Time stamp() const
Get the time stamp associated with this camera model.
Simplifies interpreting stereo image pairs geometrically using the parameters from the left and right...
double getDeltaY(double deltaV, double Z) const
Compute delta Y, given Z in Cartesian space and delta v in pixels.
const cv::Matx34d & fullProjectionMatrix() const
Returns the projection matrix for full resolution.
double cy() const
Returns the y coordinate of the optical center.
const cv::Matx33d & rotationMatrix() const
Returns the rotation matrix.
#define IMAGE_GEOMETRY_DECL
double fy() const
Returns the focal length (pixels) in y direction of the rectified image.
double cx() const
Returns the x coordinate of the optical center.
const cv::Mat_< double > & distortionCoeffs() const
Returns the distortion coefficients.
bool initialized() const
Returns true if the camera has been initialized.
cv::Rect rawRoi() const
The current raw ROI, as used for capture by the camera driver.
const cv::Matx34d & projectionMatrix() const
Returns the projection matrix.
image_geometry
Author(s): Patrick Mihelich
autogenerated on Wed Aug 21 2024 02:47:03