outrageous_error.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2014 Unbounded Robotics Inc.
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 // Author: Michael Ferguson
00018 
00019 #ifndef ROBOT_CALIBRATION_CERES_OUTRAGEOUS_ERROR_H
00020 #define ROBOT_CALIBRATION_CERES_OUTRAGEOUS_ERROR_H
00021 
00022 #include <string>
00023 #include <ceres/ceres.h>
00024 #include <robot_calibration/calibration_offset_parser.h>
00025 #include <robot_calibration/models/chain.h>
00026 
00027 namespace robot_calibration
00028 {
00029 
00034 struct OutrageousError
00035 {
00046   OutrageousError(CalibrationOffsetParser* offsets,
00047                   std::string name,
00048                   double joint_scaling,
00049                   double position_scaling,
00050                   double rotation_scaling) :
00051       offsets_(offsets),
00052       name_(name),
00053       joint_(joint_scaling),
00054       position_(position_scaling),
00055       rotation_(rotation_scaling)
00056   {
00057   }
00058 
00059   virtual ~OutrageousError() {}
00060 
00066   bool operator()(double const * const * free_params,
00067                   double * residuals) const
00068   {
00069     // Update calibration offsets based on free params
00070     offsets_->update(free_params[0]);
00071 
00072     residuals[0] = joint_ * offsets_->get(name_);
00073     KDL::Frame f;
00074     if (offsets_->getFrame(name_, f))
00075     {
00076       residuals[1] = position_ * f.p.x();
00077       residuals[2] = position_ * f.p.y();
00078       residuals[3] = position_ * f.p.z();
00079       double x, y, z;
00080       axis_magnitude_from_rotation(f.M, x, y, z);
00081       residuals[4] = rotation_ * fabs(x);
00082       residuals[5] = rotation_ * fabs(y);
00083       residuals[6] = rotation_ * fabs(z);
00084     }
00085     else
00086     {
00087       residuals[1] = 0.0;
00088       residuals[2] = 0.0;
00089       residuals[3] = 0.0;
00090       residuals[4] = 0.0;
00091       residuals[5] = 0.0;
00092       residuals[6] = 0.0;
00093     }
00094 
00095     return true;
00096   }
00097 
00101   static ceres::CostFunction* Create(CalibrationOffsetParser* offsets,
00102                                      std::string name,
00103                                      double joint_scaling,
00104                                      double position_scaling,
00105                                      double rotation_scaling)
00106   {
00107     ceres::DynamicNumericDiffCostFunction<OutrageousError, ceres::CENTRAL> * func;
00108     func = new ceres::DynamicNumericDiffCostFunction<OutrageousError, ceres::CENTRAL>(
00109                     new OutrageousError(offsets, name, joint_scaling, position_scaling, rotation_scaling));
00110     func->AddParameterBlock(offsets->size());
00111     func->SetNumResiduals(7);  // joint + 3 position + 3 rotation
00112     return static_cast<ceres::CostFunction*>(func);
00113   }
00114 
00115   CalibrationOffsetParser * offsets_;
00116   std::string name_;
00117   double joint_;
00118   double position_;
00119   double rotation_;
00120 };
00121 
00122 }  // namespace robot_calibration
00123 
00124 #endif  // ROBOT_CALIBRATION_CERES_OUTRAGEOUS_ERROR_H


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