optimizer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 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 
34 #include <boost/shared_ptr.hpp>
35 #include <string>
36 #include <map>
37 
38 namespace robot_calibration
39 {
40 
42  num_params_(0),
43  num_residuals_(0)
44 {
45  if (!model_.initString(robot_description))
46  std::cerr << "Failed to parse URDF." << std::endl;
47 
48  // Maintain consistent offset parser so we hold onto offsets
49  offsets_.reset(new CalibrationOffsetParser());
50 }
51 
53 {
54 }
55 
57  std::vector<robot_calibration_msgs::CalibrationData> data,
58  bool progress_to_stdout)
59 {
60  // Load KDL from URDF
62  {
63  std::cerr << "Failed to construct KDL tree" << std::endl;
64  return -1;
65  }
66 
67  // Create models
68  for (size_t i = 0; i < params.models.size(); ++i)
69  {
70  if (params.models[i].type == "chain")
71  {
72  ROS_INFO_STREAM("Creating chain '" << params.models[i].name << "' from " <<
73  params.base_link << " to " <<
74  params.models[i].params["frame"]);
75  ChainModel* model = new ChainModel(params.models[i].name, tree_, params.base_link, params.models[i].params["frame"]);
76  models_[params.models[i].name] = model;
77  }
78  else if (params.models[i].type == "camera3d")
79  {
80  ROS_INFO_STREAM("Creating camera3d '" << params.models[i].name << "' in frame " <<
81  params.models[i].params["frame"]);
82  Camera3dModel* model = new Camera3dModel(params.models[i].name, tree_, params.base_link, params.models[i].params["frame"]);
83  models_[params.models[i].name] = model;
84  }
85  else
86  {
87  // ERROR unknown
88  }
89  }
90 
91  // Reset which parameters are free (offset values are retained)
92  offsets_->reset();
93 
94  // Setup parameters to calibrate
95  for (size_t i = 0; i < params.free_params.size(); ++i)
96  {
97  offsets_->add(params.free_params[i]);
98  }
99  for (size_t i = 0; i < params.free_frames.size(); ++i)
100  {
101  offsets_->addFrame(params.free_frames[i].name,
102  params.free_frames[i].x,
103  params.free_frames[i].y,
104  params.free_frames[i].z,
105  params.free_frames[i].roll,
106  params.free_frames[i].pitch,
107  params.free_frames[i].yaw);
108  }
109  for (size_t i = 0; i < params.free_frames_initial_values.size(); ++i)
110  {
111  if (!offsets_->setFrame(params.free_frames_initial_values[i].name,
112  params.free_frames_initial_values[i].x,
113  params.free_frames_initial_values[i].y,
114  params.free_frames_initial_values[i].z,
115  params.free_frames_initial_values[i].roll,
116  params.free_frames_initial_values[i].pitch,
117  params.free_frames_initial_values[i].yaw))
118  {
119  ROS_ERROR_STREAM("Error setting initial value for " <<
120  params.free_frames_initial_values[i].name);
121  }
122  }
123 
124  // Allocate space
125  double* free_params = new double[offsets_->size()];
126  offsets_->initialize(free_params);
127 
128  // Houston, we have a problem...
129  ceres::Problem* problem = new ceres::Problem();
130 
131  // For each sample of data:
132  for (size_t i = 0; i < data.size(); ++i)
133  {
134  for (size_t j = 0; j < params.error_blocks.size(); ++j)
135  {
136  if (params.error_blocks[j].type == "chain3d_to_chain3d")
137  {
138  // This error block can process data generated by the LedFinder,
139  // CheckboardFinder, or any other finder that can sample the pose
140  // of one or more data points that are connected at a constant offset
141  // from a link a kinematic chain (the "arm").
142  std::string a_name = static_cast<std::string>(params.error_blocks[j].params["model_a"]);
143  std::string b_name = static_cast<std::string>(params.error_blocks[j].params["model_b"]);
144 
145  // Do some basic error checking for bad params
146  if (a_name == "" || b_name == "" || a_name == b_name)
147  {
148  ROS_ERROR("chain3d_to_chain3d improperly configured: model_a and model_b params must be set!");
149  return 0;
150  }
151 
152  // Check that this sample has the required features/observations
153  if (!hasSensor(data[i], a_name) || !hasSensor(data[i], b_name))
154  continue;
155 
156  // Create the block
157  ceres::CostFunction * cost = Chain3dToChain3d::Create(models_[a_name],
158  models_[b_name],
159  offsets_.get(),
160  data[i]);
161 
162  // Output initial error
163  if (progress_to_stdout)
164  {
165  double ** params = new double*[1];
166  params[0] = free_params;
167  double * residuals = new double[cost->num_residuals()];
168 
169  cost->Evaluate(params, residuals, NULL);
170 
171  std::cout << "INITIAL COST (" << i << ")" << std::endl << " x: ";
172  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals() / 3); ++k)
173  std::cout << " " << std::setw(10) << std::fixed << residuals[(3*k + 0)];
174  std::cout << std::endl << " y: ";
175  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals() / 3); ++k)
176  std::cout << " " << std::setw(10) << std::fixed << residuals[(3*k + 1)];
177  std::cout << std::endl << " z: ";
178  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals() / 3); ++k)
179  std::cout << " " << std::setw(10) << std::fixed << residuals[(3*k + 2)];
180  std::cout << std::endl << std::endl;
181  }
182 
183  problem->AddResidualBlock(cost,
184  NULL, // squared loss
185  free_params);
186  }
187  else if (params.error_blocks[j].type == "chain3d_to_plane")
188  {
189  // This error block can process data generated by the PlaneFinder
190  std::string chain_name = static_cast<std::string>(params.error_blocks[j].params["model_a"]);
191 
192  // Do some basic error checking for bad params
193  if (chain_name == "")
194  {
195  ROS_ERROR("chain3d_to_plane improperly configured: model_a param must be set!");
196  return 0;
197  }
198 
199  // Check that this sample has the required features/observations
200  if (!hasSensor(data[i], chain_name))
201  continue;
202 
203  // Create the block
204  ceres::CostFunction * cost =
205  Chain3dToPlane::Create(models_[chain_name],
206  offsets_.get(),
207  data[i],
208  params.getParam(params.error_blocks[j], "a", 0.0),
209  params.getParam(params.error_blocks[j], "b", 0.0),
210  params.getParam(params.error_blocks[j], "c", 1.0),
211  params.getParam(params.error_blocks[j], "d", 0.0),
212  params.getParam(params.error_blocks[j], "scale", 1.0));
213 
214  // Output initial error
215  if (progress_to_stdout)
216  {
217  double ** params = new double*[1];
218  params[0] = free_params;
219  double * residuals = new double[cost->num_residuals()];
220 
221  cost->Evaluate(params, residuals, NULL);
222 
223  std::cout << "INITIAL COST (" << i << ")" << std::endl << " d: ";
224  for (size_t k = 0; k < static_cast<size_t>(cost->num_residuals()); ++k)
225  std::cout << " " << std::setw(10) << std::fixed << residuals[(k)];
226  std::cout << std::endl << std::endl;
227  }
228 
229  problem->AddResidualBlock(cost,
230  NULL /* squared loss */,
231  free_params);
232  }
233  else if (params.error_blocks[j].type == "plane_to_plane")
234  {
235  // This error block can process data generated by the PlaneFinder,
236  // CheckerboardFinder, or any other finder that returns a series of
237  // planar points.
238  std::string a_name = static_cast<std::string>(params.error_blocks[j].params["model_a"]);
239  std::string b_name = static_cast<std::string>(params.error_blocks[j].params["model_b"]);
240 
241  // Do some basic error checking for bad params
242  if (a_name == "" || b_name == "" || a_name == b_name)
243  {
244  ROS_ERROR("plane_to_plane improperly configured: model_a and model_a params must be set!");
245  return 0;
246  }
247 
248  // Check that this sample has the required features/observations
249  if (!hasSensor(data[i], a_name) || !hasSensor(data[i], b_name))
250  continue;
251 
252  // Create the block
253  ceres::CostFunction * cost =
255  models_[b_name],
256  offsets_.get(),
257  data[i],
258  params.getParam(params.error_blocks[j], "scale_normal", 1.0),
259  params.getParam(params.error_blocks[j], "scale_offset", 1.0));
260 
261  // Output initial error
262  if (progress_to_stdout)
263  {
264  double ** params = new double*[1];
265  params[0] = free_params;
266  double * residuals = new double[cost->num_residuals()];
267 
268  cost->Evaluate(params, residuals, NULL);
269  std::cout << "INITIAL COST (" << i << ")" << std::endl << " a: ";
270  std::cout << " " << std::setw(10) << std::fixed << residuals[0];
271  std::cout << std::endl << " b: ";
272  std::cout << " " << std::setw(10) << std::fixed << residuals[1];
273  std::cout << std::endl << " c: ";
274  std::cout << " " << std::setw(10) << std::fixed << residuals[2];
275  std::cout << std::endl << " d: ";
276  std::cout << " " << std::setw(10) << std::fixed << residuals[3];
277  std::cout << std::endl << std::endl;
278  }
279 
280  problem->AddResidualBlock(cost,
281  NULL, // squared loss
282  free_params);
283  }
284  else if (params.error_blocks[j].type == "outrageous")
285  {
286  // Outrageous error block requires no particular sensors, add to every sample
287  problem->AddResidualBlock(
289  static_cast<std::string>(params.error_blocks[j].params["param"]),
290  params.getParam(params.error_blocks[j], "joint_scale", 1.0),
291  params.getParam(params.error_blocks[j], "position_scale", 1.0),
292  params.getParam(params.error_blocks[j], "rotation_scale", 1.0)),
293  NULL, // squared loss
294  free_params);
295  }
296  else
297  {
298  ROS_ERROR_STREAM("Unknown error block: " << params.error_blocks[j].type);
299  return 0;
300  }
301  }
302  }
303 
304  // Setup the actual optimization
305  ceres::Solver::Options options;
306  options.use_nonmonotonic_steps = true;
307  options.function_tolerance = 1e-10;
308  options.linear_solver_type = ceres::DENSE_QR;
309  options.max_num_iterations = 1000;
310  options.minimizer_progress_to_stdout = progress_to_stdout;
311  // options.use_nonmonotonic_steps = true;
312 
313  if (progress_to_stdout)
314  std::cout << "\nSolver output:" << std::endl;
315  summary_.reset(new ceres::Solver::Summary());
316  ceres::Solve(options, problem, summary_.get());
317  if (progress_to_stdout)
318  std::cout << "\n" << summary_->BriefReport() << std::endl;
319 
320  // Save some status
321  num_params_ = problem->NumParameters();
322  num_residuals_ = problem->NumResiduals();
323 
324  // Note: the error blocks will be managed by scoped_ptr in cost functor
325  // which takes ownership, and so we do not need to delete them here
326 
327  // Done with our free params
328  delete[] free_params;
329  delete problem;
330 
331  return 0;
332 }
333 
334 } // namespace robot_calibration
URDF_EXPORT bool initString(const std::string &xmlstring)
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
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...
std::string robot_description
int optimize(OptimizationParams &params, std::vector< robot_calibration_msgs::CalibrationData > data, bool progress_to_stdout=false)
Run optimization.
Definition: optimizer.cpp:56
Class to hold parameters for optimization.
std::vector< FreeFrameInitialValue > free_frames_initial_values
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
T getParam(Params &params, const std::string &name, T default_value)
std::vector< std::string > free_params
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...
options
boost::shared_ptr< ceres::Solver::Summary > summary_
Definition: optimizer.h:93
boost::shared_ptr< CalibrationOffsetParser > offsets_
Definition: optimizer.h:92
Calibration code lives under this namespace.
Optimizer(const std::string &robot_description)
Standard constructor.
Definition: optimizer.cpp:41
std::vector< FreeFrameParams > free_frames
Model of a camera on a kinematic chain.
Definition: camera3d.h:31
#define ROS_INFO_STREAM(args)
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...
#define ROS_ERROR_STREAM(args)
std::map< std::string, ChainModel * > models_
Definition: optimizer.h:90
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.
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.
#define ROS_ERROR(...)
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 Tue Nov 3 2020 17:30:30