moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | List of all members
pilz_industrial_motion_planner_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_planner_testutils::XmlTestdataLoader:
Inheritance graph
[legend]
Collaboration diagram for pilz_industrial_motion_planner_testutils::XmlTestdataLoader:
Collaboration 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

 XmlTestdataLoader (const std::string &path_filename)
 
 XmlTestdataLoader (const std::string &path_filename, const moveit::core::RobotModelConstPtr &robot_model)
 
 ~XmlTestdataLoader () override
 
JointConfiguration getJoints (const std::string &pos_name, const std::string &group_name) const override
 
CartesianConfiguration getPose (const std::string &pos_name, const std::string &group_name) const override
 
PtpJoint getPtpJoint (const std::string &cmd_name) const override
 Returns the command with the specified name from the test data. More...
 
PtpCart getPtpCart (const std::string &cmd_name) const override
 
PtpJointCart getPtpJointCart (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. More...
 
LinCart getLinCart (const std::string &cmd_name) const override
 
LinJointCart getLinJointCart (const std::string &cmd_name) const override
 
CircCenterCart getCircCartCenterCart (const std::string &cmd_name) const override
 Returns the command with the specified name from the test data. More...
 
CircInterimCart getCircCartInterimCart (const std::string &cmd_name) const override
 
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. More...
 
Gripper getGripper (const std::string &cmd_name) const override
 Returns the command with the specified name from the test data. More...
 
- Public Member Functions inherited from pilz_industrial_motion_planner_testutils::TestdataLoader
 TestdataLoader ()=default
 
 TestdataLoader (moveit::core::RobotModelConstPtr robot_model)
 
 TestdataLoader (const TestdataLoader &)=default
 
 TestdataLoader (TestdataLoader &&)=default
 
TestdataLoaderoperator= (const TestdataLoader &)=default
 
TestdataLoaderoperator= (TestdataLoader &&)=default
 
virtual ~TestdataLoader ()=default
 
void setRobotModel (moveit::core::RobotModelConstPtr robot_model)
 

Additional Inherited Members

- Protected Attributes inherited from pilz_industrial_motion_planner_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 119 of file xml_testdata_loader.h.

Constructor & Destructor Documentation

◆ XmlTestdataLoader() [1/2]

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

Definition at line 137 of file xml_testdata_loader.cpp.

Here is the call graph for this function:

◆ XmlTestdataLoader() [2/2]

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

Definition at line 166 of file xml_testdata_loader.cpp.

Here is the call graph for this function:

◆ ~XmlTestdataLoader()

pilz_industrial_motion_planner_testutils::XmlTestdataLoader::~XmlTestdataLoader ( )
override

Definition at line 173 of file xml_testdata_loader.cpp.

Member Function Documentation

◆ getCircCartCenterCart()

CircCenterCart pilz_industrial_motion_planner_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_planner_testutils::TestdataLoader.

Definition at line 427 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCircCartInterimCart()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 444 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCircJointCenterCart()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 478 of file xml_testdata_loader.cpp.

Here is the call graph for this function:

◆ getCircJointInterimCart()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 461 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getGripper()

Gripper pilz_industrial_motion_planner_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_planner_testutils::TestdataLoader.

Definition at line 536 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getJoints()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 222 of file xml_testdata_loader.cpp.

Here is the caller graph for this function:

◆ getLinCart()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 344 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getLinJoint()

LinJoint pilz_industrial_motion_planner_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_planner_testutils::TestdataLoader.

Definition at line 328 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getLinJointCart()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 360 of file xml_testdata_loader.cpp.

Here is the call graph for this function:

◆ getPose()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 248 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPtpCart()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 312 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPtpJoint()

PtpJoint pilz_industrial_motion_planner_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_planner_testutils::TestdataLoader.

Definition at line 280 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPtpJointCart()

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

Implements pilz_industrial_motion_planner_testutils::TestdataLoader.

Definition at line 296 of file xml_testdata_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getSequence()

Sequence pilz_industrial_motion_planner_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_planner_testutils::TestdataLoader.

Definition at line 495 of file xml_testdata_loader.cpp.

Here is the call graph for this function:

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