23 #include <ceres/ceres.h> 27 #include <robot_calibration_msgs/CalibrationData.h> 38 #include <boost/shared_ptr.hpp> 50 std::cerr <<
"Failed to parse URDF." << std::endl;
64 std::vector<robot_calibration_msgs::CalibrationData> data,
65 bool progress_to_stdout)
70 std::cerr <<
"Failed to construct KDL tree" << std::endl;
75 for (
size_t i = 0; i < params.
models.size(); ++i)
77 if (params.
models[i].type ==
"chain")
81 params.
models[i].params[
"frame"]);
85 else if (params.
models[i].type ==
"camera3d")
88 params.
models[i].params[
"frame"]);
89 std::string param_name = params.
models[i].params[
"param_name"];
93 param_name = params.
models[i].name;
108 for (
size_t i = 0; i < params.
free_params.size(); ++i)
112 for (
size_t i = 0; i < params.
free_frames.size(); ++i)
138 double* free_params =
new double[
offsets_->size()];
142 ceres::Problem* problem =
new ceres::Problem();
145 for (
size_t i = 0; i < data.size(); ++i)
149 if (params.
error_blocks[j].type ==
"chain3d_to_chain3d")
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"]);
159 if (a_name ==
"" || b_name ==
"" || a_name == b_name)
161 ROS_ERROR(
"chain3d_to_chain3d improperly configured: model_a and model_b params must be set!");
176 if (progress_to_stdout)
178 double ** params =
new double*[1];
179 params[0] = free_params;
180 double * residuals =
new double[cost->num_residuals()];
182 cost->Evaluate(params, residuals, NULL);
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;
196 problem->AddResidualBlock(cost,
200 else if (params.
error_blocks[j].type ==
"chain3d_to_plane")
203 std::string chain_name =
static_cast<std::string
>(params.
error_blocks[j].params[
"model_a"]);
206 if (chain_name ==
"")
208 ROS_ERROR(
"chain3d_to_plane improperly configured: model_a param must be set!");
217 ceres::CostFunction * cost =
228 if (progress_to_stdout)
230 double ** params =
new double*[1];
231 params[0] = free_params;
232 double * residuals =
new double[cost->num_residuals()];
234 cost->Evaluate(params, residuals, NULL);
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;
242 problem->AddResidualBlock(cost,
246 else if (params.
error_blocks[j].type ==
"chain3d_to_mesh")
249 std::string chain_name =
static_cast<std::string
>(params.
error_blocks[j].params[
"model_a"]);
252 if (chain_name ==
"")
254 ROS_ERROR(
"chain3d_to_mesh improperly configured: model_a param must be set!");
267 ROS_ERROR(
"chain3d_to_mesh improperly configured: cannot load mesh for %s", link_name.c_str());
272 ceres::CostFunction * cost =
279 if (progress_to_stdout)
281 double ** params =
new double*[1];
282 params[0] = free_params;
283 double * residuals =
new double[cost->num_residuals()];
285 cost->Evaluate(params, residuals, NULL);
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;
293 problem->AddResidualBlock(cost,
299 else if (params.
error_blocks[j].type ==
"plane_to_plane")
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"]);
308 if (a_name ==
"" || b_name ==
"" || a_name == b_name)
310 ROS_ERROR(
"plane_to_plane improperly configured: model_a and model_a params must be set!");
319 ceres::CostFunction * cost =
328 if (progress_to_stdout)
330 double ** params =
new double*[1];
331 params[0] = free_params;
332 double * residuals =
new double[cost->num_residuals()];
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;
346 problem->AddResidualBlock(cost,
353 problem->AddResidualBlock(
355 static_cast<std::string
>(params.
error_blocks[j].params[
"param"]),
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;
376 options.minimizer_progress_to_stdout = progress_to_stdout;
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;
393 delete[] free_params;
401 std::vector<std::string> camera_names;
404 if (it->second->getType() ==
"Camera3dModel")
406 camera_names.push_back(it->first);
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 ¶ms, std::vector< robot_calibration_msgs::CalibrationData > data, bool progress_to_stdout=false)
Run optimization.
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 ¶ms, const std::string &name, T default_value)
std::vector< std::string > free_params
std::vector< std::string > getCameraNames()
Get the names of all camera models.
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...
boost::shared_ptr< ceres::Solver::Summary > summary_
boost::shared_ptr< CalibrationOffsetParser > offsets_
Calibration code lives under this namespace.
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...
std::shared_ptr< shapes::Mesh > MeshPtr
Optimizer(const std::string &robot_description)
Standard constructor.
std::vector< FreeFrameParams > free_frames
Model of a camera on a kinematic chain.
std::vector< Params > models
#define ROS_INFO_STREAM(args)
std::vector< Params > error_blocks
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...
boost::shared_ptr< MeshLoader > mesh_loader_
#define ROS_ERROR_STREAM(args)
std::map< std::string, ChainModel * > models_
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.
Model of a kinematic chain. This is the basic instance where we transform the world observations into...