Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
pilz_industrial_motion_testutils::XmlTestdataLoader Class Reference

Implements a test data loader which uses a xml file to store the test data. More...

#include <xml_testdata_loader.h>

Inheritance diagram for pilz_industrial_motion_testutils::XmlTestdataLoader:
Inheritance graph
[legend]

Classes

class  AbstractCmdGetterAdapter
 Abstract base class providing a GENERIC getter-function signature which can be used to load DIFFERENT command types (like Ptp, Lin, etc.) from the test data file. More...
 

Public Member Functions

virtual CircCenterCart getCircCartCenterCart (const std::string &cmd_name) const override
 Returns the command with the specified name from the test data. More...
 
virtual CircInterimCart getCircCartInterimCart (const std::string &cmd_name) const override
 
virtual CircJointCenterCart getCircJointCenterCart (const std::string &cmd_name) const override
 
virtual CircJointInterimCart getCircJointInterimCart (const std::string &cmd_name) const override
 
virtual Gripper getGripper (const std::string &cmd_name) const override
 Returns the command with the specified name from the test data. More...
 
virtual JointConfiguration getJoints (const std::string &pos_name, const std::string &group_name) const override
 
virtual LinCart getLinCart (const std::string &cmd_name) const override
 
virtual LinJoint getLinJoint (const std::string &cmd_name) const override
 Returns the command with the specified name from the test data. More...
 
virtual LinJointCart getLinJointCart (const std::string &cmd_name) const override
 
virtual CartesianConfiguration getPose (const std::string &pos_name, const std::string &group_name) const override
 
virtual PtpCart getPtpCart (const std::string &cmd_name) const override
 
virtual PtpJoint getPtpJoint (const std::string &cmd_name) const override
 Returns the command with the specified name from the test data. More...
 
virtual PtpJointCart getPtpJointCart (const std::string &cmd_name) const override
 
virtual Sequence getSequence (const std::string &cmd_name) const override
 Returns the command with the specified name from the test data. More...
 
 XmlTestdataLoader (const std::string &path_filename)
 
 XmlTestdataLoader (const std::string &path_filename, const moveit::core::RobotModelConstPtr &robot_model)
 
 ~XmlTestdataLoader ()
 
- Public Member Functions inherited from pilz_industrial_motion_testutils::TestdataLoader
void setRobotModel (moveit::core::RobotModelConstPtr robot_model)
 
 TestdataLoader ()=default
 
 TestdataLoader (moveit::core::RobotModelConstPtr robot_model)
 
virtual ~TestdataLoader ()=default
 

Private Types

using AbstractCmdGetterUPtr = std::unique_ptr< AbstractCmdGetterAdapter >
 

Private Member Functions

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. More...
 
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. More...
 
CartesianCenter getCartesianCenter (const std::string &cmd_name, const std::string &planning_group) const
 
CartesianInterim getCartesianInterim (const std::string &cmd_name, const std::string &planning_group) const
 
JointConfiguration getJoints (const boost::property_tree::ptree &joints_tree, const std::string &group_name) const
 

Static Private Member Functions

static std::vector< double > strVec2doubleVec (std::vector< std::string > &strVec)
 Converts string vector to double vector. More...
 

Private Attributes

std::map< std::string, AbstractCmdGetterUPtrcmd_getter_funcs_
 
const pt::ptree empty_tree_ {}
 
const pt::ptree::value_type empty_value_type_ {}
 
std::string path_filename_
 
pt::ptree tree_ {}
 

Additional Inherited Members

- Protected Attributes inherited from pilz_industrial_motion_testutils::TestdataLoader
moveit::core::RobotModelConstPtr robot_model_
 

Detailed Description

Implements a test data loader which uses a xml file to store the test data.

The Xml-file has the following structure:

<testdata>

<poses> <pos name="MyTestPos1"> <joints group_name="manipulator">j1 j2 j3 j4 j5 j6</joints> <xyzQuat group_name="manipulator" link_name="prbt_tcp"> x y z wx wy wz w <seed><joints group_name="manipulator">s1 s2 s3 s4 s5 s6</joints></seed> </xyzQuat> <joints group_name="gripper">j_gripper</joints> </pos>

<pos name="MyTestPos2"> <joints group_name="manipulator">j1 j2 j3 j4 j5 j6</joints> <xyzQuat group_name="manipulator" link_name="prbt_tcp">x y z wx wy wz w</xyzQuat> <joints group_name="gripper">j_gripper</joints> </pos> </poses>

