optimization_params.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Michael Ferguson
3  * Copyright (C) 2014 Fetch 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_OPTIMIZATION_PARAMS_H
21 #define ROBOT_CALIBRATION_CERES_OPTIMIZATION_PARAMS_H
22 
23 #include <ros/ros.h>
24 
25 namespace robot_calibration
26 {
27 
30 {
32  {
33  std::string name;
34  bool x;
35  bool y;
36  bool z;
37  bool roll;
38  bool pitch;
39  bool yaw;
40  };
41 
43  {
44  std::string name;
45  double x;
46  double y;
47  double z;
48  double roll;
49  double pitch;
50  double yaw;
51  };
52 
53  struct Params
54  {
55  std::string name;
56  std::string type;
58  };
59 
60  std::string base_link;
61  std::vector<std::string> free_params;
62  std::vector<FreeFrameParams> free_frames;
63  std::vector<FreeFrameInitialValue> free_frames_initial_values;
64  std::vector<Params> models;
65  std::vector<Params> error_blocks;
66 
68  bool LoadFromROS(ros::NodeHandle& nh);
69 
70  template<typename T>
71  T getParam(Params& params, const std::string& name, T default_value)
72  {
73  if (!params.params.hasMember(name))
74  {
75  ROS_WARN_STREAM(name << " was not set, using default of " << default_value);
76  return default_value;
77  }
78 
79  return static_cast<T>(params.params[name]);
80  }
81 };
82 
83 } // namespace robot_calibration
84 
85 #endif // ROBOT_CALIBRATION_CERES_OPTIMIZATION_PARAMS_H
Class to hold parameters for optimization.
std::vector< FreeFrameInitialValue > free_frames_initial_values
T getParam(Params &params, const std::string &name, T default_value)
std::vector< std::string > free_params
Calibration code lives under this namespace.
#define ROS_WARN_STREAM(args)
std::vector< FreeFrameParams > free_frames
bool hasMember(const std::string &name) const


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