Class PinholeCameraModel
Defined in File pinhole_camera_model.h
Class Documentation
-
class PinholeCameraModel
Simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo.
Public Functions
-
IMAGE_GEOMETRY_PUBLIC PinholeCameraModel()
-
IMAGE_GEOMETRY_PUBLIC PinholeCameraModel(const PinholeCameraModel &other)
- IMAGE_GEOMETRY_PUBLIC PinholeCameraModel & operator= (const PinholeCameraModel &other)
- IMAGE_GEOMETRY_PUBLIC bool fromCameraInfo (const sensor_msgs::msg::CameraInfo &msg)
Set the camera parameters from the sensor_msgs/CameraInfo message.
- IMAGE_GEOMETRY_PUBLIC bool fromCameraInfo (const sensor_msgs::msg::CameraInfo::ConstSharedPtr &msg)
Set the camera parameters from the sensor_msgs/CameraInfo message.
- inline IMAGE_GEOMETRY_PUBLIC std::string tfFrame () const
Get the name of the camera coordinate frame in tf.
- inline IMAGE_GEOMETRY_PUBLIC builtin_interfaces::msg::Time stamp () const
Get the time stamp associated with this camera model.
- IMAGE_GEOMETRY_PUBLIC cv::Size fullResolution () const
The resolution at which the camera was calibrated.
The maximum resolution at which the camera can be used with the current calibration; normally this is the same as the imager resolution.
- IMAGE_GEOMETRY_PUBLIC cv::Size reducedResolution () const
The resolution of the current rectified image.
The size of the rectified image associated with the latest CameraInfo, as reduced by binning/ROI and affected by distortion. If binning and ROI are not in use, this is the same as fullResolution().
- IMAGE_GEOMETRY_PUBLIC cv::Point2d toFullResolution (const cv::Point2d &uv_reduced) const
- IMAGE_GEOMETRY_PUBLIC cv::Rect toFullResolution (const cv::Rect &roi_reduced) const
- IMAGE_GEOMETRY_PUBLIC cv::Point2d toReducedResolution (const cv::Point2d &uv_full) const
- IMAGE_GEOMETRY_PUBLIC cv::Rect toReducedResolution (const cv::Rect &roi_full) const
- IMAGE_GEOMETRY_PUBLIC cv::Rect rawRoi () const
The current raw ROI, as used for capture by the camera driver.
- IMAGE_GEOMETRY_PUBLIC cv::Rect rectifiedRoi () const
The current rectified ROI, which best fits the raw ROI.
- IMAGE_GEOMETRY_PUBLIC cv::Point2d project3dToPixel (const cv::Point3d &xyz) const
Project a 3d point to rectified pixel coordinates.
This is the inverse of projectPixelTo3dRay().
- Parameters
xyz – 3d point in the camera coordinate frame
- Returns
(u,v) in rectified pixel coordinates
- IMAGE_GEOMETRY_PUBLIC cv::Point3d projectPixelTo3dRay (const cv::Point2d &uv_rect) const
Project a rectified pixel to a 3d ray.
Returns the unit vector in the camera coordinate frame in the direction of rectified pixel (u,v) in the image plane. This is the inverse of project3dToPixel().
In 1.4.x, the vector has z = 1.0. Previously, this function returned a unit vector.
- Parameters
uv_rect – Rectified pixel coordinates
- Returns
3d ray passing through (u,v)
-
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect, const cv::Matx34d &P) const
- IMAGE_GEOMETRY_PUBLIC void rectifyImage (const cv::Mat &raw, cv::Mat &rectified, int interpolation=cv::INTER_LINEAR) const
Rectify a raw camera image.
- IMAGE_GEOMETRY_PUBLIC void unrectifyImage (const cv::Mat &rectified, cv::Mat &raw, int interpolation=cv::INTER_LINEAR) const
Apply camera distortion to a rectified image.
- IMAGE_GEOMETRY_PUBLIC cv::Point2d rectifyPoint (const cv::Point2d &uv_raw) const
Compute the rectified image coordinates of a pixel in the raw image.
-
cv::Point2d rectifyPoint(const cv::Point2d &uv_raw, const cv::Matx33d &K, const cv::Matx34d &P) const
- IMAGE_GEOMETRY_PUBLIC cv::Point2d unrectifyPoint (const cv::Point2d &uv_rect) const
Compute the raw image coordinates of a pixel in the rectified image.
-
cv::Point2d unrectifyPoint(const cv::Point2d &uv_rect, const cv::Matx33d &K, const cv::Matx34d &P) const
- IMAGE_GEOMETRY_PUBLIC cv::Rect rectifyRoi (const cv::Rect &roi_raw) const
Compute the rectified ROI best fitting a raw ROI.
- IMAGE_GEOMETRY_PUBLIC cv::Rect unrectifyRoi (const cv::Rect &roi_rect) const
Compute the raw ROI best fitting a rectified ROI.
- inline IMAGE_GEOMETRY_PUBLIC const sensor_msgs::msg::CameraInfo & cameraInfo () const
Returns the camera info message held internally.
- inline IMAGE_GEOMETRY_PUBLIC const cv::Matx33d & intrinsicMatrix () const
Returns the original camera matrix.
- inline IMAGE_GEOMETRY_PUBLIC const cv::Mat_< double > & distortionCoeffs () const
Returns the distortion coefficients.
- inline IMAGE_GEOMETRY_PUBLIC const cv::Matx33d & rotationMatrix () const
Returns the rotation matrix.
- inline IMAGE_GEOMETRY_PUBLIC const cv::Matx34d & projectionMatrix () const
Returns the projection matrix.
- inline IMAGE_GEOMETRY_PUBLIC const cv::Matx33d & fullIntrinsicMatrix () const
Returns the original camera matrix for full resolution.
- inline IMAGE_GEOMETRY_PUBLIC const cv::Matx34d & fullProjectionMatrix () const
Returns the projection matrix for full resolution.
- inline IMAGE_GEOMETRY_PUBLIC double fx () const
Returns the focal length (pixels) in x direction of the rectified image.
- inline IMAGE_GEOMETRY_PUBLIC double fy () const
Returns the focal length (pixels) in y direction of the rectified image.
- inline IMAGE_GEOMETRY_PUBLIC double cx () const
Returns the x coordinate of the optical center.
- inline IMAGE_GEOMETRY_PUBLIC double cy () const
Returns the y coordinate of the optical center.
- inline IMAGE_GEOMETRY_PUBLIC double Tx () const
Returns the x-translation term of the projection matrix.
- inline IMAGE_GEOMETRY_PUBLIC double Ty () const
Returns the y-translation term of the projection matrix.
- inline IMAGE_GEOMETRY_PUBLIC uint32_t binningX () const
Returns the number of columns in each bin.
- inline IMAGE_GEOMETRY_PUBLIC uint32_t binningY () const
Returns the number of rows in each bin.
- inline IMAGE_GEOMETRY_PUBLIC double getDeltaU (double deltaX, double Z) const
Compute delta u, given Z and delta X in Cartesian space.
For given Z, this is the inverse of getDeltaX().
- Parameters
deltaX – Delta X, in Cartesian space
Z – Z (depth), in Cartesian space
- inline IMAGE_GEOMETRY_PUBLIC double getDeltaV (double deltaY, double Z) const
Compute delta v, given Z and delta Y in Cartesian space.
For given Z, this is the inverse of getDeltaY().
- Parameters
deltaY – Delta Y, in Cartesian space
Z – Z (depth), in Cartesian space
- inline IMAGE_GEOMETRY_PUBLIC double getDeltaX (double deltaU, double Z) const
Compute delta X, given Z in Cartesian space and delta u in pixels.
For given Z, this is the inverse of getDeltaU().
- Parameters
deltaU – Delta u, in pixels
Z – Z (depth), in Cartesian space
- inline IMAGE_GEOMETRY_PUBLIC double getDeltaY (double deltaV, double Z) const
Compute delta Y, given Z in Cartesian space and delta v in pixels.
For given Z, this is the inverse of getDeltaV().
- Parameters
deltaV – Delta v, in pixels
Z – Z (depth), in Cartesian space
- inline IMAGE_GEOMETRY_PUBLIC bool initialized () const
Returns true if the camera has been initialized.
Protected Functions
- IMAGE_GEOMETRY_PUBLIC void initRectificationMaps () const
-
void initUnrectificationMaps() const
Protected Attributes
-
sensor_msgs::msg::CameraInfo cam_info_
-
cv::Mat_<double> D_
-
cv::Matx33d R_
-
cv::Matx33d K_
-
cv::Matx34d P_
-
cv::Matx33d K_full_
-
cv::Matx34d P_full_
-
std::shared_ptr<Cache> cache_
Friends
- friend class StereoCameraModel
-
IMAGE_GEOMETRY_PUBLIC PinholeCameraModel()