optimization_params.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 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 
67  // Parameters for the optimizer itself
69 
71  bool LoadFromROS(ros::NodeHandle& nh);
72 
73  template<typename T>
74  T getParam(Params& params, const std::string& name, T default_value)
75  {
76  if (!params.params.hasMember(name))
77  {
78  ROS_WARN_STREAM(name << " was not set, using default of " << default_value);
79  return default_value;
80  }
81 
82  return static_cast<T>(params.params[name]);
83  }
84 };
85 
86 } // namespace robot_calibration
87 
88 #endif // ROBOT_CALIBRATION_CERES_OPTIMIZATION_PARAMS_H
robot_calibration::OptimizationParams::FreeFrameParams::x
bool x
Definition: optimization_params.h:34
ros.h
robot_calibration::OptimizationParams::free_frames_initial_values
std::vector< FreeFrameInitialValue > free_frames_initial_values
Definition: optimization_params.h:63
robot_calibration::OptimizationParams::getParam
T getParam(Params &params, const std::string &name, T default_value)
Definition: optimization_params.h:74
robot_calibration::OptimizationParams::FreeFrameInitialValue::z
double z
Definition: optimization_params.h:47
robot_calibration::OptimizationParams::FreeFrameInitialValue::x
double x
Definition: optimization_params.h:45
robot_calibration::OptimizationParams::OptimizationParams
OptimizationParams()
Definition: optimization_params.cpp:25
robot_calibration::OptimizationParams::FreeFrameInitialValue::yaw
double yaw
Definition: optimization_params.h:50
robot_calibration::OptimizationParams::free_params
std::vector< std::string > free_params
Definition: optimization_params.h:61
robot_calibration::OptimizationParams::FreeFrameInitialValue::name
std::string name
Definition: optimization_params.h:44
robot_calibration::OptimizationParams::FreeFrameParams::roll
bool roll
Definition: optimization_params.h:37
robot_calibration::OptimizationParams::Params::name
std::string name
Definition: optimization_params.h:55
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
robot_calibration::OptimizationParams::FreeFrameInitialValue
Definition: optimization_params.h:42
name
std::string name
robot_calibration::OptimizationParams::LoadFromROS
bool LoadFromROS(ros::NodeHandle &nh)
Definition: optimization_params.cpp:30
robot_calibration::OptimizationParams::Params::type
std::string type
Definition: optimization_params.h:56
robot_calibration::OptimizationParams::base_link
std::string base_link
Definition: optimization_params.h:60
robot_calibration::OptimizationParams::FreeFrameParams::y
bool y
Definition: optimization_params.h:35
robot_calibration::OptimizationParams::Params::params
XmlRpc::XmlRpcValue params
Definition: optimization_params.h:57
robot_calibration::OptimizationParams::free_frames
std::vector< FreeFrameParams > free_frames
Definition: optimization_params.h:62
robot_calibration::OptimizationParams::FreeFrameInitialValue::y
double y
Definition: optimization_params.h:46
robot_calibration::OptimizationParams::FreeFrameInitialValue::roll
double roll
Definition: optimization_params.h:48
robot_calibration::OptimizationParams
Class to hold parameters for optimization.
Definition: optimization_params.h:29
XmlRpc::XmlRpcValue::hasMember
bool hasMember(const std::string &name) const
robot_calibration::OptimizationParams::FreeFrameInitialValue::pitch
double pitch
Definition: optimization_params.h:49
robot_calibration::OptimizationParams::FreeFrameParams::pitch
bool pitch
Definition: optimization_params.h:38
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::OptimizationParams::models
std::vector< Params > models
Definition: optimization_params.h:64
default_value
def default_value(type_)
robot_calibration::OptimizationParams::error_blocks
std::vector< Params > error_blocks
Definition: optimization_params.h:65
robot_calibration::OptimizationParams::max_num_iterations
int max_num_iterations
Definition: optimization_params.h:68
robot_calibration::OptimizationParams::FreeFrameParams::z
bool z
Definition: optimization_params.h:36
robot_calibration::OptimizationParams::FreeFrameParams::name
std::string name
Definition: optimization_params.h:33
robot_calibration::OptimizationParams::FreeFrameParams
Definition: optimization_params.h:31
XmlRpc::XmlRpcValue
ros::NodeHandle
robot_calibration::OptimizationParams::Params
Definition: optimization_params.h:53
robot_calibration::OptimizationParams::FreeFrameParams::yaw
bool yaw
Definition: optimization_params.h:39


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