camera3d_to_arm_error.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2015 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 required 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: Michael Ferguson
00019 
00020 #ifndef ROBOT_CALIBRATION_CERES_CAMERA3D_TO_ARM_ERROR_H
00021 #define ROBOT_CALIBRATION_CERES_CAMERA3D_TO_ARM_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 namespace robot_calibration
00031 {
00032 
00036 struct Camera3dToArmError
00037 {
00045   Camera3dToArmError(Camera3dModel* camera_model,
00046                      ChainModel* arm_model,
00047                      CalibrationOffsetParser* offsets,
00048                      robot_calibration_msgs::CalibrationData& data)
00049   {
00050     camera_model_ = camera_model;
00051     arm_model_ = arm_model;
00052     offsets_ = offsets;
00053     data_ = data;
00054   }
00055 
00056   virtual ~Camera3dToArmError() {}
00057 
00063   bool operator()(double const * const * free_params,
00064                   double* residuals) const
00065   {
00066     // Update calibration offsets based on free params
00067     offsets_->update(free_params[0]);
00068 
00069     // Project the camera observations
00070     std::vector<geometry_msgs::PointStamped> camera_pts =
00071         camera_model_->project(data_, *offsets_);
00072 
00073     // Project the arm estimation
00074     std::vector<geometry_msgs::PointStamped> arm_pts =
00075         arm_model_->project(data_, *offsets_);
00076 
00077     if (camera_pts.size() != arm_pts.size())
00078     {
00079       std::cerr << "Camera observation does not match arm estimation in size." << std::endl;
00080       return false;
00081     }
00082 
00083     // Compute residuals
00084     for (size_t i = 0; i < camera_pts.size(); ++i)
00085     {
00086       if (camera_pts[i].header.frame_id != arm_pts[i].header.frame_id)
00087         std::cerr << "Projected observation frame_id does not match projected estimate." << std::endl;
00088       residuals[(3*i)+0] = camera_pts[i].point.x - arm_pts[i].point.x;
00089       residuals[(3*i)+1] = camera_pts[i].point.y - arm_pts[i].point.y;
00090       residuals[(3*i)+2] = camera_pts[i].point.z - arm_pts[i].point.z;
00091     }
00092 
00093     return true;  // always return true
00094   }
00095 
00104   static ceres::CostFunction* Create(Camera3dModel* camera_model,
00105                                      ChainModel* arm_model,
00106                                      CalibrationOffsetParser* offsets,
00107                                      robot_calibration_msgs::CalibrationData& data)
00108   {
00109     int index = -1;
00110     for (size_t k = 0; k < data.observations.size() ; k++)
00111     {
00112       if ( data.observations[k].sensor_name == camera_model->name())
00113       {
00114         index = k;
00115         break;
00116       }
00117     }
00118     
00119     if (index == -1)
00120     {
00121       std::cerr << "Sensor name doesn't match any of the existing finders" << std::endl;
00122       return 0;
00123     }
00124 
00125     ceres::DynamicNumericDiffCostFunction<Camera3dToArmError> * func;
00126     func = new ceres::DynamicNumericDiffCostFunction<Camera3dToArmError>(
00127                     new Camera3dToArmError(camera_model, arm_model, offsets, data));
00128     func->AddParameterBlock(offsets->size());
00129     func->SetNumResiduals(data.observations[index].features.size() * 3);
00130 
00131     return static_cast<ceres::CostFunction*>(func);
00132   }
00133 
00134   Camera3dModel * camera_model_;
00135   ChainModel * arm_model_;
00136   CalibrationOffsetParser * offsets_;
00137   robot_calibration_msgs::CalibrationData data_;
00138 };
00139 
00140 }  // namespace robot_calibration
00141 
00142 #endif  // ROBOT_CALIBRATION_CERES_CAMERA3D_TO_ARM_ERROR_H


robot_calibration
Author(s): Michael Ferguson
autogenerated on Sat May 20 2017 02:35:31