<ptps> <ptp name="MyPtp1"> <startPos>MyTestPos1</startPos> <endPos>MyTestPos2</endPos> <vel>0.1</vel> <acc>0.2</acc> </ptp> </ptps>

<lins> <lin name="MyTestLin1"> <planningGroup>manipulator</planningGroup> <targetLink>prbt_tcp</targetLink> <startPos>MyTestPos1</startPos> <endPos>MyTestPos2</endPos> <vel>0.3</vel> <acc>0.4</acc> </lin> </lins>

<circs> <circ name="MyTestCirc1"> <planningGroup>manipulator</planningGroup> <targetLink>prbt_tcp</targetLink> <startPos>MyTestPos1</startPos> <intermediatePos>MyTestPos1</intermediatePos> <centerPos>MyTestPos2</centerPos> <endPos>MyTestPos1</endPos> <vel>0.2</vel> <acc>0.5</acc> </circ> </circs>

<sequences> <blend name="TestBlend"> <sequenceCmd name="TestPtp" type="ptp" blend_radius="0.2"> <sequenceCmd name="MyTestLin1" type="lin" blend_radius="0.01"> <sequenceCmd name="MyTestCirc1" type="circ" blend_radius="0"> </blend> </sequences>

</testdata>

Definition at line 102 of file xml_testdata_loader.h.

Member Typedef Documentation

◆ AbstractCmdGetterUPtr

Definition at line 181 of file xml_testdata_loader.h.

Constructor & Destructor Documentation

◆ XmlTestdataLoader() [1/2]

pilz_industrial_motion_testutils::XmlTestdataLoader::XmlTestdataLoader ( const std::string &  path_filename)

Definition at line 120 of file xml_testdata_loader.cpp.

◆ XmlTestdataLoader() [2/2]

pilz_industrial_motion_testutils::XmlTestdataLoader::XmlTestdataLoader ( const std::string &  path_filename,
const moveit::core::RobotModelConstPtr &  robot_model 
)

Definition at line 149 of file xml_testdata_loader.cpp.

◆ ~XmlTestdataLoader()

pilz_industrial_motion_testutils::XmlTestdataLoader::~XmlTestdataLoader ( )

Definition at line 156 of file xml_testdata_loader.cpp.

Member Function Documentation

◆ findCmd()

const pt::ptree::value_type & pilz_industrial_motion_testutils::XmlTestdataLoader::findCmd ( const std::string &  cmd_name,
const std::string &  cmd_path,
const std::string &  cmd_key 
) const
private

Use this function to search for a cmd-node with a given name.

Definition at line 357 of file xml_testdata_loader.cpp.

◆ findNodeWithName()

const pt::ptree::value_type & pilz_industrial_motion_testutils::XmlTestdataLoader::findNodeWithName ( const boost::property_tree::ptree &  tree,
const std::string &  name,
const std::string &  key,
const std::string &  path = "" 
) const
private

Use this function to search for a node (like an pos or cmd) with a given name.

Parameters
treeTree containing the node.
nameName of node to look for.

Definition at line 160 of file xml_testdata_loader.cpp.

◆ getCartesianCenter()

CartesianCenter pilz_industrial_motion_testutils::XmlTestdataLoader::getCartesianCenter ( const std::string &  cmd_name,
const std::string &  planning_group 
) const
private

Definition at line 371 of file xml_testdata_loader.cpp.

◆ getCartesianInterim()

CartesianInterim pilz_industrial_motion_testutils::XmlTestdataLoader::getCartesianInterim ( const std::string &  cmd_name,
const std::string &  planning_group 
) const
private

Definition at line 390 of file xml_testdata_loader.cpp.

◆ getCircCartCenterCart()

CircCenterCart pilz_industrial_motion_testutils::XmlTestdataLoader::getCircCartCenterCart ( const std::string &  cmd_name) const
overridevirtual

Returns the command with the specified name from the test data.

Implements pilz_industrial_motion_testutils::TestdataLoader.

Definition at line 409 of file xml_testdata_loader.cpp.

◆ getCircCartInterimCart()

CircInterimCart pilz_industrial_motion_testutils::XmlTestdataLoader::getCircCartInterimCart ( const std::string &  cmd_name) const
overridevirtual

◆ getCircJointCenterCart()

CircJointCenterCart pilz_industrial_motion_testutils::XmlTestdataLoader::getCircJointCenterCart ( const std::string &  cmd_name) const
overridevirtual

◆ getCircJointInterimCart()

