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/core.hpp> 6 #include <opencv2/imgproc/imgproc.hpp> 7 #include <opencv2/calib3d/calib3d.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;
115 void rectifyImage(
const cv::Mat& raw, cv::Mat& rectified,
116 int interpolation = cv::INTER_LINEAR)
const;
121 void unrectifyImage(
const cv::Mat& rectified, cv::Mat& raw,
122 int interpolation = cv::INTER_LINEAR)
const;
127 cv::Point2d rectifyPoint(
const cv::Point2d& uv_raw)
const;
132 cv::Point2d unrectifyPoint(
const cv::Point2d& uv_rect)
const;
137 cv::Rect rectifyRoi(
const cv::Rect& roi_raw)
const;
142 cv::Rect unrectifyRoi(
const cv::Rect& roi_rect)
const;
147 const sensor_msgs::CameraInfo& cameraInfo()
const;
152 const cv::Matx33d& intrinsicMatrix()
const;
157 const cv::Mat_<double>& distortionCoeffs()
const;
162 const cv::Matx33d& rotationMatrix()
const;
167 const cv::Matx34d& projectionMatrix()
const;
172 const cv::Matx33d& fullIntrinsicMatrix()
const;
177 const cv::Matx34d& fullProjectionMatrix()
const;
212 uint32_t binningX()
const;
217 uint32_t binningY()
const;
227 double getDeltaU(
double deltaX,
double Z)
const;
237 double getDeltaV(
double deltaY,
double Z)
const;
247 double getDeltaX(
double deltaU,
double Z)
const;
257 double getDeltaY(
double deltaV,
double Z)
const;
275 #ifdef BOOST_SHARED_PTR_HPP_INCLUDED 278 std::shared_ptr<Cache>
cache_;
281 void initRectificationMaps()
const;
290 assert( initialized() );
291 return cam_info_.header.frame_id;
296 assert( initialized() );
297 return cam_info_.header.stamp;
320 assert( initialized() );
321 return fx() * deltaX / Z;
326 assert( initialized() );
327 return fy() * deltaY / Z;
332 assert( initialized() );
333 return Z * deltaU / fx();
338 assert( initialized() );
339 return Z * deltaV / fy();
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.
sensor_msgs::CameraInfo cam_info_
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_
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
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...