Implements a test data loader which uses a xml file to store the test data. More...
#include <xml_testdata_loader.h>
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, AbstractCmdGetterUPtr > | cmd_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_ |
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 103 of file xml_testdata_loader.h.
|
private |
Definition at line 188 of file xml_testdata_loader.h.
pilz_industrial_motion_testutils::XmlTestdataLoader::XmlTestdataLoader | ( | const std::string & | path_filename | ) |
Definition at line 124 of file xml_testdata_loader.cpp.
pilz_industrial_motion_testutils::XmlTestdataLoader::XmlTestdataLoader | ( | const std::string & | path_filename, |
const moveit::core::RobotModelConstPtr & | robot_model | ||
) |
Definition at line 146 of file xml_testdata_loader.cpp.
pilz_industrial_motion_testutils::XmlTestdataLoader::~XmlTestdataLoader | ( | ) |
Definition at line 154 of file xml_testdata_loader.cpp.
|
private |
Use this function to search for a cmd-node with a given name.
Definition at line 341 of file xml_testdata_loader.cpp.
|
private |
Use this function to search for a node (like an pos or cmd) with a given name.
tree | Tree containing the node. |
name | Name of node to look for. |
Definition at line 159 of file xml_testdata_loader.cpp.
|
private |
Definition at line 355 of file xml_testdata_loader.cpp.
|
private |
Definition at line 374 of file xml_testdata_loader.cpp.
|
overridevirtual |
Returns the command with the specified name from the test data.
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 393 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 410 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 444 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 427 of file xml_testdata_loader.cpp.
|
overridevirtual |
Returns the command with the specified name from the test data.
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 499 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 185 of file xml_testdata_loader.cpp.
|
private |
Definition at line 197 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 309 of file xml_testdata_loader.cpp.
|
overridevirtual |
Returns the command with the specified name from the test data.
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 293 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 325 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 212 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 277 of file xml_testdata_loader.cpp.
|
overridevirtual |
Returns the command with the specified name from the test data.
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 245 of file xml_testdata_loader.cpp.
|
overridevirtual |
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 261 of file xml_testdata_loader.cpp.
|
overridevirtual |
Returns the command with the specified name from the test data.
Implements pilz_industrial_motion_testutils::TestdataLoader.
Definition at line 461 of file xml_testdata_loader.cpp.
|
inlinestaticprivate |
Converts string vector to double vector.
Definition at line 202 of file xml_testdata_loader.h.
|
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 195 of file xml_testdata_loader.h.
|
private |
Definition at line 199 of file xml_testdata_loader.h.
|
private |
Definition at line 198 of file xml_testdata_loader.h.
|
private |
Definition at line 185 of file xml_testdata_loader.h.
|
private |
Definition at line 186 of file xml_testdata_loader.h.