optimizer.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Fetch Robotics Inc.
3  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  */
17 
18 // Author: Michael Ferguson
19 
20 #ifndef ROBOT_CALIBRATION_CERES_OPTIMIZER_H
21 #define ROBOT_CALIBRATION_CERES_OPTIMIZER_H
22 
23 #include <ceres/ceres.h>
24 
25 #include <urdf/model.h>
27 #include <robot_calibration_msgs/CalibrationData.h>
28 
37 #include <boost/shared_ptr.hpp>
38 #include <string>
39 #include <map>
40 
41 namespace robot_calibration
42 {
43 
45 class Optimizer
46 {
47 public:
49  Optimizer(const std::string& robot_description);
50  virtual ~Optimizer();
51 
59  int optimize(OptimizationParams& params,
60  std::vector<robot_calibration_msgs::CalibrationData> data,
61  bool progress_to_stdout = false);
62 
65  {
66  return summary_;
67  }
68 
70  {
71  return offsets_;
72  }
73 
75  {
76  return num_params_;
77  }
78 
80  {
81  return num_residuals_;
82  }
83 
84 private:
86  std::string root_frame_;
87  std::string led_frame_;
89 
90  std::map<std::string, ChainModel*> models_;
91 
94 
96 };
97 
98 } // namespace robot_calibration
99 
100 #endif // ROBOT_CALIBRATION_CERES_OPTIMIZER_H
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.
boost::shared_ptr< CalibrationOffsetParser > getOffsets()
Definition: optimizer.h:69
boost::shared_ptr< ceres::Solver::Summary > summary_
Definition: optimizer.h:93
boost::shared_ptr< ceres::Solver::Summary > summary()
Returns the summary of the optimization last run.
Definition: optimizer.h:64
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
Class to do optimization.
Definition: optimizer.h:45
std::map< std::string, ChainModel * > models_
Definition: optimizer.h:90


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30