camera_to_camera_error.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2015-2017 Fetch Robotics Inc.
00003  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
00004  *
00005  * Licensed under the Apache License, Version 2.0 (the "License");
00006  * you may not use this file except in compliance with the License.
00007  * You may obtain a copy of the License at
00008  *
00009  *     http://www.apache.org/licenses/LICENSE-2.0
00010  *
00011  * Unless repts_matuired by applicable law or agreed to in writing, software
00012  * distributed under the License is distributed on an "AS IS" BASIS,
00013  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014  * See the License for the specific language governing permissions and
00015  * limitations under the License.
00016  */
00017 
00018 // Author: Niharika Arora
00019 
00020 #ifndef ROBOT_CALIBRATION_CERES_CAMERA_TO_CAMERA_ERROR_H
00021 #define ROBOT_CALIBRATION_CERES_CAMERA_TO_CAMERA_ERROR_H
00022 
00023 #include <string>
00024 #include <ceres/ceres.h>
00025 #include <robot_calibration/calibration_offset_parser.h>
00026 #include <robot_calibration/models/camera3d.h>
00027 #include <robot_calibration/models/chain.h>
00028 #include <robot_calibration_msgs/CalibrationData.h>
00029 
00030 #include <opencv2/calib3d/calib3d.hpp>
00031 #include <cv_bridge/cv_bridge.h>
00032 
00033 namespace robot_calibration
00034 {
00035 
00039 struct CameraToCameraError
00040 {
00048   CameraToCameraError(Camera3dModel *camera1_model,
00049       Camera3dModel *camera2_model,
00050       CalibrationOffsetParser *offsets,
00051       robot_calibration_msgs::CalibrationData &data)
00052   {
00053     camera1_model_ = camera1_model;
00054     camera2_model_ = camera2_model;
00055     offsets_ = offsets;
00056     data_ = data;
00057   }
00058 
00059   virtual ~CameraToCameraError()
00060   {}
00061 
00067   bool operator()(double const *const *free_params,
00068       double *residuals) const
00069   {
00070     // Update calibration offsets based on free params
00071     offsets_->update(free_params[0]);
00072 
00073     // Project the first camera observations
00074     std::vector <geometry_msgs::PointStamped> camera1_pts =
00075         camera1_model_->project(data_, *offsets_);
00076 
00077     // Project the second camera estimation
00078     std::vector <geometry_msgs::PointStamped> camera2_pts =
00079         camera2_model_->project(data_, *offsets_);
00080 
00081     // Calculate plane normals using SVD
00082     std::vector <cv::Point3f> camera1_points;
00083     std::vector <cv::Point3f> camera2_points;
00084 
00085     for (size_t i = 0; i < camera1_pts.size(); ++i)
00086     {
00087       camera1_points.push_back(cv::Point3f(camera1_pts[i].point.x, camera1_pts[i].point.y, camera1_pts[i].point.z));
00088     }
00089     for (size_t i = 0; i < camera2_pts.size(); ++i)
00090     {
00091       camera2_points.push_back(cv::Point3f(camera2_pts[i].point.x, camera2_pts[i].point.y, camera2_pts[i].point.z));
00092     }
00093 
00094     // Find the planes
00095     cv::Mat plane_1 = getPlane(camera1_points);
00096     cv::Mat plane_2 = getPlane(camera2_points);
00097 
00098     // Compute the residuals by minimizing the normals of the calculated planes
00099     residuals[0] = std::fabs(plane_1.at<float>(0, 0)) - std::fabs(plane_2.at<float>(0, 0));
00100     residuals[1] = std::fabs(plane_1.at<float>(0, 1)) - std::fabs(plane_2.at<float>(0, 1));
00101     residuals[2] = std::fabs(plane_1.at<float>(0, 2)) - std::fabs(plane_2.at<float>(0, 2));
00102 
00103     return true;  // always return true
00104   }
00105 
00114   static ceres::CostFunction *Create(Camera3dModel *camera1_model,
00115       Camera3dModel *camera2_model,
00116       CalibrationOffsetParser *offsets,
00117        robot_calibration_msgs::CalibrationData &data)
00118   {
00119     int index = -1;
00120     for (size_t k = 0; k < data.observations.size(); k++)
00121     {
00122       if (data.observations[k].sensor_name == camera2_model->name())
00123       {
00124         index = k;
00125         break;
00126       }
00127     }
00128 
00129     if (index == -1)
00130     {
00131       std::cerr << "Sensor name doesn't match any of the existing finders" << std::endl;
00132       return 0;
00133     }
00134 
00135     ceres::DynamicNumericDiffCostFunction <CameraToCameraError> *func;
00136     func = new ceres::DynamicNumericDiffCostFunction<CameraToCameraError>(
00137         new CameraToCameraError(camera1_model, camera2_model, offsets, data));
00138     func->AddParameterBlock(offsets->size());
00139     func->SetNumResiduals(3);
00140 
00141     return static_cast<ceres::CostFunction *>(func);
00142   }
00143 
00149   cv::Mat getPlane(std::vector <cv::Point3f> points) const
00150   {
00151     // Calculate centroid
00152     cv::Point3f centroid(0, 0, 0);
00153     for (size_t i = 0; i < points.size(); i++)
00154     {
00155       centroid += points.at(i);
00156     }
00157 
00158     centroid.x = centroid.x / points.size();
00159     centroid.y = centroid.y / points.size();
00160     centroid.z = centroid.z / points.size();
00161 
00162     // subtract centroid from all points
00163     cv::Mat pts_mat(points.size(), 3, CV_32F);
00164     for (size_t i = 0; i < points.size(); i++)
00165     {
00166       pts_mat.at<float>(i, 0) = points[i].x - centroid.x;
00167       pts_mat.at<float>(i, 1) = points[i].y - centroid.y;
00168       pts_mat.at<float>(i, 2) = points[i].z - centroid.z;
00169     }
00170 
00171     // SVD
00172     cv::SVD svd(pts_mat, cv::SVD::FULL_UV);
00173     cv::Mat normal = svd.vt.row(2);
00174 
00175     return normal;
00176   }
00177 
00178   Camera3dModel *camera1_model_;
00179   Camera3dModel *camera2_model_;
00180   CalibrationOffsetParser *offsets_;
00181   robot_calibration_msgs::CalibrationData data_;
00182 };
00183 
00184 }  // namespace robot_calibration
00185 
00186 #endif  // ROBOT_CALIBRATION_CERES_CAMERA_TO_CAMERA_ERROR_H


robot_calibration
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 21:54:10