00001 #include "image_geometry/pinhole_camera_model.h"
00002 #include <sensor_msgs/distortion_models.h>
00003 #include <boost/make_shared.hpp>
00004
00005 namespace image_geometry {
00006
00007 enum DistortionState { NONE, CALIBRATED, UNKNOWN };
00008
00009 struct PinholeCameraModel::Cache
00010 {
00011 DistortionState distortion_state;
00012
00013 cv::Mat_<double> K_binned, P_binned;
00014
00015 mutable bool full_maps_dirty;
00016 mutable cv::Mat full_map1, full_map2;
00017
00018 mutable bool reduced_maps_dirty;
00019 mutable cv::Mat reduced_map1, reduced_map2;
00020
00021 mutable bool rectified_roi_dirty;
00022 mutable cv::Rect rectified_roi;
00023
00024 Cache()
00025 : full_maps_dirty(true),
00026 reduced_maps_dirty(true),
00027 rectified_roi_dirty(true)
00028 {
00029 }
00030 };
00031
00032 PinholeCameraModel::PinholeCameraModel()
00033 {
00034 }
00035
00036 PinholeCameraModel::PinholeCameraModel(const PinholeCameraModel& other)
00037 {
00038 if (other.initialized())
00039 fromCameraInfo(other.cam_info_);
00040 }
00041
00042
00043 template<typename T>
00044 bool update(const T& new_val, T& my_val)
00045 {
00046 if (my_val == new_val)
00047 return false;
00048 my_val = new_val;
00049 return true;
00050 }
00051
00052
00053 template<typename MatT>
00054 bool updateMat(const MatT& new_mat, MatT& my_mat, cv::Mat_<double>& cv_mat, int rows, int cols)
00055 {
00056 if (my_mat == new_mat)
00057 return false;
00058 my_mat = new_mat;
00059
00060 cv_mat = (my_mat.size() == 0) ? cv::Mat_<double>() : cv::Mat_<double>(rows, cols, &my_mat[0]);
00061 return true;
00062 }
00063
00064 bool PinholeCameraModel::fromCameraInfo(const sensor_msgs::CameraInfo& msg)
00065 {
00066
00067 if (!cache_)
00068 cache_ = boost::make_shared<Cache>();
00069
00070
00071 uint32_t binning_x = msg.binning_x ? msg.binning_x : 1;
00072 uint32_t binning_y = msg.binning_y ? msg.binning_y : 1;
00073
00074
00075 sensor_msgs::RegionOfInterest roi = msg.roi;
00076 if (roi.x_offset == 0 && roi.y_offset == 0 && roi.width == 0 && roi.height == 0) {
00077 roi.width = msg.width;
00078 roi.height = msg.height;
00079 }
00080
00081
00082 cam_info_.header = msg.header;
00083
00084
00085
00086 bool &full_dirty = cache_->full_maps_dirty;
00087 full_dirty |= update(msg.height, cam_info_.height);
00088 full_dirty |= update(msg.width, cam_info_.width);
00089 full_dirty |= update(msg.distortion_model, cam_info_.distortion_model);
00090 full_dirty |= updateMat(msg.D, cam_info_.D, D_, 1, msg.D.size());
00091 full_dirty |= updateMat(msg.K, cam_info_.K, K_full_, 3, 3);
00092 full_dirty |= updateMat(msg.R, cam_info_.R, R_, 3, 3);
00093 full_dirty |= updateMat(msg.P, cam_info_.P, P_full_, 3, 4);
00094 full_dirty |= update(binning_x, cam_info_.binning_x);
00095 full_dirty |= update(binning_y, cam_info_.binning_y);
00096
00097
00098
00099 bool &reduced_dirty = cache_->reduced_maps_dirty;
00100 reduced_dirty = full_dirty;
00101 reduced_dirty |= update(roi.x_offset, cam_info_.roi.x_offset);
00102 reduced_dirty |= update(roi.y_offset, cam_info_.roi.y_offset);
00103 reduced_dirty |= update(roi.height, cam_info_.roi.height);
00104 reduced_dirty |= update(roi.width, cam_info_.roi.width);
00105 reduced_dirty |= update(roi.do_rectify, cam_info_.roi.do_rectify);
00106
00107 cache_->rectified_roi_dirty = reduced_dirty;
00108
00109
00110 if (cam_info_.distortion_model == sensor_msgs::distortion_models::PLUMB_BOB ||
00111 cam_info_.distortion_model == sensor_msgs::distortion_models::RATIONAL_POLYNOMIAL) {
00112 cache_->distortion_state = (cam_info_.D[0] == 0.0) ? NONE : CALIBRATED;
00113 }
00114 else
00115 cache_->distortion_state = UNKNOWN;
00116
00117
00119 bool adjust_binning = (binning_x > 1) || (binning_y > 1);
00120 bool adjust_roi = (roi.x_offset != 0) || (roi.y_offset != 0);
00121
00122 if (!adjust_binning && !adjust_roi) {
00123 K_ = K_full_;
00124 P_ = P_full_;
00125 }
00126 else {
00127 K_full_.copyTo(K_);
00128 P_full_.copyTo(P_);
00129
00130
00131 if (adjust_roi) {
00132
00134 K_(0,2) -= roi.x_offset;
00135 K_(1,2) -= roi.y_offset;
00136 P_(0,2) -= roi.x_offset;
00137 P_(1,2) -= roi.y_offset;
00138 }
00139
00140 if (binning_x > 1) {
00141 double scale_x = 1.0 / binning_x;
00142 K_(0,0) *= scale_x;
00143 K_(0,2) *= scale_x;
00144 P_(0,0) *= scale_x;
00145 P_(0,2) *= scale_x;
00146 P_(0,3) *= scale_x;
00147 }
00148 if (binning_y > 1) {
00149 double scale_y = 1.0 / binning_y;
00150 K_(1,1) *= scale_y;
00151 K_(1,2) *= scale_y;
00152 P_(1,1) *= scale_y;
00153 P_(1,2) *= scale_y;
00154 P_(1,3) *= scale_y;
00155 }
00156 }
00157
00158 return reduced_dirty;
00159 }
00160
00161 bool PinholeCameraModel::fromCameraInfo(const sensor_msgs::CameraInfoConstPtr& msg)
00162 {
00163 return fromCameraInfo(*msg);
00164 }
00165
00166 void PinholeCameraModel::project3dToPixel(const cv::Point3d& xyz, cv::Point2d& uv_rect) const
00167 {
00168 uv_rect = project3dToPixel(xyz);
00169 }
00170
00171 cv::Size PinholeCameraModel::fullResolution() const
00172 {
00173 assert( initialized() );
00174 return cv::Size(cam_info_.width, cam_info_.height);
00175 }
00176
00177 cv::Size PinholeCameraModel::reducedResolution() const
00178 {
00179 assert( initialized() );
00180
00181 cv::Rect roi = rectifiedRoi();
00182 return cv::Size(roi.width / binningX(), roi.height / binningY());
00183 }
00184
00185 cv::Point2d PinholeCameraModel::toFullResolution(const cv::Point2d& uv_reduced) const
00186 {
00187 cv::Rect roi = rectifiedRoi();
00188 return cv::Point2d(uv_reduced.x * binningX() + roi.x,
00189 uv_reduced.y * binningY() + roi.y);
00190 }
00191
00192 cv::Rect PinholeCameraModel::toFullResolution(const cv::Rect& roi_reduced) const
00193 {
00194 cv::Rect roi = rectifiedRoi();
00195 return cv::Rect(roi_reduced.x * binningX() + roi.x,
00196 roi_reduced.y * binningY() + roi.y,
00197 roi_reduced.width * binningX(),
00198 roi_reduced.height * binningY());
00199 }
00200
00201 cv::Point2d PinholeCameraModel::toReducedResolution(const cv::Point2d& uv_full) const
00202 {
00203 cv::Rect roi = rectifiedRoi();
00204 return cv::Point2d((uv_full.x - roi.x) / binningX(),
00205 (uv_full.y - roi.y) / binningY());
00206 }
00207
00208 cv::Rect PinholeCameraModel::toReducedResolution(const cv::Rect& roi_full) const
00209 {
00210 cv::Rect roi = rectifiedRoi();
00211 return cv::Rect((roi_full.x - roi.x) / binningX(),
00212 (roi_full.y - roi.y) / binningY(),
00213 roi_full.width / binningX(),
00214 roi_full.height / binningY());
00215 }
00216
00217 cv::Rect PinholeCameraModel::rawRoi() const
00218 {
00219 assert( initialized() );
00220
00221 return cv::Rect(cam_info_.roi.x_offset, cam_info_.roi.y_offset,
00222 cam_info_.roi.width, cam_info_.roi.height);
00223 }
00224
00225 cv::Rect PinholeCameraModel::rectifiedRoi() const
00226 {
00227 assert( initialized() );
00228
00229 if (cache_->rectified_roi_dirty)
00230 {
00231 if (!cam_info_.roi.do_rectify)
00232 cache_->rectified_roi = rawRoi();
00233 else
00234 cache_->rectified_roi = rectifyRoi(rawRoi());
00235 cache_->rectified_roi_dirty = false;
00236 }
00237 return cache_->rectified_roi;
00238 }
00239
00240 cv::Point2d PinholeCameraModel::project3dToPixel(const cv::Point3d& xyz) const
00241 {
00242 assert( initialized() );
00243 assert(P_(2, 3) == 0.0);
00244
00245
00246
00247
00248 cv::Point2d uv_rect;
00249 uv_rect.x = (fx()*xyz.x + Tx()) / xyz.z + cx();
00250 uv_rect.y = (fy()*xyz.y + Ty()) / xyz.z + cy();
00251 return uv_rect;
00252 }
00253
00254 void PinholeCameraModel::projectPixelTo3dRay(const cv::Point2d& uv_rect, cv::Point3d& ray) const
00255 {
00256 ray = projectPixelTo3dRay(uv_rect);
00257 }
00258
00259 cv::Point3d PinholeCameraModel::projectPixelTo3dRay(const cv::Point2d& uv_rect) const
00260 {
00261 assert( initialized() );
00262
00263 cv::Point3d ray;
00264 ray.x = (uv_rect.x - cx() - Tx()) / fx();
00265 ray.y = (uv_rect.y - cy() - Ty()) / fy();
00266 ray.z = 1.0;
00267 return ray;
00268 }
00269
00270 void PinholeCameraModel::rectifyImage(const cv::Mat& raw, cv::Mat& rectified, int interpolation) const
00271 {
00272 assert( initialized() );
00273
00274 switch (cache_->distortion_state) {
00275 case NONE:
00276 raw.copyTo(rectified);
00277 break;
00278 case CALIBRATED:
00279 initRectificationMaps();
00280 cv::remap(raw, rectified, cache_->reduced_map1, cache_->reduced_map2, interpolation);
00281 break;
00282 default:
00283 assert(cache_->distortion_state == UNKNOWN);
00284 throw Exception("Cannot call rectifyImage when distortion is unknown.");
00285 }
00286 }
00287
00288 void PinholeCameraModel::unrectifyImage(const cv::Mat& rectified, cv::Mat& raw, int interpolation) const
00289 {
00290 assert( initialized() );
00291
00292 throw Exception("PinholeCameraModel::unrectifyImage is unimplemented.");
00294
00295
00296
00297
00298
00299
00300 }
00301
00302 void PinholeCameraModel::rectifyPoint(const cv::Point2d& uv_raw, cv::Point2d& uv_rect) const
00303 {
00304 uv_rect = rectifyPoint(uv_raw);
00305 }
00306
00307 cv::Point2d PinholeCameraModel::rectifyPoint(const cv::Point2d& uv_raw) const
00308 {
00309 assert( initialized() );
00310
00311 if (cache_->distortion_state == NONE)
00312 return uv_raw;
00313 if (cache_->distortion_state == UNKNOWN)
00314 throw Exception("Cannot call rectifyPoint when distortion is unknown.");
00315 assert(cache_->distortion_state == CALIBRATED);
00316
00318 cv::Point2f raw32 = uv_raw, rect32;
00319 const cv::Mat src_pt(1, 1, CV_32FC2, &raw32.x);
00320 cv::Mat dst_pt(1, 1, CV_32FC2, &rect32.x);
00321 cv::undistortPoints(src_pt, dst_pt, K_, D_, R_, P_);
00322 return rect32;
00323 }
00324
00325 void PinholeCameraModel::unrectifyPoint(const cv::Point2d& uv_rect, cv::Point2d& uv_raw) const
00326 {
00327 uv_raw = unrectifyPoint(uv_rect);
00328 }
00329
00330 cv::Point2d PinholeCameraModel::unrectifyPoint(const cv::Point2d& uv_rect) const
00331 {
00332 assert( initialized() );
00333
00334 if (cache_->distortion_state == NONE)
00335 return uv_rect;
00336 if (cache_->distortion_state == UNKNOWN)
00337 throw Exception("Cannot call unrectifyPoint when distortion is unknown.");
00338 assert(cache_->distortion_state == CALIBRATED);
00339
00342
00343
00344
00345
00346
00347
00348
00349 double x = (uv_rect.x - cx() - Tx()) / fx();
00350 double y = (uv_rect.y - cy() - Ty()) / fy();
00351
00352 double X = R_(0,0)*x + R_(1,0)*y + R_(2,0);
00353 double Y = R_(0,1)*x + R_(1,1)*y + R_(2,1);
00354 double W = R_(0,2)*x + R_(1,2)*y + R_(2,2);
00355
00356 double xp = X / W;
00357 double yp = Y / W;
00358
00359
00360
00361 double r2 = xp*xp + yp*yp;
00362 double r4 = r2*r2;
00363 double r6 = r4*r2;
00364 double a1 = 2*xp*yp;
00365 double k1 = D_(0,0), k2 = D_(0,1), p1 = D_(0,2), p2 = D_(0,3), k3 = D_(0,4);
00366 double barrel_correction = 1 + k1*r2 + k2*r4 + k3*r6;
00367 if (D_.cols == 8)
00368 barrel_correction /= (1.0 + D_(0,5)*r2 + D_(0,6)*r4 + D_(0,7)*r6);
00369 double xpp = xp*barrel_correction + p1*a1 + p2*(r2+2*(xp*xp));
00370 double ypp = yp*barrel_correction + p1*(r2+2*(yp*yp)) + p2*a1;
00371
00372
00373
00374 return cv::Point2d(xpp*K_(0,0) + K_(0,2), ypp*K_(1,1) + K_(1,2));
00375 }
00376
00377 cv::Rect PinholeCameraModel::rectifyRoi(const cv::Rect& roi_raw) const
00378 {
00379 assert( initialized() );
00380
00382
00383
00384 cv::Point2d rect_tl = rectifyPoint(cv::Point2d(roi_raw.x, roi_raw.y));
00385 cv::Point2d rect_tr = rectifyPoint(cv::Point2d(roi_raw.x + roi_raw.width, roi_raw.y));
00386 cv::Point2d rect_br = rectifyPoint(cv::Point2d(roi_raw.x + roi_raw.width,
00387 roi_raw.y + roi_raw.height));
00388 cv::Point2d rect_bl = rectifyPoint(cv::Point2d(roi_raw.x, roi_raw.y + roi_raw.height));
00389
00390 cv::Point roi_tl(std::ceil (std::min(rect_tl.x, rect_bl.x)),
00391 std::ceil (std::min(rect_tl.y, rect_tr.y)));
00392 cv::Point roi_br(std::floor(std::max(rect_tr.x, rect_br.x)),
00393 std::floor(std::max(rect_bl.y, rect_br.y)));
00394
00395 return cv::Rect(roi_tl.x, roi_tl.y, roi_br.x - roi_tl.x, roi_br.y - roi_tl.y);
00396 }
00397
00398 cv::Rect PinholeCameraModel::unrectifyRoi(const cv::Rect& roi_rect) const
00399 {
00400 assert( initialized() );
00401
00403
00404
00405 cv::Point2d raw_tl = unrectifyPoint(cv::Point2d(roi_rect.x, roi_rect.y));
00406 cv::Point2d raw_tr = unrectifyPoint(cv::Point2d(roi_rect.x + roi_rect.width, roi_rect.y));
00407 cv::Point2d raw_br = unrectifyPoint(cv::Point2d(roi_rect.x + roi_rect.width,
00408 roi_rect.y + roi_rect.height));
00409 cv::Point2d raw_bl = unrectifyPoint(cv::Point2d(roi_rect.x, roi_rect.y + roi_rect.height));
00410
00411 cv::Point roi_tl(std::floor(std::min(raw_tl.x, raw_bl.x)),
00412 std::floor(std::min(raw_tl.y, raw_tr.y)));
00413 cv::Point roi_br(std::ceil (std::max(raw_tr.x, raw_br.x)),
00414 std::ceil (std::max(raw_bl.y, raw_br.y)));
00415
00416 return cv::Rect(roi_tl.x, roi_tl.y, roi_br.x - roi_tl.x, roi_br.y - roi_tl.y);
00417 }
00418
00419 void PinholeCameraModel::initRectificationMaps() const
00420 {
00423
00424 if (cache_->full_maps_dirty) {
00425
00427 cv::Size binned_resolution = fullResolution();
00428 binned_resolution.width /= binningX();
00429 binned_resolution.height /= binningY();
00430
00431 cv::Mat_<double> K_binned, P_binned;
00432 if (binningX() == 1 && binningY() == 1) {
00433 K_binned = K_full_;
00434 P_binned = P_full_;
00435 }
00436 else {
00437 K_full_.copyTo(K_binned);
00438 P_full_.copyTo(P_binned);
00439 if (binningX() > 1) {
00440 double scale_x = 1.0 / binningX();
00441 K_binned(0,0) *= scale_x;
00442 K_binned(0,2) *= scale_x;
00443 P_binned(0,0) *= scale_x;
00444 P_binned(0,2) *= scale_x;
00445 P_binned(0,3) *= scale_x;
00446 }
00447 if (binningY() > 1) {
00448 double scale_y = 1.0 / binningY();
00449 K_binned(1,1) *= scale_y;
00450 K_binned(1,2) *= scale_y;
00451 P_binned(1,1) *= scale_y;
00452 P_binned(1,2) *= scale_y;
00453 P_binned(1,3) *= scale_y;
00454 }
00455 }
00456
00457
00458 cv::initUndistortRectifyMap(K_binned, D_, R_, P_binned, binned_resolution,
00459 CV_16SC2, cache_->full_map1, cache_->full_map2);
00460 cache_->full_maps_dirty = false;
00461 }
00462
00463 if (cache_->reduced_maps_dirty) {
00465 cv::Rect roi(cam_info_.roi.x_offset, cam_info_.roi.y_offset,
00466 cam_info_.roi.width, cam_info_.roi.height);
00467 if (roi.x != 0 || roi.y != 0 ||
00468 roi.height != (int)cam_info_.height ||
00469 roi.width != (int)cam_info_.width) {
00470
00471
00472
00473 roi.x /= binningX();
00474 roi.y /= binningY();
00475 roi.width /= binningX();
00476 roi.height /= binningY();
00477 cache_->reduced_map1 = cache_->full_map1(roi) - cv::Scalar(roi.x, roi.y);
00478 cache_->reduced_map2 = cache_->full_map2(roi);
00479 }
00480 else {
00481
00482 cache_->reduced_map1 = cache_->full_map1;
00483 cache_->reduced_map2 = cache_->full_map2;
00484 }
00485 cache_->reduced_maps_dirty = false;
00486 }
00487 }
00488
00489 }