20 #ifndef ROBOT_CALIBRATION_CERES_OPTIMIZER_H 21 #define ROBOT_CALIBRATION_CERES_OPTIMIZER_H 23 #include <ceres/ceres.h> 27 #include <robot_calibration_msgs/CalibrationData.h> 37 #include <boost/shared_ptr.hpp> 60 std::vector<robot_calibration_msgs::CalibrationData> data,
61 bool progress_to_stdout =
false);
90 std::map<std::string, ChainModel*>
models_;
100 #endif // ROBOT_CALIBRATION_CERES_OPTIMIZER_H
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.
boost::shared_ptr< CalibrationOffsetParser > getOffsets()
boost::shared_ptr< ceres::Solver::Summary > summary_
boost::shared_ptr< ceres::Solver::Summary > summary()
Returns the summary of the optimization last run.
boost::shared_ptr< CalibrationOffsetParser > offsets_
Calibration code lives under this namespace.
Optimizer(const std::string &robot_description)
Standard constructor.
Class to do optimization.
std::map< std::string, ChainModel * > models_