optimizer.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2014 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 
21 #ifndef ROBOT_CALIBRATION_CERES_OPTIMIZER_H
22 #define ROBOT_CALIBRATION_CERES_OPTIMIZER_H
23 
24 #include <ceres/ceres.h>
25 
26 #include <urdf/model.h>
28 #include <robot_calibration_msgs/CalibrationData.h>
34 #include <boost/shared_ptr.hpp>
35 #include <string>
36 #include <map>
37 
38 namespace robot_calibration
39 {
40 
42 class Optimizer
43 {
44 public:
46  Optimizer(const std::string& robot_description);
47  virtual ~Optimizer();
48 
56  int optimize(OptimizationParams& params,
57  std::vector<robot_calibration_msgs::CalibrationData> data,
58  bool progress_to_stdout = false);
59 
64  {
65  return summary_;
66  }
67 
69  {
70  return offsets_;
71  }
72 
74  {
75  return num_params_;
76  }
77 
79  {
80  return num_residuals_;
81  }
82 
88  std::vector<std::string> getCameraNames();
89 
90 private:
92  std::string root_frame_;
93  std::string led_frame_;
94  KDL::Tree tree_;
95 
97 
98  std::map<std::string, ChainModel*> models_;
99 
102 
104 };
105 
106 } // namespace robot_calibration
107 
108 #endif // ROBOT_CALIBRATION_CERES_OPTIMIZER_H
robot_calibration::Optimizer::model_
urdf::Model model_
Definition: optimizer.h:91
boost::shared_ptr< ceres::Solver::Summary >
robot_calibration::Optimizer::summary_
boost::shared_ptr< ceres::Solver::Summary > summary_
Definition: optimizer.h:101
robot_calibration::Optimizer::getNumResiduals
int getNumResiduals()
Definition: optimizer.h:78
offset_parser.h
robot_calibration::Optimizer::~Optimizer
virtual ~Optimizer()
Definition: optimizer.cpp:59
robot_calibration::Optimizer::summary
boost::shared_ptr< ceres::Solver::Summary > summary()
Returns the summary of the optimization last run.
Definition: optimizer.h:63
urdf::Model
robot_calibration::Optimizer::models_
std::map< std::string, ChainModel * > models_
Definition: optimizer.h:98
robot_description
std::string robot_description
Definition: calibration_offset_parser_tests.cpp:7
robot_calibration::Optimizer::num_params_
int num_params_
Definition: optimizer.h:103
robot_calibration::Optimizer::getCameraNames
std::vector< std::string > getCameraNames()
Get the names of all camera models.
Definition: optimizer.cpp:399
robot_calibration::Optimizer::Optimizer
Optimizer(const std::string &robot_description)
Standard constructor.
Definition: optimizer.cpp:45
robot_calibration::Optimizer::optimize
int optimize(OptimizationParams &params, std::vector< robot_calibration_msgs::CalibrationData > data, bool progress_to_stdout=false)
Run optimization.
Definition: optimizer.cpp:63
robot_calibration::Optimizer::led_frame_
std::string led_frame_
Definition: optimizer.h:93
robot_calibration::Optimizer::getOffsets
boost::shared_ptr< CalibrationOffsetParser > getOffsets()
Definition: optimizer.h:68
robot_calibration::Optimizer
Class to do optimization.
Definition: optimizer.h:42
model.h
mesh_loader.h
chain.h
robot_calibration::Optimizer::mesh_loader_
boost::shared_ptr< MeshLoader > mesh_loader_
Definition: optimizer.h:96
kdl_parser.hpp
robot_calibration::OptimizationParams
Class to hold parameters for optimization.
Definition: optimization_params.h:29
robot_calibration::Optimizer::tree_
KDL::Tree tree_
Definition: optimizer.h:94
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
optimization_params.h
robot_calibration::Optimizer::offsets_
boost::shared_ptr< CalibrationOffsetParser > offsets_
Definition: optimizer.h:100
robot_calibration::Optimizer::root_frame_
std::string root_frame_
Definition: optimizer.h:92
camera3d.h
robot_calibration::Optimizer::getNumParameters
int getNumParameters()
Definition: optimizer.h:73
robot_calibration::Optimizer::num_residuals_
int num_residuals_
Definition: optimizer.h:103


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01