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


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