optimizer.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2014-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 #include <robot_calibration/ceres/optimizer.h>
00021 
00022 #include <ceres/ceres.h>
00023 
00024 #include <urdf/model.h>
00025 #include <kdl_parser/kdl_parser.hpp>
00026 #include <robot_calibration_msgs/CalibrationData.h>
00027 
00028 #include <robot_calibration/calibration_offset_parser.h>
00029 #include <robot_calibration/ceres/camera3d_to_arm_error.h>
00030 #include <robot_calibration/ceres/ground_plane_error.h>
00031 #include <robot_calibration/ceres/data_functions.h>
00032 #include <robot_calibration/ceres/outrageous_error.h>
00033 #include <robot_calibration/models/camera3d.h>
00034 #include <robot_calibration/models/chain.h>
00035 #include <boost/shared_ptr.hpp>
00036 #include <string>
00037 #include <map>
00038 
00039 namespace robot_calibration
00040 {
00041 
00042 Optimizer::Optimizer(const std::string& robot_description)
00043 {
00044   if (!model_.initString(robot_description))
00045     std::cerr << "Failed to parse URDF." << std::endl;
00046 }
00047 
00048 Optimizer::~Optimizer()
00049 {
00050 }
00051 
00052 // Determine if a sample of data has an observation from
00053 // the desired sensor
00054 bool hasSensor(
00055   const robot_calibration_msgs::CalibrationData& msg,
00056   const std::string& sensor)
00057 {
00058   for (size_t i = 0; i < msg.observations.size(); i++)
00059   {
00060     if (msg.observations[i].sensor_name == sensor)
00061       return true;
00062   }
00063   return false;
00064 }
00065 
00066 int Optimizer::optimize(OptimizationParams& params,
00067                         std::vector<robot_calibration_msgs::CalibrationData> data,
00068                         bool progress_to_stdout)
00069 {
00070   // Load KDL from URDF
00071   if (!kdl_parser::treeFromUrdfModel(model_, tree_))
00072   {
00073     std::cerr << "Failed to construct KDL tree" << std::endl;
00074     return -1;
00075   }
00076 
00077   // Create models
00078   for (size_t i = 0; i < params.models.size(); ++i)
00079   {
00080     if (params.models[i].type == "chain")
00081     {
00082       ROS_INFO_STREAM("Creating chain '" << params.models[i].name << "' from " <<
00083                                             params.base_link << " to " <<
00084                                             params.models[i].params["frame"]);
00085       ChainModel* model = new ChainModel(params.models[i].name, tree_, params.base_link, params.models[i].params["frame"]);
00086       models_[params.models[i].name] = model;
00087     }
00088     else if (params.models[i].type == "camera3d")
00089     {
00090       ROS_INFO_STREAM("Creating camera3d '" << params.models[i].name << "' in frame " <<
00091                                                params.models[i].params["frame"]);
00092       Camera3dModel* model = new Camera3dModel(params.models[i].name, tree_, params.base_link, params.models[i].params["frame"]);
00093       models_[params.models[i].name] = model;
00094     }
00095     else
00096     {
00097       // ERROR unknown
00098     }
00099   }
00100 
00101   // Setup  parameters to calibrate
00102   offsets_.reset(new CalibrationOffsetParser());
00103   for (size_t i = 0; i < params.free_params.size(); ++i)
00104   {
00105     offsets_->add(params.free_params[i]);
00106   }
00107   for (size_t i = 0; i < params.free_frames.size(); ++i)
00108   {
00109     offsets_->addFrame(params.free_frames[i].name,
00110                        params.free_frames[i].x,
00111                        params.free_frames[i].y,
00112                        params.free_frames[i].z,
00113                        params.free_frames[i].roll,
00114                        params.free_frames[i].pitch,
00115                        params.free_frames[i].yaw);
00116   }
00117 
00118   // Allocate space
00119   double* free_params = new double[offsets_->size()];
00120   for (int i = 0; i < offsets_->size(); ++i)
00121     free_params[i] = 0.0;
00122 
00123   double z_ = 0;
00124   // Houston, we have a problem...
00125   ceres::Problem* problem = new ceres::Problem();
00126 
00127   // For each sample of data:
00128   for (size_t i = 0; i < data.size(); ++i)
00129   {
00130     for (size_t j = 0; j < params.error_blocks.size(); ++j)
00131     {
00132       if (params.error_blocks[j].type == "camera3d_to_arm")
00133       {
00134         // This error block can process data generated by the LedFinder,
00135         // CheckboardFinder, or any other finder that can sample the pose
00136         // of one or more data points that are connected at a constant offset
00137         // from a link a kinematic chain (the "arm").
00138 
00139         std::string camera_name = static_cast<std::string>(params.error_blocks[j].params["camera"]);
00140         std::string arm_name = static_cast<std::string>(params.error_blocks[j].params["arm"]);
00141 
00142         // Check that this sample has the required features/observations
00143         if (!hasSensor(data[i], camera_name) || !hasSensor(data[i], arm_name))
00144           continue;
00145 
00146         // Create the block
00147         ceres::CostFunction * cost = Camera3dToArmError::Create(
00148             dynamic_cast<Camera3dModel*>(models_[camera_name]),
00149             models_[arm_name],
00150             offsets_.get(), data[i]);
00151 
00152         int index = -1;
00153         for (size_t k = 0; k < data[i].observations.size(); k++)
00154         {
00155            if (data[i].observations[k].sensor_name == camera_name)
00156           {
00157             index = k;
00158             break;
00159           }
00160         }
00161 
00162         if (index == -1)
00163         {
00164           std::cerr << "Sensor name doesn't exist" << std::endl;
00165           return 0;
00166         }
00167 
00168         if (progress_to_stdout)
00169         {
00170           double ** params = new double*[1];
00171           params[0] = free_params;
00172           double * residuals = new double[data[i].observations[index].features.size() * 3];  // TODO: should check that all features are same length?
00173 
00174           cost->Evaluate(params, residuals, NULL);
00175           std::cout << "INITIAL COST (" << i << ")" << std::endl << "  x: ";
00176           for (size_t k = 0; k < data[i].observations[index].features.size(); ++k)
00177             std::cout << "  " << std::setw(10) << std::fixed << residuals[(3*k + 0)];
00178           std::cout << std::endl << "  y: ";
00179           for (size_t k = 0; k < data[i].observations[index].features.size(); ++k)
00180             std::cout << "  " << std::setw(10) << std::fixed << residuals[(3*k + 1)];
00181           std::cout << std::endl << "  z: ";
00182           for (size_t k = 0; k < data[i].observations[index].features.size(); ++k)
00183             std::cout << "  " << std::setw(10) << std::fixed << residuals[(3*k + 2)];
00184           std::cout << std::endl << std::endl;
00185         }
00186 
00187         problem->AddResidualBlock(cost,
00188                                   NULL,  // squared loss
00189                                   free_params);
00190       }
00191       else if (params.error_blocks[j].type =="camera3d_to_ground")
00192       {
00193         std::string camera_name = static_cast<std::string>(params.error_blocks[j].params["camera"]);
00194         std::string ground_name = static_cast<std::string>(params.error_blocks[j].params["ground"]);
00195 
00196         // Check that this sample has the required features/observations
00197         if (!hasSensor(data[i], camera_name) || !hasSensor(data[i], ground_name))
00198           continue;
00199 
00200         // Create the block
00201         ceres::CostFunction * cost = GroundPlaneError::Create(
00202           dynamic_cast<Camera3dModel*>(models_[camera_name]),
00203           z_,
00204           offsets_.get(), data[i]);
00205 
00206         int index = -1;
00207         for (size_t k =0; k < data[i].observations.size(); k++)
00208         {
00209           if (data[i].observations[k].sensor_name == camera_name)
00210           {
00211             index = k;
00212             break;
00213           }
00214         }
00215         
00216         if(index == -1)
00217         {
00218           std::cerr << "Sensor name doesn't exist" << std::endl;
00219           return 0;
00220         }
00221 
00222         if (progress_to_stdout)
00223         {
00224           double ** params = new double*[1];
00225           params[0] = free_params;
00226           double * residuals = new double[data[i].observations[index].features.size()];
00227 
00228           cost->Evaluate(params, residuals, NULL);
00229 
00230           std::cout << std::endl << "  z: ";
00231           for (size_t k = 0; k < data[i].observations[index].features.size(); ++k)
00232             std::cout << "  " << std::setw(10) << std::fixed << residuals[(k)];
00233           std::cout << std::endl << std::endl;
00234         }
00235 
00236         problem->AddResidualBlock(cost,
00237                                   NULL /* squared loss */,
00238                                   free_params);
00239       }
00240       if (params.error_blocks[j].type == "camera_to_camera")
00241       {
00242         // This error block can process data generated by the PlaneFinder,
00243         // CheckerboardFinder, or any other finder that can sample the pose
00244         // of one or more data points in two camera frames.
00245         // This also finds the a plane that fits the points and minimizes
00246         // over the normals
00247         std::string camera1_name = static_cast<std::string>(params.error_blocks[j].params["camera1"]);
00248         std::string camera2_name = static_cast<std::string>(params.error_blocks[j].params["camera2"]);
00249 
00250         // Create the block
00251         ceres::CostFunction * cost = CameraToCameraError::Create(
00252             dynamic_cast<Camera3dModel*>(models_[camera1_name]),
00253             dynamic_cast<Camera3dModel*>(models_[camera2_name]),
00254             offsets_.get(), data[i]);
00255 
00256         int index_1 = -1;
00257         int index_2 = -1;
00258 
00259         for (size_t k = 0; k < data[i].observations.size(); k++)
00260         {
00261           if (data[i].observations[k].sensor_name == camera1_name)
00262           {
00263             index_1 = k;
00264           }
00265           if (data[i].observations[k].sensor_name == camera2_name)
00266           {
00267             index_2 = k;
00268           }
00269           if (index_1 == -1 && index_2 == -1)
00270           {
00271             break;
00272           }
00273         }
00274 
00275         if (index_1 == -1 || index_2 == -1)
00276         {
00277           std::cerr << "Sensor name doesn't exist" << std::endl;
00278           return 0;
00279         }
00280 
00281         if (progress_to_stdout)
00282         {
00283           double ** params = new double*[1];
00284           params[0] = free_params;
00285           double * residuals = new double[3];
00286 
00287           cost->Evaluate(params, residuals, NULL);
00288           std::cout << "INITIAL COST (" << i << ")" << std::endl << "  x: ";
00289             std::cout << "  " << std::setw(10) << std::fixed << residuals[0];
00290           std::cout << std::endl << "  y: ";
00291             std::cout << "  " << std::setw(10) << std::fixed << residuals[1];
00292           std::cout << std::endl << "  z: ";
00293             std::cout << "  " << std::setw(10) << std::fixed << residuals[2];
00294           std::cout << std::endl << std::endl;
00295         }
00296 
00297         problem->AddResidualBlock(cost,
00298                                   NULL,  // squared loss
00299                                   free_params);
00300       }
00301       else if (params.error_blocks[j].type == "outrageous")
00302       {
00303         // Outrageous error block requires no particular sensors, add to every sample
00304         problem->AddResidualBlock(
00305           OutrageousError::Create(offsets_.get(),
00306                                   params.error_blocks[j].name,
00307                                   static_cast<double>(params.error_blocks[j].params["joint_scale"]),
00308                                   static_cast<double>(params.error_blocks[j].params["position_scale"]),
00309                                   static_cast<double>(params.error_blocks[j].params["rotation_scale"])),
00310           NULL, // squared loss
00311           free_params);
00312       }
00313       else
00314       {
00315         // ERROR unknown
00316       }
00317     }
00318   }
00319 
00320   // Setup the actual optimization
00321   ceres::Solver::Options options;
00322   options.use_nonmonotonic_steps = true;
00323   options.function_tolerance = 1e-10;
00324   options.linear_solver_type = ceres::DENSE_QR;
00325   options.max_num_iterations = 1000;
00326   options.minimizer_progress_to_stdout = progress_to_stdout;
00327   //  options.use_nonmonotonic_steps = true;
00328 
00329   if (progress_to_stdout)
00330     std::cout << "\nSolver output:" << std::endl;
00331   summary_.reset(new ceres::Solver::Summary());
00332   ceres::Solve(options, problem, summary_.get());
00333   if (progress_to_stdout)
00334     std::cout << "\n" << summary_->BriefReport() << std::endl;
00335 
00336   // TODO output stats
00337   /*if (progress_to_stdout)
00338     {
00339     CalibrationOffsetParser no_offsets;
00340     offsets_->update(free_params);
00341     for (size_t i = 0; i < data.size(); ++i)
00342     {
00343     std::cout << "Sample " << i << std::endl;
00344     printSimpleDistanceError(arm_model_, camera_model_, &no_offsets, offsets_, data[i]);
00345     printComparePoints(arm_model_, camera_model_, &no_offsets, offsets_, data[i]);
00346     }
00347     }*/
00348 
00349   // Note: the error blocks will be managed by scoped_ptr in cost functor
00350   //       which takes ownership, and so we do not need to delete them here
00351 
00352   // Done with our free params
00353   delete[] free_params;
00354   delete problem;
00355 
00356   return 0;
00357 }
00358 
00359 }  // namespace robot_calibration


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