param_parser.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
20 #include <urdf/model.h>
21 #include <angles/angles.h>
22 #include <XmlRpcException.h>
23 
26 #include <tf2/LinearMath/Vector3.h>
27 
30 public:
32  MergedXmlRpcStruct(const XmlRpc::XmlRpcValue& a, const MergedXmlRpcStruct &b, bool recursive= true) :XmlRpc::XmlRpcValue(a){
33  assertStruct();
34 
35  for(ValueStruct::const_iterator it = b._value.asStruct->begin(); it != b._value.asStruct->end(); ++it){
36  std::pair<XmlRpc::XmlRpcValue::iterator,bool> res = _value.asStruct->insert(*it);
37 
38  if(recursive && !res.second && res.first->second.getType() == XmlRpc::XmlRpcValue::TypeStruct && it->second.getType() == XmlRpc::XmlRpcValue::TypeStruct){
39  res.first->second = MergedXmlRpcStruct(res.first->second, it->second); // recursive struct merge with implicit cast
40  }
41  }
42 
43 
44  }
45 };
46 
47 template<typename T> T read_typed(XmlRpc::XmlRpcValue &val){
48  return val;
49 }
50 template<> double read_typed(XmlRpc::XmlRpcValue &val){
51  if(val.getType() == XmlRpc::XmlRpcValue::TypeInt) return read_typed<int>(val);
52  return val;
53 }
54 
55 template<typename T> bool read_optional(T& val, const std::string &name, XmlRpc::XmlRpcValue &wheel){
56  try{
57  if(wheel.hasMember(name)){
58  val = read_typed<T>(wheel[name]);
59  return true;
60  }
61  }catch(XmlRpc::XmlRpcException &e){
62  ROS_ERROR_STREAM("Could not access '" << name << "', reason: " << e.getMessage());
63  }
64  return false;
65 }
66 
67 template<typename T> bool read_with_default(T& val, const std::string &name, XmlRpc::XmlRpcValue &wheel, const T& def){
68  if(!read_optional(val, name, wheel)){
69  val = def;
70  return false;
71  }
72  return true;
73 }
74 
75 template<typename T> bool read(T& val, const std::string &name, XmlRpc::XmlRpcValue &wheel){
76  if(!read_optional(val, name, wheel)){
77  ROS_ERROR_STREAM("Parameter not found: " << name);
78  return false;
79  }
80  return true;
81 }
82 
84  double deg;
85  read_with_default(deg, "steer_neutral_position", wheel, 0.0);
87 
88  std::string steer_name, drive_name;
89  double max_steer_rate, max_drive_rate;
90  read_with_default(steer_name, "steer", wheel, std::string());
91  read_with_default(drive_name, "drive", wheel, std::string());
92 
93  urdf::JointConstSharedPtr steer_joint;
94  if(model && !steer_name.empty()){
95  steer_joint = model->getJoint(steer_name);
96  if(steer_joint){
97  params.dMaxSteerRateRadpS = steer_joint->limits->velocity;
98  }
99  }
100  if(!read_optional(params.dMaxSteerRateRadpS, "max_steer_rate", wheel) && !steer_joint){
101  ROS_WARN_STREAM("max_steer_rate not set - defaulting to 0.0");
102  params.dMaxSteerRateRadpS = 0.0;
103  }
104  urdf::JointConstSharedPtr drive_joint;
105  if(model && !drive_name.empty()){
106  drive_joint = model->getJoint(drive_name);
107  if(drive_joint){
108  params.dMaxDriveRateRadpS = drive_joint->limits->velocity;
109  }
110  }
111  if(!read_optional(params.dMaxDriveRateRadpS, "max_drive_rate", wheel) && !drive_joint){
112  ROS_WARN_STREAM("max_drive_rate not set - defaulting to 0.0");
113  params.dMaxDriveRateRadpS = 0.0;
114  }
115 
116  ROS_DEBUG_STREAM("max_steer_rate: " << params.dMaxSteerRateRadpS);
117  ROS_DEBUG_STREAM("max_drive_rate: " << params.dMaxDriveRateRadpS);
118 
119  return true;
120 }
121 
123  if(!wheel.hasMember("steer_ctrl")){
124  ROS_ERROR_STREAM("steer_ctrl not found");
125  return false;
126  }
127  XmlRpc::XmlRpcValue &steer = wheel["steer_ctrl"];
128 
129  return read(params.dSpring, "spring", steer)
130  && read(params.dDamp, "damp", steer)
131  && read(params.dVirtM, "virt_mass", steer)
132  && read(params.dDPhiMax, "d_phi_max", steer)
133  && read(params.dDDPhiMax, "dd_phi_max", steer);
134 }
135 
137 
138  read_with_default(geom.steer_name, "steer", wheel, std::string());
139  read_with_default(geom.drive_name, "drive", wheel, std::string());
140  read_with_default(geom.dSteerDriveCoupling, "steer_drive_coupling", wheel, 0.0);
141 
142  urdf::JointConstSharedPtr steer_joint;
143  urdf::Vector3 steer_pos;
144 
145  if(model && !geom.steer_name.empty()){
146  steer_joint = model->getJoint(geom.steer_name);
147  if(steer_joint){
148  tf2::Transform transform;
149  if(parseWheelTransform(geom.steer_name, model->getRoot()->name, transform, model)){
150  steer_pos.x = transform.getOrigin().getX();
151  steer_pos.y = transform.getOrigin().getY();
152  steer_pos.z = transform.getOrigin().getZ();
153  }
154  }
155  }
156 
157  if(!read_optional(steer_pos.x, "x_pos", wheel) && !steer_joint){
158  ROS_ERROR_STREAM("Could not parse x_pos");
159  return false;
160  }
161 
162  if(!read_optional(steer_pos.y, "y_pos", wheel) && !steer_joint){
163  ROS_ERROR_STREAM("Could not parse y_pos");
164  return false;
165  }
166 
167  if(!read_optional(steer_pos.z, "wheel_radius", merged) && !steer_joint){
168  ROS_ERROR_STREAM("Could not parse wheel_radius");
169  return false;
170  }
171 
172  if(steer_pos.z == 0){
173  ROS_ERROR_STREAM("wheel_radius must be non-zero");
174  return false;
175  }
176 
177  ROS_DEBUG_STREAM(geom.steer_name<<" steer_pos \tx:"<<steer_pos.x<<" \ty:"<<steer_pos.y<<" \tz:"<<steer_pos.z);
178 
179  geom.dWheelXPosMM = steer_pos.x * 1000;
180  geom.dWheelYPosMM = steer_pos.y * 1000;
181  geom.dRadiusWheelMM = fabs(steer_pos.z * 1000);
182 
183  double offset = 0;
184 
185  if(!read_optional(offset, "wheel_offset", merged)){
186  urdf::JointConstSharedPtr drive_joint;
187  if(model && !geom.drive_name.empty()){
188  drive_joint = model->getJoint(geom.drive_name);
189  }
190  if(drive_joint){
191  const urdf::Vector3& pos = drive_joint->parent_to_joint_origin_transform.position;
192  offset = sqrt(pos.x*pos.x + pos.y * pos.y);
193  }else{
194  ROS_ERROR_STREAM("Could not parse wheel_offset");
195  return false;
196  }
197  }
198  geom.dDistSteerAxisToDriveWheelMM = offset * 1000;
199  return true;
200 }
201 
202 template<typename W> bool parseWheel(W & params, XmlRpc::XmlRpcValue &wheel, MergedXmlRpcStruct &merged, urdf::Model* model);
203 
205  return parseWheelGeom(params.geom, wheel, merged, model);
206 }
207 
209  return parseWheelGeom(params.geom, wheel, merged, model) && parseCtrlParams(params.ctrl, merged, model);
210 }
211 
213  return parseWheelGeom(params.geom, wheel, merged, model) && parseCtrlParams(params.ctrl, merged, model) && parsePosCtrlParams(params.pos_ctrl, merged);
214 }
215 
217  if(wheel_list.getType() == XmlRpc::XmlRpcValue::TypeArray){
218  XmlRpc::XmlRpcValue new_stuct;
219  for(size_t i = 0; i < wheel_list.size(); ++i){
220  new_stuct[boost::lexical_cast<std::string>(i)] = wheel_list[i];
221  }
222  wheel_list = new_stuct;
223  }else if(wheel_list.getType() != XmlRpc::XmlRpcValue::TypeStruct){
224  return false;
225  }
226 
227  return wheel_list.size() > 0;
228 }
229 
230 template<typename W> bool parseWheels(std::vector<W> &wheel_params, const ros::NodeHandle &nh, bool read_urdf){
231 
232  urdf::Model model;
233 
234  std::string description_name;
235  bool has_model = read_urdf && nh.searchParam("robot_description", description_name) && model.initParam(description_name);
236 
237  MergedXmlRpcStruct defaults;
238  nh.getParam("defaults", defaults);
239 
240  // clear vector in case of reinititialization
241  wheel_params.clear();
242 
243  XmlRpc::XmlRpcValue wheel_list;
244  if (!nh.getParam("wheels", wheel_list)){
245  ROS_ERROR("List of wheels not found");
246  return false;
247  }
248 
249  if (!make_wheel_struct(wheel_list)){
250  ROS_ERROR("List of wheels is invalid");
251  return false;
252  }
253 
254  for(XmlRpc::XmlRpcValue::iterator it = wheel_list.begin(); it != wheel_list.end(); ++it){
255 
256  W params;
257  MergedXmlRpcStruct merged(it->second, defaults);
258 
259  if(!parseWheel(params, it->second, merged, has_model?&model:0)){
260  return false;
261  }
262 
263  wheel_params.push_back(params);
264  }
265  return !wheel_params.empty();
266 }
267 
268 namespace cob_omni_drive_controller{
269 
270 bool parseWheelParams(std::vector<UndercarriageGeom::WheelParams> &params, const ros::NodeHandle &nh, bool read_urdf /* = true*/){
271  return parseWheels(params, nh, read_urdf);
272 }
273 bool parseWheelParams(std::vector<UndercarriageDirectCtrl::WheelParams> &params, const ros::NodeHandle &nh, bool read_urdf /* = true*/){
274  return parseWheels(params, nh, read_urdf);
275 }
276 bool parseWheelParams(std::vector<UndercarriageCtrl::WheelParams> &params, const ros::NodeHandle &nh, bool read_urdf /* = true*/){
277  return parseWheels(params, nh, read_urdf);
278 }
279 
280 
281 }
const std::string & getMessage() const
bool parseWheelParams(std::vector< UndercarriageGeom::WheelParams > &params, const ros::NodeHandle &nh, bool read_urdf=true)
double dSteerDriveCoupling
ValueStruct::iterator iterator
bool parsePosCtrlParams(PosCtrlParams &params, XmlRpc::XmlRpcValue &wheel)
int size() const
bool read(T &val, const std::string &name, XmlRpc::XmlRpcValue &wheel)
T read_typed(XmlRpc::XmlRpcValue &val)
MergedXmlRpcStruct(const XmlRpc::XmlRpcValue &a, const MergedXmlRpcStruct &b, bool recursive=true)
Type const & getType() const
void assertStruct() const
bool parseWheelGeom(WheelGeom &geom, XmlRpc::XmlRpcValue &wheel, MergedXmlRpcStruct &merged, urdf::Model *model)
union XmlRpc::XmlRpcValue::@0 _value
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
static double from_degrees(double degrees)
bool searchParam(const std::string &key, std::string &result) const
bool parseWheelTransform(const std::string &joint_name, const std::string &parent_link_name, tf2::Transform &transform, urdf::Model *model)
Definition: param_parser.h:27
bool parseWheels(std::vector< W > &wheel_params, const ros::NodeHandle &nh, bool read_urdf)
URDF_EXPORT bool initParam(const std::string &param)
double dDistSteerAxisToDriveWheelMM
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
bool read_optional(T &val, const std::string &name, XmlRpc::XmlRpcValue &wheel)
MergedXmlRpcStruct(const XmlRpc::XmlRpcValue &a)
bool hasMember(const std::string &name) const
bool parseWheel(W &params, XmlRpc::XmlRpcValue &wheel, MergedXmlRpcStruct &merged, urdf::Model *model)
bool parseCtrlParams(CtrlParams &params, XmlRpc::XmlRpcValue &wheel, urdf::Model *model)
bool getParam(const std::string &key, std::string &s) const
std::string steer_name
std::string drive_name
ValueStruct * asStruct
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
bool read_with_default(T &val, const std::string &name, XmlRpc::XmlRpcValue &wheel, const T &def)
bool make_wheel_struct(XmlRpc::XmlRpcValue &wheel_list)


cob_omni_drive_controller
Author(s): Christian Connette, Mathias Lüdtke
autogenerated on Thu Apr 8 2021 02:39:52