00001 #ifndef IMAGE_GEOMETRY_PINHOLE_CAMERA_MODEL_H
00002 #define IMAGE_GEOMETRY_PINHOLE_CAMERA_MODEL_H
00003
00004 #include <sensor_msgs/CameraInfo.h>
00005 #include <opencv/cv.h>
00006 #include <stdexcept>
00007
00008 namespace image_geometry {
00009
00010 class Exception : public std::runtime_error
00011 {
00012 public:
00013 Exception(const std::string& description) : std::runtime_error(description) {}
00014 };
00015
00020 class PinholeCameraModel
00021 {
00022 public:
00023
00024 PinholeCameraModel();
00025
00026 PinholeCameraModel(const PinholeCameraModel& other);
00027
00031 bool fromCameraInfo(const sensor_msgs::CameraInfo& msg);
00032
00036 bool fromCameraInfo(const sensor_msgs::CameraInfoConstPtr& msg);
00037
00041 std::string tfFrame() const;
00042
00046 ros::Time stamp() const;
00047
00054 cv::Size fullResolution() const;
00055
00063 cv::Size reducedResolution() const;
00064
00065 cv::Point2d toFullResolution(const cv::Point2d& uv_reduced) const;
00066
00067 cv::Rect toFullResolution(const cv::Rect& roi_reduced) const;
00068
00069 cv::Point2d toReducedResolution(const cv::Point2d& uv_full) const;
00070
00071 cv::Rect toReducedResolution(const cv::Rect& roi_full) const;
00072
00076 cv::Rect rawRoi() const;
00077
00081 cv::Rect rectifiedRoi() const;
00082
00084 void project3dToPixel(const cv::Point3d& xyz, cv::Point2d& uv_rect) const ROS_DEPRECATED;
00085
00094 cv::Point2d project3dToPixel(const cv::Point3d& xyz) const;
00095
00096 void projectPixelTo3dRay(const cv::Point2d& uv_rect, cv::Point3d& ray) const ROS_DEPRECATED;
00097
00109 cv::Point3d projectPixelTo3dRay(const cv::Point2d& uv_rect) const;
00110
00114 void rectifyImage(const cv::Mat& raw, cv::Mat& rectified,
00115 int interpolation = CV_INTER_LINEAR) const;
00116
00120 void unrectifyImage(const cv::Mat& rectified, cv::Mat& raw,
00121 int interpolation = CV_INTER_LINEAR) const;
00122
00123 void rectifyPoint(const cv::Point2d& uv_raw, cv::Point2d& uv_rect) const ROS_DEPRECATED;
00124
00128 cv::Point2d rectifyPoint(const cv::Point2d& uv_raw) const;
00129
00130 void unrectifyPoint(const cv::Point2d& uv_rect, cv::Point2d& uv_raw) const ROS_DEPRECATED;
00131
00135 cv::Point2d unrectifyPoint(const cv::Point2d& uv_rect) const;
00136
00140 cv::Rect rectifyRoi(const cv::Rect& roi_raw) const;
00141
00145 cv::Rect unrectifyRoi(const cv::Rect& roi_rect) const;
00146
00150 const cv::Mat_<double>& intrinsicMatrix() const;
00151
00155 const cv::Mat_<double>& distortionCoeffs() const;
00156
00160 const cv::Mat_<double>& rotationMatrix() const;
00161
00165 const cv::Mat_<double>& projectionMatrix() const;
00166
00170 const cv::Mat_<double>& fullIntrinsicMatrix() const;
00171
00175 const cv::Mat_<double>& fullProjectionMatrix() const;
00176
00180 double fx() const;
00181
00185 double fy() const;
00186
00190 double cx() const;
00191
00195 double cy() const;
00196
00200 double Tx() const;
00201
00205 double Ty() const;
00206
00210 uint32_t height() const ROS_DEPRECATED;
00211
00215 uint32_t width() const ROS_DEPRECATED;
00216
00220 uint32_t binningX() const;
00221
00225 uint32_t binningY() const;
00226
00235 double getDeltaU(double deltaX, double Z) const;
00236
00245 double getDeltaV(double deltaY, double Z) const;
00246
00255 double getDeltaX(double deltaU, double Z) const;
00256
00265 double getDeltaY(double deltaV, double Z) const;
00266
00267 protected:
00268 sensor_msgs::CameraInfo cam_info_;
00269 cv::Mat_<double> D_, R_;
00270 cv::Mat_<double> K_, P_;
00271 cv::Mat_<double> K_full_, P_full_;
00272
00273
00274 struct Cache;
00275 boost::shared_ptr<Cache> cache_;
00276
00277 void initRectificationMaps() const;
00278
00279 bool initialized() const { return cache_; }
00280
00281 friend class StereoCameraModel;
00282 };
00283
00284
00285
00286 inline std::string PinholeCameraModel::tfFrame() const
00287 {
00288 assert( initialized() );
00289 return cam_info_.header.frame_id;
00290 }
00291
00292 inline ros::Time PinholeCameraModel::stamp() const
00293 {
00294 assert( initialized() );
00295 return cam_info_.header.stamp;
00296 }
00297
00298 inline const cv::Mat_<double>& PinholeCameraModel::intrinsicMatrix() const { return K_; }
00299 inline const cv::Mat_<double>& PinholeCameraModel::distortionCoeffs() const { return D_; }
00300 inline const cv::Mat_<double>& PinholeCameraModel::rotationMatrix() const { return R_; }
00301 inline const cv::Mat_<double>& PinholeCameraModel::projectionMatrix() const { return P_; }
00302 inline const cv::Mat_<double>& PinholeCameraModel::fullIntrinsicMatrix() const { return K_full_; }
00303 inline const cv::Mat_<double>& PinholeCameraModel::fullProjectionMatrix() const { return P_full_; }
00304
00305 inline double PinholeCameraModel::fx() const { return P_(0,0); }
00306 inline double PinholeCameraModel::fy() const { return P_(1,1); }
00307 inline double PinholeCameraModel::cx() const { return P_(0,2); }
00308 inline double PinholeCameraModel::cy() const { return P_(1,2); }
00309 inline double PinholeCameraModel::Tx() const { return P_(0,3); }
00310 inline double PinholeCameraModel::Ty() const { return P_(1,3); }
00311 inline uint32_t PinholeCameraModel::height() const { return cam_info_.height; }
00312 inline uint32_t PinholeCameraModel::width() const { return cam_info_.width; }
00313
00314 inline uint32_t PinholeCameraModel::binningX() const { return cam_info_.binning_x; }
00315 inline uint32_t PinholeCameraModel::binningY() const { return cam_info_.binning_y; }
00316
00317 inline double PinholeCameraModel::getDeltaU(double deltaX, double Z) const
00318 {
00319 assert( initialized() );
00320 return fx() * deltaX / Z;
00321 }
00322
00323 inline double PinholeCameraModel::getDeltaV(double deltaY, double Z) const
00324 {
00325 assert( initialized() );
00326 return fy() * deltaY / Z;
00327 }
00328
00329 inline double PinholeCameraModel::getDeltaX(double deltaU, double Z) const
00330 {
00331 assert( initialized() );
00332 return Z * deltaU / fx();
00333 }
00334
00335 inline double PinholeCameraModel::getDeltaY(double deltaV, double Z) const
00336 {
00337 assert( initialized() );
00338 return Z * deltaV / fy();
00339 }
00340
00341 }
00342
00343 #endif