optimization_params.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2014-2015 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 
21 
22 namespace robot_calibration
23 {
24 
26  base_link("base_link")
27 {
28 }
29 
31 {
32  nh.param("base_link", base_link, base_link);
33  nh.param("max_num_iterations", max_num_iterations, 1000);
34 
35  if (nh.hasParam("free_params"))
36  {
37  free_params.clear();
38 
39  XmlRpc::XmlRpcValue names;
40  nh.getParam("free_params", names);
42 
43  for (int i = 0; i < names.size(); ++i)
44  {
45  free_params.push_back(static_cast<std::string>(names[i]));
46  }
47  }
48 
49  if (nh.hasParam("free_frames"))
50  {
51  free_frames.clear();
52 
53  XmlRpc::XmlRpcValue free_frame_params;
54  nh.getParam("free_frames", free_frame_params);
55  ROS_ASSERT(free_frame_params.getType() == XmlRpc::XmlRpcValue::TypeArray);
56 
57  for (int i = 0; i < free_frame_params.size(); ++i)
58  {
59  FreeFrameParams params;
60  params.name = static_cast<std::string>(free_frame_params[i]["name"]);
61  params.x = static_cast<bool>(free_frame_params[i]["x"]);
62  params.y = static_cast<bool>(free_frame_params[i]["y"]);
63  params.z = static_cast<bool>(free_frame_params[i]["z"]);
64  params.roll = static_cast<bool>(free_frame_params[i]["roll"]);
65  params.pitch = static_cast<bool>(free_frame_params[i]["pitch"]);
66  params.yaw = static_cast<bool>(free_frame_params[i]["yaw"]);
67  free_frames.push_back(params);
68  }
69  }
70 
71  if (nh.hasParam("free_frames_initial_values"))
72  {
74 
75  XmlRpc::XmlRpcValue initial_value_params;
76  nh.getParam("free_frames_initial_values", initial_value_params);
77  ROS_ASSERT(initial_value_params.getType() == XmlRpc::XmlRpcValue::TypeArray);
78 
79  for (int i = 0; i < initial_value_params.size(); ++i)
80  {
81  FreeFrameInitialValue params;
82  params.name = static_cast<std::string>(initial_value_params[i]["name"]);
83  params.x = static_cast<double>(initial_value_params[i]["x"]);
84  params.y = static_cast<double>(initial_value_params[i]["y"]);
85  params.z = static_cast<double>(initial_value_params[i]["z"]);
86  params.roll = static_cast<double>(initial_value_params[i]["roll"]);
87  params.pitch = static_cast<double>(initial_value_params[i]["pitch"]);
88  params.yaw = static_cast<double>(initial_value_params[i]["yaw"]);
89  free_frames_initial_values.push_back(params);
90  }
91  }
92 
93  if (nh.hasParam("models"))
94  {
95  models.clear();
96 
97  XmlRpc::XmlRpcValue model_params;
98  nh.getParam("models", model_params);
100 
101  for (int i = 0; i < model_params.size(); ++i)
102  {
103  Params params;
104  params.name = static_cast<std::string>(model_params[i]["name"]);
105  params.type = static_cast<std::string>(model_params[i]["type"]);
106  params.params = model_params[i];
107  models.push_back(params);
108  }
109  }
110 
111  if (nh.hasParam("error_blocks"))
112  {
113  error_blocks.clear();
114 
115  XmlRpc::XmlRpcValue error_params;
116  nh.getParam("error_blocks", error_params);
118 
119  for (int i = 0; i < error_params.size(); ++i)
120  {
121  Params params;
122  params.name = static_cast<std::string>(error_params[i]["name"]);
123  params.type = static_cast<std::string>(error_params[i]["type"]);
124  params.params = error_params[i];
125  error_blocks.push_back(params);
126  }
127  }
128 
129  return true;
130 }
131 
132 } // namespace robot_calibration
XmlRpc::XmlRpcValue::size
int size() const
robot_calibration::OptimizationParams::FreeFrameParams::x
bool x
Definition: optimization_params.h:34
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
robot_calibration::OptimizationParams::free_frames_initial_values
std::vector< FreeFrameInitialValue > free_frames_initial_values
Definition: optimization_params.h:63
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
robot_calibration::OptimizationParams::FreeFrameInitialValue
Definition: optimization_params.h:42
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
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
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
XmlRpc::XmlRpcValue::getType
const Type & getType() const
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
XmlRpc::XmlRpcValue::TypeArray
TypeArray
robot_calibration::OptimizationParams::FreeFrameInitialValue::roll
double roll
Definition: optimization_params.h:48
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
optimization_params.h
robot_calibration::OptimizationParams::models
std::vector< Params > models
Definition: optimization_params.h:64
robot_calibration::OptimizationParams::error_blocks
std::vector< Params > error_blocks
Definition: optimization_params.h:65
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
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
ROS_ASSERT
#define ROS_ASSERT(cond)
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