23 #include <ceres/ceres.h> 27 #include <robot_calibration_msgs/CalibrationData.h> 34 #include <boost/shared_ptr.hpp> 46 std::cerr <<
"Failed to parse URDF." << std::endl;
57 std::vector<robot_calibration_msgs::CalibrationData> data,
58 bool progress_to_stdout)
63 std::cerr <<
"Failed to construct KDL tree" << std::endl;
68 for (
size_t i = 0; i < params.
models.size(); ++i)
70 if (params.
models[i].type ==
"chain")
74 params.
models[i].params[
"frame"]);
78 else if (params.
models[i].type ==
"camera3d")
81 params.
models[i].params[
"frame"]);
95 for (
size_t i = 0; i < params.
free_params.size(); ++i)
99 for (
size_t i = 0; i < params.
free_frames.size(); ++i)
125 double* free_params =
new double[
offsets_->size()];
129 ceres::Problem* problem =
new ceres::Problem();
132 for (
size_t i = 0; i < data.size(); ++i)
136 if (params.
error_blocks[j].type ==
"chain3d_to_chain3d")
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"]);
146 if (a_name ==
"" || b_name ==
"" || a_name == b_name)
148 ROS_ERROR(
"chain3d_to_chain3d improperly configured: model_a and model_b params must be set!");
163 if (progress_to_stdout)
165 double ** params =
new double*[1];
166 params[0] = free_params;
167 double * residuals =
new double[cost->num_residuals()];
169 cost->Evaluate(params, residuals, NULL);
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;
183 problem->AddResidualBlock(cost,
187 else if (params.
error_blocks[j].type ==
"chain3d_to_plane")
190 std::string chain_name =
static_cast<std::string
>(params.
error_blocks[j].params[
"model_a"]);
193 if (chain_name ==
"")
195 ROS_ERROR(
"chain3d_to_plane improperly configured: model_a param must be set!");
204 ceres::CostFunction * cost =
215 if (progress_to_stdout)
217 double ** params =
new double*[1];
218 params[0] = free_params;
219 double * residuals =
new double[cost->num_residuals()];
221 cost->Evaluate(params, residuals, NULL);
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;
229 problem->AddResidualBlock(cost,
233 else if (params.
error_blocks[j].type ==
"plane_to_plane")
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"]);
242 if (a_name ==
"" || b_name ==
"" || a_name == b_name)
244 ROS_ERROR(
"plane_to_plane improperly configured: model_a and model_a params must be set!");
253 ceres::CostFunction * cost =
262 if (progress_to_stdout)
264 double ** params =
new double*[1];
265 params[0] = free_params;
266 double * residuals =
new double[cost->num_residuals()];
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;
280 problem->AddResidualBlock(cost,
287 problem->AddResidualBlock(
289 static_cast<std::string
>(params.
error_blocks[j].params[
"param"]),
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;
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;
328 delete[] free_params;
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
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.
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...
#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...