Simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo. More...
#include <pinhole_camera_model.h>
Classes | |
struct | Cache |
Public Member Functions | |
uint32_t | binningX () const |
Returns the number of columns in each bin. | |
uint32_t | binningY () const |
Returns the number of rows in each bin. | |
double | cx () const |
Returns the x coordinate of the optical center. | |
double | cy () const |
Returns the y coordinate of the optical center. | |
const cv::Mat_< double > & | distortionCoeffs () const |
Returns the distortion coefficients. | |
bool | fromCameraInfo (const sensor_msgs::CameraInfo &msg) |
Set the camera parameters from the sensor_msgs/CameraInfo message. | |
bool | fromCameraInfo (const sensor_msgs::CameraInfoConstPtr &msg) |
Set the camera parameters from the sensor_msgs/CameraInfo message. | |
const cv::Mat_< double > & | fullIntrinsicMatrix () const |
Returns the original camera matrix for full resolution. | |
const cv::Mat_< double > & | fullProjectionMatrix () const |
Returns the projection matrix for full resolution. | |
cv::Size | fullResolution () const |
The resolution at which the camera was calibrated. | |
double | fx () const |
Returns the focal length (pixels) in x direction of the rectified image. | |
double | fy () const |
Returns the focal length (pixels) in y direction of the rectified image. | |
double | getDeltaU (double deltaX, double Z) const |
Compute delta u, given Z and delta X in Cartesian space. | |
double | getDeltaV (double deltaY, double Z) const |
Compute delta v, given Z and delta Y in Cartesian space. | |
double | getDeltaX (double deltaU, double Z) const |
Compute delta X, given Z in Cartesian space and delta u in pixels. | |
double | getDeltaY (double deltaV, double Z) const |
Compute delta Y, given Z in Cartesian space and delta v in pixels. | |
uint32_t | height () const ROS_DEPRECATED |
Returns the image height. | |
bool | initialized () const |
Returns true if the camera has been initialized. | |
const cv::Mat_< double > & | intrinsicMatrix () const |
Returns the original camera matrix. | |
PinholeCameraModel () | |
PinholeCameraModel (const PinholeCameraModel &other) | |
void | project3dToPixel (const cv::Point3d &xyz, cv::Point2d &uv_rect) const ROS_DEPRECATED |
cv::Point2d | project3dToPixel (const cv::Point3d &xyz) const |
Project a 3d point to rectified pixel coordinates. | |
const cv::Mat_< double > & | projectionMatrix () const |
Returns the projection matrix. | |
void | projectPixelTo3dRay (const cv::Point2d &uv_rect, cv::Point3d &ray) const ROS_DEPRECATED |
cv::Point3d | projectPixelTo3dRay (const cv::Point2d &uv_rect) const |
Project a rectified pixel to a 3d ray. | |
cv::Rect | rawRoi () const |
The current raw ROI, as used for capture by the camera driver. | |
cv::Rect | rectifiedRoi () const |
The current rectified ROI, which best fits the raw ROI. | |
void | rectifyImage (const cv::Mat &raw, cv::Mat &rectified, int interpolation=CV_INTER_LINEAR) const |
Rectify a raw camera image. | |
void | rectifyPoint (const cv::Point2d &uv_raw, cv::Point2d &uv_rect) const ROS_DEPRECATED |
cv::Point2d | rectifyPoint (const cv::Point2d &uv_raw) const |
Compute the rectified image coordinates of a pixel in the raw image. | |
cv::Rect | rectifyRoi (const cv::Rect &roi_raw) const |
Compute the rectified ROI best fitting a raw ROI. | |
cv::Size | reducedResolution () const |
The resolution of the current rectified image. | |
const cv::Mat_< double > & | rotationMatrix () const |
Returns the rotation matrix. | |
ros::Time | stamp () const |
Get the time stamp associated with this camera model. | |
std::string | tfFrame () const |
Get the name of the camera coordinate frame in tf. | |
cv::Point2d | toFullResolution (const cv::Point2d &uv_reduced) const |
cv::Rect | toFullResolution (const cv::Rect &roi_reduced) const |
cv::Point2d | toReducedResolution (const cv::Point2d &uv_full) const |
cv::Rect | toReducedResolution (const cv::Rect &roi_full) const |
double | Tx () const |
Returns the x-translation term of the projection matrix. | |
double | Ty () const |
Returns the y-translation term of the projection matrix. | |
void | unrectifyImage (const cv::Mat &rectified, cv::Mat &raw, int interpolation=CV_INTER_LINEAR) const |
Apply camera distortion to a rectified image. | |
void | unrectifyPoint (const cv::Point2d &uv_rect, cv::Point2d &uv_raw) const ROS_DEPRECATED |
cv::Point2d | unrectifyPoint (const cv::Point2d &uv_rect) const |
Compute the raw image coordinates of a pixel in the rectified image. | |
cv::Rect | unrectifyRoi (const cv::Rect &roi_rect) const |
Compute the raw ROI best fitting a rectified ROI. | |
uint32_t | width () const ROS_DEPRECATED |
Returns the image width. | |
Protected Member Functions | |
void | initRectificationMaps () const |
Protected Attributes | |
boost::shared_ptr< Cache > | cache_ |
sensor_msgs::CameraInfo | cam_info_ |
cv::Mat_< double > | D_ |
cv::Mat_< double > | K_ |
cv::Mat_< double > | K_full_ |
cv::Mat_< double > | P_ |
cv::Mat_< double > | P_full_ |
cv::Mat_< double > | R_ |
Friends | |
class | StereoCameraModel |
Simplifies interpreting images geometrically using the parameters from sensor_msgs/CameraInfo.
Definition at line 22 of file pinhole_camera_model.h.
Definition at line 32 of file pinhole_camera_model.cpp.
image_geometry::PinholeCameraModel::PinholeCameraModel | ( | const PinholeCameraModel & | other | ) |
Definition at line 36 of file pinhole_camera_model.cpp.
uint32_t image_geometry::PinholeCameraModel::binningX | ( | ) | const [inline] |
Returns the number of columns in each bin.
Definition at line 319 of file pinhole_camera_model.h.
uint32_t image_geometry::PinholeCameraModel::binningY | ( | ) | const [inline] |
Returns the number of rows in each bin.
Definition at line 320 of file pinhole_camera_model.h.
double image_geometry::PinholeCameraModel::cx | ( | ) | const [inline] |
Returns the x coordinate of the optical center.
Definition at line 312 of file pinhole_camera_model.h.
double image_geometry::PinholeCameraModel::cy | ( | ) | const [inline] |
Returns the y coordinate of the optical center.
Definition at line 313 of file pinhole_camera_model.h.
const cv::Mat_< double > & image_geometry::PinholeCameraModel::distortionCoeffs | ( | ) | const [inline] |
Returns the distortion coefficients.
Definition at line 304 of file pinhole_camera_model.h.
bool image_geometry::PinholeCameraModel::fromCameraInfo | ( | const sensor_msgs::CameraInfo & | msg | ) |
Set the camera parameters from the sensor_msgs/CameraInfo message.
Definition at line 64 of file pinhole_camera_model.cpp.
bool image_geometry::PinholeCameraModel::fromCameraInfo | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) |
Set the camera parameters from the sensor_msgs/CameraInfo message.
Definition at line 161 of file pinhole_camera_model.cpp.
const cv::Mat_< double > & image_geometry::PinholeCameraModel::fullIntrinsicMatrix | ( | ) | const [inline] |
Returns the original camera matrix for full resolution.
Definition at line 307 of file pinhole_camera_model.h.
const cv::Mat_< double > & image_geometry::PinholeCameraModel::fullProjectionMatrix | ( | ) | const [inline] |
Returns the projection matrix for full resolution.
Definition at line 308 of file pinhole_camera_model.h.
cv::Size image_geometry::PinholeCameraModel::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.
Definition at line 171 of file pinhole_camera_model.cpp.
double image_geometry::PinholeCameraModel::fx | ( | ) | const [inline] |
Returns the focal length (pixels) in x direction of the rectified image.
Definition at line 310 of file pinhole_camera_model.h.
double image_geometry::PinholeCameraModel::fy | ( | ) | const [inline] |
Returns the focal length (pixels) in y direction of the rectified image.
Definition at line 311 of file pinhole_camera_model.h.
double image_geometry::PinholeCameraModel::getDeltaU | ( | double | deltaX, |
double | Z | ||
) | const [inline] |
Compute delta u, given Z and delta X in Cartesian space.
For given Z, this is the inverse of getDeltaX().
deltaX | Delta X, in Cartesian space |
Z | Z (depth), in Cartesian space |
Definition at line 322 of file pinhole_camera_model.h.
double image_geometry::PinholeCameraModel::getDeltaV | ( | double | deltaY, |
double | Z | ||
) | const [inline] |
Compute delta v, given Z and delta Y in Cartesian space.
For given Z, this is the inverse of getDeltaY().
deltaY | Delta Y, in Cartesian space |
Z | Z (depth), in Cartesian space |
Definition at line 328 of file pinhole_camera_model.h.
double image_geometry::PinholeCameraModel::getDeltaX | ( | double | deltaU, |
double | Z | ||
) | const [inline] |
Compute delta X, given Z in Cartesian space and delta u in pixels.
For given Z, this is the inverse of getDeltaU().
deltaU | Delta u, in pixels |
Z | Z (depth), in Cartesian space |
Definition at line 334 of file pinhole_camera_model.h.
double image_geometry::PinholeCameraModel::getDeltaY | ( | double | deltaV, |
double | Z | ||
) | const [inline] |
Compute delta Y, given Z in Cartesian space and delta v in pixels.
For given Z, this is the inverse of getDeltaV().
deltaV | Delta v, in pixels |
Z | Z (depth), in Cartesian space |
Definition at line 340 of file pinhole_camera_model.h.
uint32_t image_geometry::PinholeCameraModel::height | ( | ) | const [inline] |
Returns the image height.
Definition at line 316 of file pinhole_camera_model.h.
bool image_geometry::PinholeCameraModel::initialized | ( | ) | const [inline] |
Returns true if the camera has been initialized.
Definition at line 272 of file pinhole_camera_model.h.
void image_geometry::PinholeCameraModel::initRectificationMaps | ( | ) | const [protected] |
Definition at line 394 of file pinhole_camera_model.cpp.
const cv::Mat_< double > & image_geometry::PinholeCameraModel::intrinsicMatrix | ( | ) | const [inline] |
Returns the original camera matrix.
Definition at line 303 of file pinhole_camera_model.h.
void image_geometry::PinholeCameraModel::project3dToPixel | ( | const cv::Point3d & | xyz, |
cv::Point2d & | uv_rect | ||
) | const |
Definition at line 166 of file pinhole_camera_model.cpp.
cv::Point2d image_geometry::PinholeCameraModel::project3dToPixel | ( | const cv::Point3d & | xyz | ) | const |
Project a 3d point to rectified pixel coordinates.
This is the inverse of projectPixelTo3dRay().
xyz | 3d point in the camera coordinate frame |
Definition at line 240 of file pinhole_camera_model.cpp.
const cv::Mat_< double > & image_geometry::PinholeCameraModel::projectionMatrix | ( | ) | const [inline] |
Returns the projection matrix.
Definition at line 306 of file pinhole_camera_model.h.
void image_geometry::PinholeCameraModel::projectPixelTo3dRay | ( | const cv::Point2d & | uv_rect, |
cv::Point3d & | ray | ||
) | const |
Definition at line 254 of file pinhole_camera_model.cpp.
cv::Point3d image_geometry::PinholeCameraModel::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.
uv_rect | Rectified pixel coordinates |
Definition at line 259 of file pinhole_camera_model.cpp.
cv::Rect image_geometry::PinholeCameraModel::rawRoi | ( | ) | const |
The current raw ROI, as used for capture by the camera driver.
Definition at line 217 of file pinhole_camera_model.cpp.
cv::Rect image_geometry::PinholeCameraModel::rectifiedRoi | ( | ) | const |
The current rectified ROI, which best fits the raw ROI.
Definition at line 225 of file pinhole_camera_model.cpp.
void image_geometry::PinholeCameraModel::rectifyImage | ( | const cv::Mat & | raw, |
cv::Mat & | rectified, | ||
int | interpolation = CV_INTER_LINEAR |
||
) | const |
Rectify a raw camera image.
Definition at line 270 of file pinhole_camera_model.cpp.
void image_geometry::PinholeCameraModel::rectifyPoint | ( | const cv::Point2d & | uv_raw, |
cv::Point2d & | uv_rect | ||
) | const |
Definition at line 302 of file pinhole_camera_model.cpp.
cv::Point2d image_geometry::PinholeCameraModel::rectifyPoint | ( | const cv::Point2d & | uv_raw | ) | const |
Compute the rectified image coordinates of a pixel in the raw image.
Definition at line 307 of file pinhole_camera_model.cpp.
cv::Rect image_geometry::PinholeCameraModel::rectifyRoi | ( | const cv::Rect & | roi_raw | ) | const |
Compute the rectified ROI best fitting a raw ROI.
Definition at line 352 of file pinhole_camera_model.cpp.
cv::Size image_geometry::PinholeCameraModel::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().
Definition at line 177 of file pinhole_camera_model.cpp.
const cv::Mat_< double > & image_geometry::PinholeCameraModel::rotationMatrix | ( | ) | const [inline] |
Returns the rotation matrix.
Definition at line 305 of file pinhole_camera_model.h.
ros::Time image_geometry::PinholeCameraModel::stamp | ( | ) | const [inline] |
Get the time stamp associated with this camera model.
Definition at line 297 of file pinhole_camera_model.h.
std::string image_geometry::PinholeCameraModel::tfFrame | ( | ) | const [inline] |
Get the name of the camera coordinate frame in tf.
Definition at line 291 of file pinhole_camera_model.h.
cv::Point2d image_geometry::PinholeCameraModel::toFullResolution | ( | const cv::Point2d & | uv_reduced | ) | const |
Definition at line 185 of file pinhole_camera_model.cpp.
cv::Rect image_geometry::PinholeCameraModel::toFullResolution | ( | const cv::Rect & | roi_reduced | ) | const |
Definition at line 192 of file pinhole_camera_model.cpp.
cv::Point2d image_geometry::PinholeCameraModel::toReducedResolution | ( | const cv::Point2d & | uv_full | ) | const |
Definition at line 201 of file pinhole_camera_model.cpp.
cv::Rect image_geometry::PinholeCameraModel::toReducedResolution | ( | const cv::Rect & | roi_full | ) | const |
Definition at line 208 of file pinhole_camera_model.cpp.
double image_geometry::PinholeCameraModel::Tx | ( | ) | const [inline] |
Returns the x-translation term of the projection matrix.
Definition at line 314 of file pinhole_camera_model.h.
double image_geometry::PinholeCameraModel::Ty | ( | ) | const [inline] |
Returns the y-translation term of the projection matrix.
Definition at line 315 of file pinhole_camera_model.h.
void image_geometry::PinholeCameraModel::unrectifyImage | ( | const cv::Mat & | rectified, |
cv::Mat & | raw, | ||
int | interpolation = CV_INTER_LINEAR |
||
) | const |
Apply camera distortion to a rectified image.
Definition at line 288 of file pinhole_camera_model.cpp.
void image_geometry::PinholeCameraModel::unrectifyPoint | ( | const cv::Point2d & | uv_rect, |
cv::Point2d & | uv_raw | ||
) | const |
Definition at line 325 of file pinhole_camera_model.cpp.
cv::Point2d image_geometry::PinholeCameraModel::unrectifyPoint | ( | const cv::Point2d & | uv_rect | ) | const |
Compute the raw image coordinates of a pixel in the rectified image.
Definition at line 330 of file pinhole_camera_model.cpp.
cv::Rect image_geometry::PinholeCameraModel::unrectifyRoi | ( | const cv::Rect & | roi_rect | ) | const |
Compute the raw ROI best fitting a rectified ROI.
Definition at line 373 of file pinhole_camera_model.cpp.
uint32_t image_geometry::PinholeCameraModel::width | ( | ) | const [inline] |
Returns the image width.
Definition at line 317 of file pinhole_camera_model.h.
friend class StereoCameraModel [friend] |
Definition at line 286 of file pinhole_camera_model.h.
boost::shared_ptr<Cache> image_geometry::PinholeCameraModel::cache_ [protected] |
Definition at line 281 of file pinhole_camera_model.h.
sensor_msgs::CameraInfo image_geometry::PinholeCameraModel::cam_info_ [protected] |
Definition at line 275 of file pinhole_camera_model.h.
cv::Mat_<double> image_geometry::PinholeCameraModel::D_ [protected] |
Definition at line 276 of file pinhole_camera_model.h.
cv::Mat_<double> image_geometry::PinholeCameraModel::K_ [protected] |
Definition at line 277 of file pinhole_camera_model.h.
cv::Mat_<double> image_geometry::PinholeCameraModel::K_full_ [protected] |
Definition at line 278 of file pinhole_camera_model.h.
cv::Mat_<double> image_geometry::PinholeCameraModel::P_ [protected] |
Definition at line 277 of file pinhole_camera_model.h.
cv::Mat_<double> image_geometry::PinholeCameraModel::P_full_ [protected] |
Definition at line 278 of file pinhole_camera_model.h.
cv::Mat_<double> image_geometry::PinholeCameraModel::R_ [protected] |
Definition at line 276 of file pinhole_camera_model.h.