moveit2
The MoveIt Motion Planning Framework for ROS 2.
xml_testdata_loader.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 #include <iostream>
38 
39 #include <boost/property_tree/xml_parser.hpp>
40 #include <boost/algorithm/string.hpp>
41 
45 
46 namespace pt = boost::property_tree;
48 {
49 class CmdReader
50 {
51 public:
52  CmdReader(const pt::ptree::value_type& node) : cmd_node_(node)
53  {
54  }
55 
56 public:
57  std::string getPlanningGroup() const;
58  std::string getTargetLink() const;
59  std::string getStartPoseName() const;
60  std::string getEndPoseName() const;
61 
62  double getVelocityScale() const;
63  double getAccelerationScale() const;
64 
65  CmdReader& setDefaultVelocityScale(double scale);
67 
68 private:
69  const pt::ptree::value_type& cmd_node_;
70 
71  double default_velocity_scale_{ DEFAULT_VEL };
72  double default_acceleration_scale_{ DEFAULT_ACC };
73 };
74 
75 inline std::string CmdReader::getPlanningGroup() const
76 {
77  return cmd_node_.second.get<std::string>(PLANNING_GROUP_STR);
78 }
79 
80 inline std::string CmdReader::getTargetLink() const
81 {
82  return cmd_node_.second.get<std::string>(TARGET_LINK_STR);
83 }
84 
85 inline std::string CmdReader::getStartPoseName() const
86 {
87  return cmd_node_.second.get<std::string>(START_POS_STR);
88 }
89 
90 inline std::string CmdReader::getEndPoseName() const
91 {
92  return cmd_node_.second.get<std::string>(END_POS_STR);
93 }
94 
95 inline double CmdReader::getVelocityScale() const
96 {
97  return cmd_node_.second.get<double>(VEL_STR, default_velocity_scale_);
98 }
99 
100 inline double CmdReader::getAccelerationScale() const
101 {
102  return cmd_node_.second.get<double>(ACC_STR, default_acceleration_scale_);
103 }
104 
106 {
107  default_velocity_scale_ = scale;
108  return *this;
109 }
110 
112 {
113  default_acceleration_scale_ = scale;
114  return *this;
115 }
116 
117 template <class CmdType>
119 {
120 public:
121  using FuncType = std::function<CmdType(const std::string&)>;
122 
124  {
125  }
126 
127 public:
128  CmdVariant getCmd(const std::string& cmd_name) const override
129  {
130  return CmdVariant(func_(cmd_name));
131  }
132 
133 private:
134  FuncType func_;
135 };
136 
137 XmlTestdataLoader::XmlTestdataLoader(const std::string& path_filename) : TestdataLoader(), path_filename_(path_filename)
138 {
139  // Parse the XML into the property tree.
140  pt::read_xml(path_filename_, tree_, pt::xml_parser::no_comments);
141 
142  using std::placeholders::_1;
143  cmd_getter_funcs_["ptp"] = AbstractCmdGetterUPtr(
144  new CmdGetterAdapter<PtpJoint>([this](const std::string& cmd) { return getPtpJoint(cmd); }));
145  cmd_getter_funcs_["ptp_joint_cart"] = AbstractCmdGetterUPtr(
146  new CmdGetterAdapter<PtpJointCart>([this](const std::string& cmd) { return getPtpJointCart(cmd); }));
147  cmd_getter_funcs_["ptp_cart_cart"] =
148  AbstractCmdGetterUPtr(new CmdGetterAdapter<PtpCart>([this](const std::string& cmd) { return getPtpCart(cmd); }));
149 
150  cmd_getter_funcs_["lin"] = AbstractCmdGetterUPtr(
151  new CmdGetterAdapter<LinJoint>([this](const std::string& cmd) { return getLinJoint(cmd); }));
152  cmd_getter_funcs_["lin_cart"] =
153  AbstractCmdGetterUPtr(new CmdGetterAdapter<LinCart>([this](const std::string& cmd) { return getLinCart(cmd); }));
154 
155  cmd_getter_funcs_["circ_center_cart"] = AbstractCmdGetterUPtr(
156  new CmdGetterAdapter<CircCenterCart>([this](const std::string& cmd) { return getCircCartCenterCart(cmd); }));
157  cmd_getter_funcs_["circ_interim_cart"] = AbstractCmdGetterUPtr(
158  new CmdGetterAdapter<CircInterimCart>([this](const std::string& cmd) { return getCircCartInterimCart(cmd); }));
159  cmd_getter_funcs_["circ_joint_interim_cart"] = AbstractCmdGetterUPtr(new CmdGetterAdapter<CircJointInterimCart>(
160  [this](const std::string& cmd) { return getCircJointInterimCart(cmd); }));
161 
162  cmd_getter_funcs_["gripper"] =
163  AbstractCmdGetterUPtr(new CmdGetterAdapter<Gripper>([this](const std::string& cmd) { return getGripper(cmd); }));
164 }
165 
166 XmlTestdataLoader::XmlTestdataLoader(const std::string& path_filename,
167  const moveit::core::RobotModelConstPtr& robot_model)
168  : XmlTestdataLoader(path_filename)
169 {
170  setRobotModel(robot_model);
171 }
172 
174 {
175 }
176 
177 const pt::ptree::value_type& XmlTestdataLoader::findNodeWithName(const boost::property_tree::ptree& tree,
178  const std::string& name, const std::string& key,
179  const std::string& path) const
180 {
181  std::string path_str{ (path.empty() ? NAME_PATH_STR : path) };
182 
183  // Search for node with given name.
184  for (const pt::ptree::value_type& val : tree)
185  {
186  // Ignore attributes which are always the first element of a tree.
187  if (val.first == XML_ATTR_STR)
188  {
189  continue;
190  }
191 
192  if (val.first != key)
193  {
194  continue;
195  }
196 
197  const auto& node{ val.second.get_child(path_str, empty_tree_) };
198  if (node == empty_tree_)
199  {
200  break;
201  }
202  if (node.data() == name)
203  {
204  return val;
205  }
206  }
207 
208  std::string msg;
209  msg.append("Node of type \"")
210  .append(key)
211  .append("\" with ")
212  .append(path_str)
213  .append("=\"")
214  .append(name)
215  .append("\" "
216  "not "
217  "foun"
218  "d.");
219  throw TestDataLoaderReadingException(msg);
220 }
221 
222 JointConfiguration XmlTestdataLoader::getJoints(const std::string& pos_name, const std::string& group_name) const
223 {
224  // Search for node with given name.
225  const auto& poses_tree{ tree_.get_child(POSES_PATH_STR, empty_tree_) };
226  if (poses_tree == empty_tree_)
227  {
228  throw TestDataLoaderReadingException("No poses found.");
229  }
230  return getJoints(findNodeWithName(poses_tree, pos_name, POSE_STR).second, group_name);
231 }
232 
233 JointConfiguration XmlTestdataLoader::getJoints(const boost::property_tree::ptree& joints_tree,
234  const std::string& group_name) const
235 {
236  // Search joints node with given group_name.
237  if (joints_tree == empty_tree_)
238  {
239  throw TestDataLoaderReadingException("No joints found.");
240  }
241  const auto& joint_node{ findNodeWithName(joints_tree, group_name, JOINT_STR, GROUP_NAME_PATH_STR) };
242 
243  std::vector<std::string> strs;
244  boost::split(strs, joint_node.second.data(), boost::is_any_of(" "));
245  return JointConfiguration(group_name, strVec2doubleVec(strs), robot_model_);
246 }
247 
248 CartesianConfiguration XmlTestdataLoader::getPose(const std::string& pos_name, const std::string& group_name) const
249 {
250  const auto& all_poses_tree{ tree_.get_child(POSES_PATH_STR, empty_tree_) };
251  if (all_poses_tree == empty_tree_)
252  {
253  throw TestDataLoaderReadingException("No poses found.");
254  }
255  const auto& pose_tree{ findNodeWithName(all_poses_tree, pos_name, POSE_STR).second };
256  const auto& xyz_quat_tree{ findNodeWithName(pose_tree, group_name, XYZ_QUAT_STR, GROUP_NAME_PATH_STR).second };
257  const boost::property_tree::ptree& link_name_attr{ xyz_quat_tree.get_child(LINK_NAME_PATH_STR, empty_tree_) };
258  if (link_name_attr == empty_tree_)
259  {
260  throw TestDataLoaderReadingException("No link name found.");
261  }
262 
263  // Get rid of things like "\n", etc.
264  std::string data{ xyz_quat_tree.data() };
265  boost::trim(data);
266 
267  std::vector<std::string> pos_ori_str;
268  boost::split(pos_ori_str, data, boost::is_any_of(" "));
269  CartesianConfiguration cart_config{ CartesianConfiguration(group_name, link_name_attr.data(),
270  strVec2doubleVec(pos_ori_str), robot_model_) };
271 
272  const auto& seeds_tree{ xyz_quat_tree.get_child(SEED_STR, empty_tree_) };
273  if (seeds_tree != empty_tree_)
274  {
275  cart_config.setSeed(getJoints(seeds_tree, group_name));
276  }
277  return cart_config;
278 }
279 
280 PtpJoint XmlTestdataLoader::getPtpJoint(const std::string& cmd_name) const
281 {
282  CmdReader cmd_reader{ findCmd(cmd_name, PTPS_PATH_STR, PTP_STR) };
283  std::string planning_group{ cmd_reader.getPlanningGroup() };
284 
285  PtpJoint cmd;
286  cmd.setPlanningGroup(planning_group);
287  cmd.setVelocityScale(cmd_reader.getVelocityScale());
288  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
289 
290  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
291  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
292 
293  return cmd;
294 }
295 
296 PtpJointCart XmlTestdataLoader::getPtpJointCart(const std::string& cmd_name) const
297 {
298  CmdReader cmd_reader{ findCmd(cmd_name, PTPS_PATH_STR, PTP_STR) };
299  std::string planning_group{ cmd_reader.getPlanningGroup() };
300 
301  PtpJointCart cmd;
302  cmd.setPlanningGroup(planning_group);
303  cmd.setVelocityScale(cmd_reader.getVelocityScale());
304  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
305 
306  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
307  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
308 
309  return cmd;
310 }
311 
312 PtpCart XmlTestdataLoader::getPtpCart(const std::string& cmd_name) const
313 {
314  CmdReader cmd_reader{ findCmd(cmd_name, PTPS_PATH_STR, PTP_STR) };
315  std::string planning_group{ cmd_reader.getPlanningGroup() };
316 
317  PtpCart cmd;
318  cmd.setPlanningGroup(planning_group);
319  cmd.setVelocityScale(cmd_reader.getVelocityScale());
320  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
321 
322  cmd.setStartConfiguration(getPose(cmd_reader.getStartPoseName(), planning_group));
323  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
324 
325  return cmd;
326 }
327 
328 LinJoint XmlTestdataLoader::getLinJoint(const std::string& cmd_name) const
329 {
330  CmdReader cmd_reader{ findCmd(cmd_name, LINS_PATH_STR, LIN_STR) };
331  std::string planning_group{ cmd_reader.getPlanningGroup() };
332 
333  LinJoint cmd;
334  cmd.setPlanningGroup(planning_group);
335  cmd.setVelocityScale(cmd_reader.getVelocityScale());
336  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
337 
338  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
339  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
340 
341  return cmd;
342 }
343 
344 LinCart XmlTestdataLoader::getLinCart(const std::string& cmd_name) const
345 {
346  CmdReader cmd_reader{ findCmd(cmd_name, LINS_PATH_STR, LIN_STR) };
347  std::string planning_group{ cmd_reader.getPlanningGroup() };
348 
349  LinCart cmd;
350  cmd.setPlanningGroup(planning_group);
351  cmd.setVelocityScale(cmd_reader.getVelocityScale());
352  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
353 
354  cmd.setStartConfiguration(getPose(cmd_reader.getStartPoseName(), planning_group));
355  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
356 
357  return cmd;
358 }
359 
360 LinJointCart XmlTestdataLoader::getLinJointCart(const std::string& cmd_name) const
361 {
362  CmdReader cmd_reader{ findCmd(cmd_name, LINS_PATH_STR, LIN_STR) };
363  std::string planning_group{ cmd_reader.getPlanningGroup() };
364 
365  LinJointCart cmd;
366  cmd.setPlanningGroup(planning_group);
367  cmd.setVelocityScale(cmd_reader.getVelocityScale());
368  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
369 
370  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
371  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
372 
373  return cmd;
374 }
375 
376 const pt::ptree::value_type& XmlTestdataLoader::findCmd(const std::string& cmd_name, const std::string& cmd_path,
377  const std::string& cmd_key) const
378 {
379  // Search for node with given name.
380  const boost::property_tree::ptree& cmds_tree{ tree_.get_child(cmd_path, empty_tree_) };
381  if (cmds_tree == empty_tree_)
382  {
383  throw TestDataLoaderReadingException("No list of commands of type \"" + cmd_key + "\" found");
384  }
385 
386  return findNodeWithName(cmds_tree, cmd_name, cmd_key);
387 }
388 
389 CartesianCenter XmlTestdataLoader::getCartesianCenter(const std::string& cmd_name,
390  const std::string& planning_group) const
391 {
392  const pt::ptree::value_type& cmd_node{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
393  std::string aux_pos_name;
394  try
395  {
396  aux_pos_name = cmd_node.second.get<std::string>(CENTER_POS_STR);
397  }
398  catch (...)
399  {
400  throw TestDataLoaderReadingException("Did not find center of circ");
401  }
402 
403  CartesianCenter aux;
404  aux.setConfiguration(getPose(aux_pos_name, planning_group));
405  return aux;
406 }
407 
408 CartesianInterim XmlTestdataLoader::getCartesianInterim(const std::string& cmd_name,
409  const std::string& planning_group) const
410 {
411  const pt::ptree::value_type& cmd_node{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
412  std::string aux_pos_name;
413  try
414  {
415  aux_pos_name = cmd_node.second.get<std::string>(INTERMEDIATE_POS_STR);
416  }
417  catch (...)
418  {
419  throw TestDataLoaderReadingException("Did not find interim of circ");
420  }
421 
422  CartesianInterim aux;
423  aux.setConfiguration(getPose(aux_pos_name, planning_group));
424  return aux;
425 }
426 
428 {
429  CmdReader cmd_reader{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
430  std::string planning_group{ cmd_reader.getPlanningGroup() };
431 
432  CircCenterCart cmd;
433  cmd.setPlanningGroup(planning_group);
434  cmd.setVelocityScale(cmd_reader.getVelocityScale());
435  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
436 
437  cmd.setStartConfiguration(getPose(cmd_reader.getStartPoseName(), planning_group));
438  cmd.setAuxiliaryConfiguration(getCartesianCenter(cmd_name, planning_group));
439  cmd.setGoalConfiguration(getPose(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 
449  CircInterimCart cmd;
450  cmd.setPlanningGroup(planning_group);
451  cmd.setVelocityScale(cmd_reader.getVelocityScale());
452  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
453 
454  cmd.setStartConfiguration(getPose(cmd_reader.getStartPoseName(), planning_group));
455  cmd.setAuxiliaryConfiguration(getCartesianInterim(cmd_name, planning_group));
456  cmd.setGoalConfiguration(getPose(cmd_reader.getEndPoseName(), planning_group));
457 
458  return cmd;
459 }
460 
462 {
463  CmdReader cmd_reader{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
464  std::string planning_group{ cmd_reader.getPlanningGroup() };
465 
467  cmd.setPlanningGroup(planning_group);
468  cmd.setVelocityScale(cmd_reader.getVelocityScale());
469  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
470 
471  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
472  cmd.setAuxiliaryConfiguration(getCartesianInterim(cmd_name, planning_group));
473  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
474 
475  return cmd;
476 }
477 
479 {
480  CmdReader cmd_reader{ findCmd(cmd_name, CIRCS_PATH_STR, CIRC_STR) };
481  std::string planning_group{ cmd_reader.getPlanningGroup() };
482 
484  cmd.setPlanningGroup(planning_group);
485  cmd.setVelocityScale(cmd_reader.getVelocityScale());
486  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
487 
488  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
489  cmd.setAuxiliaryConfiguration(getCartesianCenter(cmd_name, planning_group));
490  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
491 
492  return cmd;
493 }
494 
495 Sequence XmlTestdataLoader::getSequence(const std::string& cmd_name) const
496 {
497  Sequence seq;
498 
499  // Find sequence with given name and loop over all its cmds
500  const auto& sequence_cmd_tree{ findCmd(cmd_name, SEQUENCE_PATH_STR, BLEND_STR).second };
501  for (const pt::ptree::value_type& seq_cmd : sequence_cmd_tree)
502  {
503  // Ignore attributes which are always the first element of a tree.
504  if (seq_cmd.first == XML_ATTR_STR)
505  {
506  continue;
507  }
508 
509  // Get name of blend cmd.
510  const boost::property_tree::ptree& cmd_name_attr = seq_cmd.second.get_child(NAME_PATH_STR, empty_tree_);
511  if (cmd_name_attr == empty_tree_)
512  {
513  throw TestDataLoaderReadingException("Did not find name of sequence cmd");
514  }
515 
516  const std::string& cmd_name{ cmd_name_attr.data() };
517 
518  // Get type of blend cmd
519  const boost::property_tree::ptree& type_name_attr{ seq_cmd.second.get_child(CMD_TYPE_PATH_STR, empty_tree_) };
520  if (type_name_attr == empty_tree_)
521  {
522  throw TestDataLoaderReadingException("Did not find type of sequence cmd \"" + cmd_name + "\"");
523  }
524  const std::string& cmd_type{ type_name_attr.data() };
525 
526  // Get blend radius of blend cmd.
527  double blend_radius{ seq_cmd.second.get<double>(BLEND_RADIUS_PATH_STR, DEFAULT_BLEND_RADIUS) };
528 
529  // Read current command from test data + Add command to sequence
530  seq.add(cmd_getter_funcs_.at(cmd_type)->getCmd(cmd_name), blend_radius);
531  }
532 
533  return seq;
534 }
535 
536 Gripper XmlTestdataLoader::getGripper(const std::string& cmd_name) const
537 {
538  CmdReader cmd_reader{ findCmd(cmd_name, GRIPPERS_PATH_STR, GRIPPER_STR) };
539  cmd_reader.setDefaultVelocityScale(DEFAULT_VEL_GRIPPER);
540  cmd_reader.setDefaultAccelerationScale(DEFAULT_ACC_GRIPPER);
541  std::string planning_group{ cmd_reader.getPlanningGroup() };
542 
543  Gripper cmd;
544  cmd.setPlanningGroup(planning_group);
545  cmd.setVelocityScale(cmd_reader.getVelocityScale());
546  cmd.setAccelerationScale(cmd_reader.getAccelerationScale());
547 
548  cmd.setStartConfiguration(getJoints(cmd_reader.getStartPoseName(), planning_group));
549  cmd.setGoalConfiguration(getJoints(cmd_reader.getEndPoseName(), planning_group));
550 
551  return cmd;
552 }
553 
554 } // namespace pilz_industrial_motion_planner_testutils
Class to define a robot configuration in space with the help of cartesian coordinates.
Data class storing all information regarding a Circ command.
Definition: circ.h:49
void setAuxiliaryConfiguration(AuxiliaryType auxiliary)
Definition: circ.h:72
CmdVariant getCmd(const std::string &cmd_name) const override
std::function< CmdType(const std::string &)> FuncType
Class to define a robot configuration in space with the help of joint values.
Data class storing all information regarding a linear command.
Definition: lin.h:48
void setAccelerationScale(double acceleration_scale)
Definition: motioncmd.h:84
void setPlanningGroup(const std::string &planning_group)
Definition: motioncmd.h:69
void setVelocityScale(double velocity_scale)
Definition: motioncmd.h:79
Data class storing all information regarding a Sequence command.
Definition: sequence.h:54
void add(const CmdVariant &cmd, const double blend_radius=0.)
Adds a command to the end of the sequence.
Definition: sequence.h:103
Abstract base class describing the interface to access test data like robot poses and robot commands.
void setRobotModel(moveit::core::RobotModelConstPtr robot_model)
Abstract base class providing a GENERIC getter-function signature which can be used to load DIFFERENT...
Implements a test data loader which uses a xml file to store the test data.
CircCenterCart getCircCartCenterCart(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
JointConfiguration getJoints(const std::string &pos_name, const std::string &group_name) const override
LinJointCart getLinJointCart(const std::string &cmd_name) const override
PtpCart getPtpCart(const std::string &cmd_name) const override
CircInterimCart getCircCartInterimCart(const std::string &cmd_name) const override
CartesianConfiguration getPose(const std::string &pos_name, const std::string &group_name) const override
PtpJointCart getPtpJointCart(const std::string &cmd_name) const override
LinCart getLinCart(const std::string &cmd_name) const override
LinJoint getLinJoint(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
CircJointCenterCart getCircJointCenterCart(const std::string &cmd_name) const override
CircJointInterimCart getCircJointInterimCart(const std::string &cmd_name) const override
Sequence getSequence(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
Gripper getGripper(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
PtpJoint getPtpJoint(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
Interim< CartesianConfiguration, CartesianPathConstraintsBuilder > CartesianInterim
std::variant< PtpJoint, PtpJointCart, PtpCart, LinJoint, LinCart, CircCenterCart, CircInterimCart, CircJointCenterCart, CircJointInterimCart, Gripper > CmdVariant
Center< CartesianConfiguration, CartesianPathConstraintsBuilder > CartesianCenter
name
Definition: setup.py:7