xml_testdata_loader.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018 Pilz GmbH & Co. KG
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 
18 
19 #include <iostream>
20 
21 #include <boost/property_tree/xml_parser.hpp>
22 #include <boost/algorithm/string.hpp>
23 #include <boost/optional.hpp>
24 
28 
29 namespace pt = boost::property_tree;
31 {
32 
33 class CmdReader
34 {
35 public:
36  CmdReader(const pt::ptree::value_type & node)
37  : cmd_node_(node)
38  {}
39 
40 public:
41  std::string getPlanningGroup() const;
42  std::string getTargetLink() const;
43  std::string getStartPoseName() const;
44  std::string getEndPoseName() const;
45 
46  double getVelocityScale() const;
47  double getAccelerationScale() const;
48 
49  CmdReader& setDefaultVelocityScale(double scale);
51 
52 private:
53  const pt::ptree::value_type &cmd_node_;
54 
57 
58 };
59 
60 inline std::string CmdReader::getPlanningGroup() const
61 {
62  return cmd_node_.second.get<std::string>(PLANNING_GROUP_STR);
63 }
64 
65 inline std::string CmdReader::getTargetLink() const
66 {
67  return cmd_node_.second.get<std::string>(TARGET_LINK_STR);
68 }
69 
70 inline std::string CmdReader::getStartPoseName() const
71 {
72  return cmd_node_.second.get<std::string>(START_POS_STR);
73 }
74 
75 inline std::string CmdReader::getEndPoseName() const
76 {
77  return cmd_node_.second.get<std::string>(END_POS_STR);
78 }
79 
80 inline double CmdReader::getVelocityScale() const
81 {
82  return cmd_node_.second.get<double>(VEL_STR, default_velocity_scale_);
83 }
84 
85 inline double CmdReader::getAccelerationScale() const
86 {
87  return cmd_node_.second.get<double>(ACC_STR, default_acceleration_scale_);
88 }
89 
91 {
93  return *this;
94 }
95 
97 {
99  return *this;
100 }
101 
102 template<class CmdType>
104 {
105 public:
106  using FuncType = std::function<CmdType(const std::string&)>;
107 
109  : AbstractCmdGetterAdapter()
110  , func_(func)
111  {
112  }
113 
114 public:
115  CmdVariant getCmd(const std::string& cmd_name) const override
116  {
117  return CmdVariant(func_(cmd_name));
118  }
119 
120 private:
122 };
123 
124 XmlTestdataLoader::XmlTestdataLoader(const std::string &path_filename)
125  : TestdataLoader()
126  , path_filename_(path_filename)
127 {
128  // Parse the XML into the property tree.
129  pt::read_xml(path_filename_, tree_, pt::xml_parser::no_comments);
130 
131  using std::placeholders::_1;
135 
138 
142 
144 }
145 
146 XmlTestdataLoader::XmlTestdataLoader(const std::string &path_filename,
147  const moveit::core::RobotModelConstPtr& robot_model)
148  : XmlTestdataLoader(path_filename)
149 {
150  setRobotModel(robot_model);
151 }
152 
153 
155 {
156 
157 }
158 
159 const pt::ptree::value_type& XmlTestdataLoader::findNodeWithName(const boost::property_tree::ptree &tree,
160  const std::string &name,
161  const std::string &key,
162  const std::string& path) const
163 {
164  std::string path_str {(path.empty()? NAME_PATH_STR : path)};
165 
166  // Search for node with given name.
167  for (const pt::ptree::value_type& val : tree)
168  {
169  // Ignore attributes which are always the first element of a tree.
170  if (val.first == XML_ATTR_STR){ continue; }
171 
172  if (val.first != key) {continue;}
173 
174  const auto& node {val.second.get_child(path_str, empty_tree_)};
175  if (node == empty_tree_) { break; }
176  if (node.data() == name) { return val; }
177  }
178 
179  std::string msg;
180  msg.append("Node of type \"").append(key).append("\" with ").
181  append(path_str).append("=\"").append(name).append("\" not found.");
183 }
184 
186  const std::string &group_name) const
187 {
188  // Search for node with given name.
189  const auto& poses_tree {tree_.get_child(POSES_PATH_STR, empty_tree_)};
190  if (poses_tree == empty_tree_)
191  {
192  throw TestDataLoaderReadingException("No poses found.");
193  }
194  return getJoints(findNodeWithName(poses_tree, pos_name, POSE_STR).second, group_name);
195 }
196 
197 JointConfiguration XmlTestdataLoader::getJoints(const boost::property_tree::ptree& joints_tree,
198  const std::string &group_name) const
199 {
200  // Search joints node with given group_name.
201  if (joints_tree == empty_tree_)
202  {
203  throw TestDataLoaderReadingException("No joints found.");
204  }
205  const auto& joint_node {findNodeWithName(joints_tree, group_name, JOINT_STR, GROUP_NAME_PATH_STR)};
206 
207  std::vector<std::string> strs;
208  boost::split(strs, joint_node.second.data(), boost::is_any_of(" "));
209  return JointConfiguration(group_name, strVec2doubleVec(strs), robot_model_);
210 }
211 
213  const std::string &group_name) const
214 {
215  const auto& all_poses_tree {tree_.get_child(POSES_PATH_STR, empty_tree_)};
216  if (all_poses_tree == empty_tree_)
217  {
218  throw TestDataLoaderReadingException("No poses found.");
219  }
220  const auto& pose_tree {findNodeWithName(all_poses_tree, pos_name, POSE_STR).second};
221  const auto& xyz_quat_tree {findNodeWithName(pose_tree, group_name, XYZ_QUAT_STR, GROUP_NAME_PATH_STR).second};
222  const boost::property_tree::ptree& link_name_attr {xyz_quat_tree.get_child(LINK_NAME_PATH_STR, empty_tree_)};
223  if (link_name_attr == empty_tree_)
224  {
225  throw TestDataLoaderReadingException("No link name found.");
226  }
227 
228  // Get rid of things like "\n", etc.
229  std::string data {xyz_quat_tree.data()};
230  boost::trim(data);
231 
232  std::vector<std::string> pos_ori_str;
233  boost::split(pos_ori_str, data, boost::is_any_of(" "));
234  CartesianConfiguration cart_config { CartesianConfiguration(group_name, link_name_attr.data(),
235  strVec2doubleVec(pos_ori_str), robot_model_)};
236 
237  const auto& seeds_tree {xyz_quat_tree.get_child(SEED_STR, empty_tree_)};
238  if (seeds_tree != empty_tree_)
239  {
240  cart_config.setSeed(getJoints(seeds_tree, group_name));
241  }
242  return cart_config;
243 }
244 
245 PtpJoint XmlTestdataLoader::getPtpJoint(const std::string& cmd_name) const
246 {
247  CmdReader cmd_reader{ findCmd(cmd_name, PTPS_PATH_STR, PTP_STR) };
248  std::string planning_group {cmd_reader.getPlanningGroup()};
249 
250  PtpJoint cmd;
252  cmd.setVelocityScale(cmd_reader.getVelocityScale());
253  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
254 
255  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
256  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
257 
258  return cmd;
259 }
260 
261 PtpJointCart XmlTestdataLoader::getPtpJointCart(const std::string& cmd_name) const
262 {
263  CmdReader cmd_reader{ findCmd(cmd_name, PTPS_PATH_STR, PTP_STR) };
264  std::string planning_group {cmd_reader.getPlanningGroup()};
265 
268  cmd.setVelocityScale(cmd_reader.getVelocityScale());
269  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
270 
271  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
272  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
273 
274  return cmd;
275 }
276 
277 PtpCart XmlTestdataLoader::getPtpCart(const std::string& cmd_name) const
278 {
279  CmdReader cmd_reader{ findCmd(cmd_name, PTPS_PATH_STR, PTP_STR) };
280  std::string planning_group {cmd_reader.getPlanningGroup()};
281 
282  PtpCart cmd;
284  cmd.setVelocityScale(cmd_reader.getVelocityScale());
285  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
286 
287  cmd.setStartConfiguration(getPose(cmd_reader.getStartPoseName(), planning_group));
288  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
289 
290  return cmd;
291 }
292 
293 LinJoint XmlTestdataLoader::getLinJoint(const std::string& cmd_name) const
294 {
295  CmdReader cmd_reader{ findCmd(cmd_name, LINS_PATH_STR, LIN_STR) };
296  std::string planning_group {cmd_reader.getPlanningGroup()};
297 
298  LinJoint cmd;
300  cmd.setVelocityScale(cmd_reader.getVelocityScale());
301  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
302 
303  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
304  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
305 
306  return cmd;
307 }
308 
309 LinCart XmlTestdataLoader::getLinCart(const std::string& cmd_name) const
310 {
311  CmdReader cmd_reader{ findCmd(cmd_name, LINS_PATH_STR, LIN_STR) };
312  std::string planning_group {cmd_reader.getPlanningGroup()};
313 
314  LinCart cmd;
316  cmd.setVelocityScale(cmd_reader.getVelocityScale());
317  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
318 
319  cmd.setStartConfiguration(getPose(cmd_reader.getStartPoseName(), planning_group));
320  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
321 
322  return cmd;
323 }
324 
325 LinJointCart XmlTestdataLoader::getLinJointCart(const std::string& cmd_name) const
326 {
327  CmdReader cmd_reader{ findCmd(cmd_name, LINS_PATH_STR, LIN_STR) };
328  std::string planning_group {cmd_reader.getPlanningGroup()};
329 
332  cmd.setVelocityScale(cmd_reader.getVelocityScale());
333  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
334 
335  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
336  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
337 
338  return cmd;
339 }
340 
341 const pt::ptree::value_type & XmlTestdataLoader::findCmd(const std::string &cmd_name,
342  const std::string& cmd_path,
343  const std::string &cmd_key) const
344 {
345  // Search for node with given name.
346  const boost::property_tree::ptree& cmds_tree {tree_.get_child(cmd_path, empty_tree_)};
347  if (cmds_tree == empty_tree_)
348  {
349  throw TestDataLoaderReadingException("No list of commands of type \"" + cmd_key + "\" found");
350  }
351 
352  return findNodeWithName(cmds_tree, cmd_name, cmd_key);
353 }
354 
356  const std::string &planning_group) const
357 {
358  const pt::ptree::value_type &cmd_node { findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
359  std::string aux_pos_name;
360  try
361  {
362  aux_pos_name = cmd_node.second.get<std::string>(CENTER_POS_STR);
363  }
364  catch(...)
365  {
366  throw TestDataLoaderReadingException("Did not find center of circ");
367  }
368 
369  CartesianCenter aux;
370  aux.setConfiguration(getPose(aux_pos_name, planning_group));
371  return aux;
372 }
373 
375  const std::string &planning_group) const
376 {
377  const pt::ptree::value_type &cmd_node { findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
378  std::string aux_pos_name;
379  try
380  {
381  aux_pos_name = cmd_node.second.get<std::string>(INTERMEDIATE_POS_STR);
382  }
383  catch(...)
384  {
385  throw TestDataLoaderReadingException("Did not find interim of circ");
386  }
387 
388  CartesianInterim aux;
389  aux.setConfiguration(getPose(aux_pos_name, planning_group));
390  return aux;
391 }
392 
394 {
395  CmdReader cmd_reader{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
396  std::string planning_group {cmd_reader.getPlanningGroup()};
397 
400  cmd.setVelocityScale(cmd_reader.getVelocityScale());
401  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
402 
403  cmd.setStartConfiguration(getPose(cmd_reader.getStartPoseName(), planning_group));
405  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
406 
407  return cmd;
408 }
409 
411 {
412  CmdReader cmd_reader{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
413  std::string planning_group {cmd_reader.getPlanningGroup()};
414 
417  cmd.setVelocityScale(cmd_reader.getVelocityScale());
418  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
419 
420  cmd.setStartConfiguration(getPose(cmd_reader.getStartPoseName(), planning_group));
422  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
423 
424  return cmd;
425 }
426 
428 {
429  CmdReader cmd_reader{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
430  std::string planning_group {cmd_reader.getPlanningGroup()};
431 
434  cmd.setVelocityScale(cmd_reader.getVelocityScale());
435  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
436 
437  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
439  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
440 
441  return cmd;
442 }
443 
445 {
446  CmdReader cmd_reader{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
447  std::string planning_group {cmd_reader.getPlanningGroup()};
448 
451  cmd.setVelocityScale(cmd_reader.getVelocityScale());
452  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
453 
454  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
456  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
457 
458  return cmd;
459 }
460 
461 Sequence XmlTestdataLoader::getSequence(const std::string &cmd_name) const
462 {
463  Sequence seq;
464 
465  // Find sequence with given name and loop over all its cmds
466  const auto& sequence_cmd_tree {findCmd(cmd_name, SEQUENCE_PATH_STR, BLEND_STR).second};
467  for (const pt::ptree::value_type& seq_cmd : sequence_cmd_tree)
468  {
469  // Ignore attributes which are always the first element of a tree.
470  if (seq_cmd.first == XML_ATTR_STR){ continue; }
471 
472  // Get name of blend cmd.
473  const boost::property_tree::ptree& cmd_name_attr = seq_cmd.second.get_child(NAME_PATH_STR, empty_tree_);
474  if (cmd_name_attr == empty_tree_)
475  {
476  throw TestDataLoaderReadingException("Did not find name of sequence cmd");
477  }
478 
479  const std::string& cmd_name {cmd_name_attr.data()};
480 
481  // Get type of blend cmd
482  const boost::property_tree::ptree& type_name_attr {seq_cmd.second.get_child(CMD_TYPE_PATH_STR, empty_tree_)};
483  if (type_name_attr == empty_tree_)
484  {
485  throw TestDataLoaderReadingException("Did not find type of sequence cmd \"" + cmd_name + "\"");
486  }
487  const std::string& cmd_type {type_name_attr.data()};
488 
489  // Get blend radius of blend cmd.
490  double blend_radius {seq_cmd.second.get<double>(BLEND_RADIUS_PATH_STR, DEFAULT_BLEND_RADIUS)};
491 
492  // Read current command from test data + Add command to sequence
493  seq.add(cmd_getter_funcs_.at(cmd_type)->getCmd(cmd_name), blend_radius);
494  }
495 
496  return seq;
497 }
498 
499 Gripper XmlTestdataLoader::getGripper(const std::string &cmd_name) const
500 {
501  CmdReader cmd_reader{ findCmd(cmd_name, GRIPPERS_PATH_STR, GRIPPER_STR) };
502  cmd_reader.setDefaultVelocityScale(DEFAULT_VEL_GRIPPER);
503  cmd_reader.setDefaultAccelerationScale(DEFAULT_ACC_GRIPPER);
504  std::string planning_group {cmd_reader.getPlanningGroup()};
505 
506  Gripper cmd;
508  cmd.setVelocityScale(cmd_reader.getVelocityScale());
509  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
510 
511  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
512  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
513 
514  return cmd;
515 }
516 
517 
518 } // namespace pilz_industrial_motion_testutils
static std::vector< double > strVec2doubleVec(std::vector< std::string > &strVec)
Converts string vector to double vector.
static constexpr double DEFAULT_VEL
virtual CircInterimCart getCircCartInterimCart(const std::string &cmd_name) const override
std::map< std::string, AbstractCmdGetterUPtr > cmd_getter_funcs_
CartesianInterim getCartesianInterim(const std::string &cmd_name, const std::string &planning_group) const
virtual LinCart getLinCart(const std::string &cmd_name) const override
const std::string CMD_TYPE_PATH_STR
Definition: xml_constants.h:58
static constexpr double DEFAULT_ACC
virtual CircCenterCart getCircCartCenterCart(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
static constexpr double DEFAULT_VEL_GRIPPER
string cmd
Data class storing all information regarding a Circ command.
Definition: circ.h:32
virtual LinJoint getLinJoint(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
virtual PtpCart getPtpCart(const std::string &cmd_name) const override
virtual LinJointCart getLinJointCart(const std::string &cmd_name) const override
boost::variant< PtpJoint, PtpJointCart, PtpCart, LinJoint, LinCart, CircCenterCart, CircInterimCart, CircJointCenterCart, CircJointInterimCart, Gripper > CmdVariant
planning_group
Implements a test data loader which uses a xml file to store the test data.
void setGoalConfiguration(GoalType goal)
Definition: basecmd.h:66
const std::string BLEND_RADIUS_PATH_STR
Definition: xml_constants.h:59
Data class storing all information regarding a linear command.
Definition: lin.h:31
void setAuxiliaryConfiguration(AuxiliaryType auxiliary)
Definition: circ.h:57
void setStartConfiguration(StartType start)
Definition: basecmd.h:60
data
Abstract base class providing a GENERIC getter-function signature which can be used to load DIFFERENT...
void setPlanningGroup(const std::string &planning_group)
Definition: motioncmd.h:54
Class to define a robot configuration in space with the help of joint values.
const std::string CIRCS_PATH_STR
Definition: xml_constants.h:53
virtual JointConfiguration getJoints(const std::string &pos_name, const std::string &group_name) const override
const std::string GROUP_NAME_PATH_STR
Definition: xml_constants.h:61
virtual Sequence getSequence(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
const pt::ptree::value_type & findNodeWithName(const boost::property_tree::ptree &tree, const std::string &name, const std::string &key, const std::string &path="") const
Use this function to search for a node (like an pos or cmd) with a given name.
void setConfiguration(const ConfigType &auxiliary_config)
Definition: circauxiliary.h:51
const std::string CENTER_POS_STR
Definition: xml_constants.h:45
Data class storing all information regarding a Sequence command.
Definition: sequence.h:36
virtual CircJointCenterCart getCircJointCenterCart(const std::string &cmd_name) const override
const std::string PLANNING_GROUP_STR
Definition: xml_constants.h:40
const std::string SEQUENCE_PATH_STR
Definition: xml_constants.h:54
const std::string LINK_NAME_PATH_STR
Definition: xml_constants.h:60
void add(const CmdVariant &cmd, const double blend_radius=0.)
Adds a command to the end of the sequence.
Definition: sequence.h:86
moveit::core::RobotModelConstPtr robot_model_
virtual CircJointInterimCart getCircJointInterimCart(const std::string &cmd_name) const override
CmdVariant getCmd(const std::string &cmd_name) const override
const std::string GRIPPERS_PATH_STR
Definition: xml_constants.h:55
Abstract base class describing the interface to access test data like robot poses and robot commands...
void setAccelerationScale(double acceleration_scale)
Definition: motioncmd.h:69
void setRobotModel(moveit::core::RobotModelConstPtr robot_model)
static constexpr double DEFAULT_ACC_GRIPPER
void setVelocityScale(double velocity_scale)
Definition: motioncmd.h:64
static constexpr double DEFAULT_BLEND_RADIUS
const pt::ptree::value_type & findCmd(const std::string &cmd_name, const std::string &cmd_path, const std::string &cmd_key) const
Use this function to search for a cmd-node with a given name.
Class to define a point on the circle on which the robot is supposed to move via circ command...
Definition: interim.h:30
const std::string POSES_PATH_STR
Definition: xml_constants.h:50
virtual CartesianConfiguration getPose(const std::string &pos_name, const std::string &group_name) const override
Class to define a robot configuration in space with the help of cartesian coordinates.
const std::string TARGET_LINK_STR
Definition: xml_constants.h:41
Class to define the center point of the circle on which the robot is supposed to move via circ comman...
Definition: center.h:30
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
virtual Gripper getGripper(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
virtual PtpJointCart getPtpJointCart(const std::string &cmd_name) const override
CartesianCenter getCartesianCenter(const std::string &cmd_name, const std::string &planning_group) const
std::function< CmdType(const std::string &)> FuncType
std::unique_ptr< AbstractCmdGetterAdapter > AbstractCmdGetterUPtr
CmdReader(const pt::ptree::value_type &node)
const std::string INTERMEDIATE_POS_STR
Definition: xml_constants.h:44
virtual PtpJoint getPtpJoint(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.


pilz_industrial_motion_testutils
Author(s):
autogenerated on Mon Apr 6 2020 03:17:28