optimizer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2014-2015 Fetch Robotics Inc.
4  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Michael Ferguson
20 
22 
23 #include <ceres/ceres.h>
24 
25 #include <urdf/model.h>
27 #include <robot_calibration_msgs/CalibrationData.h>
28 
38 #include <boost/shared_ptr.hpp>
39 #include <string>
40 #include <map>
41 
42 namespace robot_calibration
43 {
44 
46  num_params_(0),
47  num_residuals_(0)
48 {
50  std::cerr << "Failed to parse URDF." << std::endl;
51 
52  // Maintain consistent offset parser so we hold onto offsets
53  offsets_.reset(new CalibrationOffsetParser());
54 
55  // Create a mesh loader
56  mesh_loader_.reset(new MeshLoader(model_));
57 }
58 
60 {
61 }
62 
64  std::vector<robot_calibration_msgs::CalibrationData> data,
65  bool progress_to_stdout)
66 {
67  // Load KDL from URDF
69  {
70  std::cerr << "Failed to construct KDL tree" << std::endl;
71  return -1;
72  }
73 
74  // Create models
75  for (size_t i = 0; i < params.models.size(); ++i)
76  {
77  if (params.models[i].type == "chain")
78  {
79  ROS_INFO_STREAM("Creating chain '" << params.models[i].name << "' from " <<
80  params.base_link << " to " <<
81  params.models[i].params["frame"]);
82  ChainModel* model = new ChainModel(params.models[i].name, tree_, params.base_link, params.models[i].params["frame"]);
83  models_[params.models[i].name] = model;
84  }
85  else if (params.models[i].type == "camera3d")
86  {
87  ROS_INFO_STREAM("Creating camera3d '" << params.models[i].name << "' in frame " <<
88  params.models[i].params["frame"]);
89  std::string param_name = params.models[i].params["param_name"];
90  if (param_name == "")
91  {
92  // Default to same name as sensor
93  param_name = params.models[i].name;
94  }
95  Camera3dModel* model = new Camera3dModel(params.models[i].name, param_name, tree_, params.base_link, params.models[i].params["frame"]);
96  models_[params.models[i].name] = model;
97  }
98  else
99  {
100  // ERROR unknown
101  }
102  }
103 
104  // Reset which parameters are free (offset values are retained)
105  offsets_->reset();
106 
107  // Setup parameters to calibrate
108  for (size_t i = 0; i < params.free_params.size(); ++i)
109  {
110  offsets_->add(params.free_params[i]);
111  }
112  for (size_t i = 0; i < params.free_frames.size(); ++i)
113  {
114  offsets_->addFrame(params.free_frames[i].name,
115  params.free_frames[i].x,
116  params.free_frames[i].y,
117  params.free_frames[i].z,
118  params.free_frames[i].roll,
119  params.free_frames[i].pitch,
120  params.free_frames[i].yaw);
121  }
122  for (size_t i = 0; i < params.free_frames_initial_values.size(); ++i)
123  {
124  if (!offsets_->setFrame(params.free_frames_initial_values[i].name,
125  params.free_frames_initial_values[i].x,
126  params.free_frames_initial_values[i].y,
127  params.free_frames_initial_values[i].z,
128  params.free_frames_initial_values[i].roll,
129  params.free_frames_initial_values[i].pitch,
130  params.free_frames_initial_values[i].yaw))
131  {
132  ROS_ERROR_STREAM("Error setting initial value for " <<
133  params.free_frames_initial_values[i].name);
134  }
135  }
136 
137  // Allocate space
138  double* free_params = new double[offsets_->size()];
139  offsets_->initialize(free_params);
140 
141  // Houston, we have a problem...
142  ceres::Problem* problem = new ceres::Problem();
143 
144  // For each sample of data:
145  for (size_t i = 0; i < data.size(); ++i)
146  {
147  for (size_t j = 0; j < params.error_blocks.size(); ++j)
148  {
149  if (params.error_blocks[j].type == "chain3d_to_chain3d")
150  {
151  // This error block can process data generated by the LedFinder,
152  // CheckboardFinder, or any other finder that can sample the pose
153  // of one or more data points that are connected at a constant offset
154  // from a link a kinematic chain (the "arm").
155  std::string a_name = static_cast<std::string>(params.error_blocks[j].params["model_a"]);
156  std::string b_name = static_cast<std::string>(params.error_blocks[j].params["model_b"]);
157 
158  // Do some basic error checking for bad params
159  if (a_name == "" || b_name == "" || a_name == b_name)
160  {
161  ROS_ERROR("chain3d_to_chain3d improperly configured: model_a and model_b params must be set!");
162  return 0;
163  }
164 
165  // Check that this sample has the required features/observations
166  if (!hasSensor(data[i], a_name) || !hasSensor(data[i], b_name))
167  continue;
168 
169  // Create the block
170  ceres::CostFunction * cost = Chain3dToChain3d::Create(models_[a_name],
171  models_[b_name],
172  offsets_.get(),
173  data[i]);
174 
175  // Output initial error
176  if (progress_to_stdout)
177  {
178  double ** params = new double*[1];
179  params[0] = free_params;
180  double * residuals = new double[cost->num_residuals()];
181 
182  cost->Evaluate(params, residuals, NULL);
183 
184  std::cout << "INITIAL COST (" << i << ")" << std::endl << " x: ";
185  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals() / 3); ++k)
186  std::cout << " " << std::setw(10) << std::fixed << residuals[(3*k + 0)];
187  std::cout << std::endl << " y: ";
188  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals() / 3); ++k)
189  std::cout << " " << std::setw(10) << std::fixed << residuals[(3*k + 1)];
190  std::cout << std::endl << " z: ";
191  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals() / 3); ++k)
192  std::cout << " " << std::setw(10) << std::fixed << residuals[(3*k + 2)];
193  std::cout << std::endl << std::endl;
194  }
195 
196  problem->AddResidualBlock(cost,
197  NULL, // squared loss
198  free_params);
199  }
200  else if (params.error_blocks[j].type == "chain3d_to_plane")
201  {
202  // This error block can process data generated by the PlaneFinder
203  std::string chain_name = static_cast<std::string>(params.error_blocks[j].params["model_a"]);
204 
205  // Do some basic error checking for bad params
206  if (chain_name == "")
207  {
208  ROS_ERROR("chain3d_to_plane improperly configured: model_a param must be set!");
209  return 0;
210  }
211 
212  // Check that this sample has the required features/observations
213  if (!hasSensor(data[i], chain_name))
214  continue;
215 
216  // Create the block
217  ceres::CostFunction * cost =
218  Chain3dToPlane::Create(models_[chain_name],
219  offsets_.get(),
220  data[i],
221  params.getParam(params.error_blocks[j], "a", 0.0),
222  params.getParam(params.error_blocks[j], "b", 0.0),
223  params.getParam(params.error_blocks[j], "c", 1.0),
224  params.getParam(params.error_blocks[j], "d", 0.0),
225  params.getParam(params.error_blocks[j], "scale", 1.0));
226 
227  // Output initial error
228  if (progress_to_stdout)
229  {
230  double ** params = new double*[1];
231  params[0] = free_params;
232  double * residuals = new double[cost->num_residuals()];
233 
234  cost->Evaluate(params, residuals, NULL);
235 
236  std::cout << "INITIAL COST (" << i << ")" << std::endl << " d: ";
237  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals()); ++k)
238  std::cout << " " << std::setw(10) << std::fixed << residuals[(k)];
239  std::cout << std::endl << std::endl;
240  }
241 
242  problem->AddResidualBlock(cost,
243  NULL /* squared loss */,
244  free_params);
245  }
246  else if (params.error_blocks[j].type == "chain3d_to_mesh")
247  {
248  // This error block can process data generated by the RobotFinder
249  std::string chain_name = static_cast<std::string>(params.error_blocks[j].params["model_a"]);
250 
251  // Do some basic error checking for bad params
252  if (chain_name == "")
253  {
254  ROS_ERROR("chain3d_to_mesh improperly configured: model_a param must be set!");
255  return 0;
256  }
257 
258  // Check that this sample has the required features/observations
259  if (!hasSensor(data[i], chain_name))
260  continue;
261 
262  // Get the mesh
263  std::string link_name = params.getParam(params.error_blocks[j], "link_name", std::string(""));
264  MeshPtr mesh = mesh_loader_->getCollisionMesh(link_name);
265  if (!mesh)
266  {
267  ROS_ERROR("chain3d_to_mesh improperly configured: cannot load mesh for %s", link_name.c_str());
268  return 0;
269  }
270 
271  // Create the block
272  ceres::CostFunction * cost =
273  Chain3dToMesh::Create(models_[chain_name],
274  offsets_.get(),
275  data[i],
276  mesh);
277 
278  // Output initial error
279  if (progress_to_stdout)
280  {
281  double ** params = new double*[1];
282  params[0] = free_params;
283  double * residuals = new double[cost->num_residuals()];
284 
285  cost->Evaluate(params, residuals, NULL);
286 
287  std::cout << "INITIAL COST (" << i << ")" << std::endl << " d: ";
288  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals()); ++k)
289  std::cout << " " << std::setw(10) << std::fixed << residuals[(k)];
290  std::cout << std::endl << std::endl;
291  }
292 
293  problem->AddResidualBlock(cost,
294  NULL /* squared loss */,
295  free_params);
296 
297 
298  }
299  else if (params.error_blocks[j].type == "plane_to_plane")
300  {
301  // This error block can process data generated by the PlaneFinder,
302  // CheckerboardFinder, or any other finder that returns a series of
303  // planar points.
304  std::string a_name = static_cast<std::string>(params.error_blocks[j].params["model_a"]);
305  std::string b_name = static_cast<std::string>(params.error_blocks[j].params["model_b"]);
306 
307  // Do some basic error checking for bad params
308  if (a_name == "" || b_name == "" || a_name == b_name)
309  {
310  ROS_ERROR("plane_to_plane improperly configured: model_a and model_a params must be set!");
311  return 0;
312  }
313 
314  // Check that this sample has the required features/observations
315  if (!hasSensor(data[i], a_name) || !hasSensor(data[i], b_name))
316  continue;
317 
318  // Create the block
319  ceres::CostFunction * cost =
321  models_[b_name],
322  offsets_.get(),
323  data[i],
324  params.getParam(params.error_blocks[j], "scale_normal", 1.0),
325  params.getParam(params.error_blocks[j], "scale_offset", 1.0));
326 
327  // Output initial error
328  if (progress_to_stdout)
329  {
330  double ** params = new double*[1];
331  params[0] = free_params;
332  double * residuals = new double[cost->num_residuals()];
333 
334  cost->Evaluate(params, residuals, NULL);
335  std::cout << "INITIAL COST (" << i << ")" << std::endl << " a: ";
336  std::cout << " " << std::setw(10) << std::fixed << residuals[0];
337  std::cout << std::endl << " b: ";
338  std::cout << " " << std::setw(10) << std::fixed << residuals[1];
339  std::cout << std::endl << " c: ";
340  std::cout << " " << std::setw(10) << std::fixed << residuals[2];
341  std::cout << std::endl << " d: ";
342  std::cout << " " << std::setw(10) << std::fixed << residuals[3];
343  std::cout << std::endl << std::endl;
344  }
345 
346  problem->AddResidualBlock(cost,
347  NULL, // squared loss
348  free_params);
349  }
350  else if (params.error_blocks[j].type == "outrageous")
351  {
352  // Outrageous error block requires no particular sensors, add to every sample
353  problem->AddResidualBlock(
355  static_cast<std::string>(params.error_blocks[j].params["param"]),
356  params.getParam(params.error_blocks[j], "joint_scale", 1.0),
357  params.getParam(params.error_blocks[j], "position_scale", 1.0),
358  params.getParam(params.error_blocks[j], "rotation_scale", 1.0)),
359  NULL, // squared loss
360  free_params);
361  }
362  else
363  {
364  ROS_ERROR_STREAM("Unknown error block: " << params.error_blocks[j].type);
365  return 0;
366  }
367  }
368  }
369 
370  // Setup the actual optimization
371  ceres::Solver::Options options;
372  options.use_nonmonotonic_steps = true;
373  options.function_tolerance = 1e-10;
374  options.linear_solver_type = ceres::DENSE_QR;
375  options.max_num_iterations = params.max_num_iterations;
376  options.minimizer_progress_to_stdout = progress_to_stdout;
377 
378  if (progress_to_stdout)
379  std::cout << "\nSolver output:" << std::endl;
380  summary_.reset(new ceres::Solver::Summary());
381  ceres::Solve(options, problem, summary_.get());
382  if (progress_to_stdout)
383  std::cout << "\n" << summary_->BriefReport() << std::endl;
384 
385  // Save some status
386  num_params_ = problem->NumParameters();
387  num_residuals_ = problem->NumResiduals();
388 
389  // Note: the error blocks will be managed by scoped_ptr in cost functor
390  // which takes ownership, and so we do not need to delete them here
391 
392  // Done with our free params
393  delete[] free_params;
394  delete problem;
395 
396  return 0;
397 }
398 
399 std::vector<std::string> Optimizer::getCameraNames()
400 {
401  std::vector<std::string> camera_names;
402  for (auto it = models_.begin(); it != models_.end(); ++it)
403  {
404  if (it->second->getType() == "Camera3dModel")
405  {
406  camera_names.push_back(it->first);
407  }
408  }
409  return camera_names;
410 }
411 
412 } // namespace robot_calibration
chain3d_to_plane_error.h
robot_calibration::PlaneToPlaneError::Create
static ceres::CostFunction * Create(ChainModel *model_a, ChainModel *model_b, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double scale_normal, double scale_offset)
Helper factory function to create a new error block. Parameters are described in the class constructo...
Definition: plane_to_plane_error.h:117
robot_calibration::Optimizer::model_
urdf::Model model_
Definition: optimizer.h:91
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
robot_calibration::Optimizer::summary_
boost::shared_ptr< ceres::Solver::Summary > summary_
Definition: optimizer.h:101
robot_calibration::CalibrationOffsetParser
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
Definition: offset_parser.h:33
robot_calibration::OptimizationParams::free_frames_initial_values
std::vector< FreeFrameInitialValue > free_frames_initial_values
Definition: optimization_params.h:63
robot_calibration::OptimizationParams::getParam
T getParam(Params &params, const std::string &name, T default_value)
Definition: optimization_params.h:74
offset_parser.h
robot_calibration::Optimizer::~Optimizer
virtual ~Optimizer()
Definition: optimizer.cpp:59
robot_calibration::OptimizationParams::free_params
std::vector< std::string > free_params
Definition: optimization_params.h:61
robot_calibration::Optimizer::models_
std::map< std::string, ChainModel * > models_
Definition: optimizer.h:98
robot_description
std::string robot_description
Definition: calibration_offset_parser_tests.cpp:7
kdl_parser::treeFromUrdfModel
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
robot_calibration::Optimizer::num_params_
int num_params_
Definition: optimizer.h:103
robot_calibration::Optimizer::getCameraNames
std::vector< std::string > getCameraNames()
Get the names of all camera models.
Definition: optimizer.cpp:399
robot_calibration::Optimizer::Optimizer
Optimizer(const std::string &robot_description)
Standard constructor.
Definition: optimizer.cpp:45
robot_calibration::Optimizer::optimize
int optimize(OptimizationParams &params, std::vector< robot_calibration_msgs::CalibrationData > data, bool progress_to_stdout=false)
Run optimization.
Definition: optimizer.cpp:63
chain3d_to_chain3d_error.h
robot_calibration::MeshPtr
std::shared_ptr< shapes::Mesh > MeshPtr
Definition: mesh_loader.h:32
model.h
robot_calibration::MeshLoader
Definition: mesh_loader.h:34
plane_to_plane_error.h
ROS_ERROR
#define ROS_ERROR(...)
chain3d_to_mesh_error.h
robot_calibration::OptimizationParams::base_link
std::string base_link
Definition: optimization_params.h:60
chain.h
urdf::Model::initString
URDF_EXPORT bool initString(const std::string &xmlstring)
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
robot_calibration::Chain3dToChain3d::Create
static ceres::CostFunction * Create(ChainModel *a_model, ChainModel *b_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data)
Helper factory function to create a new error block. Parameters are described in the class constructo...
Definition: chain3d_to_chain3d_error.h:102
robot_calibration::Optimizer::mesh_loader_
boost::shared_ptr< MeshLoader > mesh_loader_
Definition: optimizer.h:96
robot_calibration::OptimizationParams::free_frames
std::vector< FreeFrameParams > free_frames
Definition: optimization_params.h:62
robot_calibration::Chain3dToMesh::Create
static ceres::CostFunction * Create(ChainModel *a_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, MeshPtr mesh)
Helper factory function to create a new error block. Parameters are described in the class constructo...
Definition: chain3d_to_mesh_error.h:135
kdl_parser.hpp
robot_calibration::OptimizationParams
Class to hold parameters for optimization.
Definition: optimization_params.h:29
outrageous_error.h
robot_calibration::Optimizer::tree_
KDL::Tree tree_
Definition: optimizer.h:94
robot_calibration::Chain3dToPlane::Create
static ceres::CostFunction * Create(ChainModel *a_model, CalibrationOffsetParser *offsets, robot_calibration_msgs::CalibrationData &data, double a, double b, double c, double d, double scale)
Helper factory function to create a new error block. Parameters are described in the class constructo...
Definition: chain3d_to_plane_error.h:103
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::OptimizationParams::models
std::vector< Params > models
Definition: optimization_params.h:64
optimizer.h
robot_calibration::OptimizationParams::error_blocks
std::vector< Params > error_blocks
Definition: optimization_params.h:65
robot_calibration::Optimizer::offsets_
boost::shared_ptr< CalibrationOffsetParser > offsets_
Definition: optimizer.h:100
robot_calibration::OutrageousError::Create
static ceres::CostFunction * Create(CalibrationOffsetParser *offsets, std::string name, double joint_scaling, double position_scaling, double rotation_scaling)
Helper factory function to create a new error block.
Definition: outrageous_error.h:101
robot_calibration::OptimizationParams::max_num_iterations
int max_num_iterations
Definition: optimization_params.h:68
robot_calibration::Camera3dModel
Model of a camera on a kinematic chain.
Definition: camera3d.h:31
calibration_data_helpers.h
camera3d.h
robot_calibration::hasSensor
bool hasSensor(const robot_calibration_msgs::CalibrationData &msg, const std::string &sensor)
Determine if a sample of data has an observation from the desired sensor.
Definition: calibration_data_helpers.h:47
robot_calibration::Optimizer::num_residuals_
int num_residuals_
Definition: optimizer.h:103
robot_calibration::ChainModel
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
Definition: chain.h:107


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01