CircJointInterimCart pilz_industrial_motion_testutils::XmlTestdataLoader::getCircJointInterimCart ( const std::string &  cmd_name) const
overridevirtual

◆ getGripper()

Gripper pilz_industrial_motion_testutils::XmlTestdataLoader::getGripper ( const std::string &  cmd_name) const
overridevirtual

Returns the command with the specified name from the test data.

Implements pilz_industrial_motion_testutils::TestdataLoader.

Definition at line 518 of file xml_testdata_loader.cpp.

◆ getJoints() [1/2]

JointConfiguration pilz_industrial_motion_testutils::XmlTestdataLoader::getJoints ( const std::string &  pos_name,
const std::string &  group_name 
) const
overridevirtual

◆ getJoints() [2/2]

JointConfiguration pilz_industrial_motion_testutils::XmlTestdataLoader::getJoints ( const boost::property_tree::ptree &  joints_tree,
const std::string &  group_name 
) const
private

Definition at line 214 of file xml_testdata_loader.cpp.

◆ getLinCart()

LinCart pilz_industrial_motion_testutils::XmlTestdataLoader::getLinCart ( const std::string &  cmd_name) const
overridevirtual

◆ getLinJoint()

LinJoint pilz_industrial_motion_testutils::XmlTestdataLoader::getLinJoint ( const std::string &  cmd_name) const
overridevirtual

Returns the command with the specified name from the test data.

Implements pilz_industrial_motion_testutils::TestdataLoader.

Definition at line 309 of file xml_testdata_loader.cpp.

◆ getLinJointCart()

LinJointCart pilz_industrial_motion_testutils::XmlTestdataLoader::getLinJointCart ( const std::string &  cmd_name) const
overridevirtual

◆ getPose()

CartesianConfiguration pilz_industrial_motion_testutils::XmlTestdataLoader::getPose ( const std::string &  pos_name,
const std::string &  group_name 
) const
overridevirtual

◆ getPtpCart()

PtpCart pilz_industrial_motion_testutils::XmlTestdataLoader::getPtpCart ( const std::string &  cmd_name) const
overridevirtual

◆ getPtpJoint()

PtpJoint pilz_industrial_motion_testutils::XmlTestdataLoader::getPtpJoint ( const std::string &  cmd_name) const
overridevirtual

Returns the command with the specified name from the test data.

Implements pilz_industrial_motion_testutils::TestdataLoader.

Definition at line 261 of file xml_testdata_loader.cpp.

◆ getPtpJointCart()

PtpJointCart pilz_industrial_motion_testutils::XmlTestdataLoader::getPtpJointCart ( const std::string &  cmd_name) const
overridevirtual

◆ getSequence()

Sequence pilz_industrial_motion_testutils::XmlTestdataLoader::getSequence ( const std::string &  cmd_name) const
overridevirtual

Returns the command with the specified name from the test data.

Implements pilz_industrial_motion_testutils::TestdataLoader.

Definition at line 477 of file xml_testdata_loader.cpp.

◆ strVec2doubleVec()

std::vector< double > pilz_industrial_motion_testutils::XmlTestdataLoader::strVec2doubleVec ( std::vector< std::string > &  strVec)
inlinestaticprivate

Converts string vector to double vector.

Definition at line 195 of file xml_testdata_loader.h.

Member Data Documentation

◆ cmd_getter_funcs_

std::map<std::string, AbstractCmdGetterUPtr> pilz_industrial_motion_testutils::XmlTestdataLoader::cmd_getter_funcs_
private

Stores the mapping between command type and the getter function which have to be called.

Please note: This mapping is only relevant for sequence commands.

Definition at line 188 of file xml_testdata_loader.h.

◆ empty_tree_

const pt::ptree pilz_industrial_motion_testutils::XmlTestdataLoader::empty_tree_ {}
private

Definition at line 192 of file xml_testdata_loader.h.

◆ empty_value_type_

const pt::ptree::value_type pilz_industrial_motion_testutils::XmlTestdataLoader::empty_value_type_ {}
private

Definition at line 191 of file xml_testdata_loader.h.

◆ path_filename_

std::string pilz_industrial_motion_testutils::XmlTestdataLoader::path_filename_
private

Definition at line 178 of file xml_testdata_loader.h.

◆ tree_

pt::ptree pilz_industrial_motion_testutils::XmlTestdataLoader::tree_ {}
private

Definition at line 179 of file xml_testdata_loader.h.


The documentation for this class was generated from the following files:


pilz_industrial_motion_testutils
Author(s):
autogenerated on Mon Feb 28 2022 23:13:36