Namespaces | Classes | Typedefs | Functions | Variables
pilz_industrial_motion_testutils Namespace Reference

Namespaces

 acceptance_test_utils
 
 integration_test_utils
 
 robot_motion_observer
 
 xml_testdata_loader
 

Classes

class  BaseCmd
 
class  CartesianConfiguration
 Class to define a robot configuration in space with the help of cartesian coordinates. More...
 
class  CartesianPathConstraintsBuilder
 Helper class to build moveit_msgs::Constraints from a given configuration. More...
 
class  Center
 Class to define the center point of the circle on which the robot is supposed to move via circ command. More...
 
class  Circ
 Data class storing all information regarding a Circ command. More...
 
class  CircAuxiliary
 Base class to define an auxiliary point needed to specify circ commands. More...
 
class  CmdGetterAdapter
 
class  CmdReader
 
class  GoalConstraintMsgConvertible
 Interface class to express that a derived class can be converted into a moveit_msgs::Constaints. More...
 
class  Gripper
 
class  Interim
 Class to define a point on the circle on which the robot is supposed to move via circ command. More...
 
class  JointConfiguration
 Class to define a robot configuration in space with the help of joint values. More...
 
class  JointConfigurationException
 
class  Lin
 Data class storing all information regarding a linear command. More...
 
class  MotionCmd
 Base class for commands storing all general information of a command. More...
 
class  MotionPlanRequestConvertible
 Interface class to express that a derived class can be converted into a planning_interface::MotionPlanRequest. More...
 
class  Ptp
 Data class storing all information regarding a Ptp command. More...
 
class  RobotConfiguration
 Class to define robot configuration in space. More...
 
class  RobotStateMsgConvertible
 Interface class to express that a derived class can be converted into a moveit_msgs::RobotState. More...
 
class  Sequence
 Data class storing all information regarding a Sequence command. More...
 
class  TestdataLoader
 Abstract base class describing the interface to access test data like robot poses and robot commands. More...
 
class  TestDataLoaderReadingException
 
class  ToBaseVisitor
 Visitor returning not the specific command type but the base type. More...
 
class  ToReqVisitor
 Visitor transforming the stored command into a MotionPlanRequest. More...
 
class  XmlTestdataLoader
 Implements a test data loader which uses a xml file to store the test data. More...
 

Typedefs

using CartesianCenter = Center< CartesianConfiguration, CartesianPathConstraintsBuilder >
 
using CartesianInterim = Interim< CartesianConfiguration, CartesianPathConstraintsBuilder >
 
typedef Circ< CartesianConfiguration, CartesianCenter, CartesianConfigurationCircCenterCart
 
typedef Circ< CartesianConfiguration, CartesianInterim, CartesianConfigurationCircInterimCart
 
typedef Circ< JointConfiguration, CartesianCenter, JointConfigurationCircJointCenterCart
 
typedef Circ< JointConfiguration, CartesianInterim, JointConfigurationCircJointInterimCart
 
typedef boost::variant< PtpJoint, PtpJointCart, PtpCart, LinJoint, LinCart, CircCenterCart, CircInterimCart, CircJointCenterCart, CircJointInterimCart, GripperCmdVariant
 
using CreateJointNameFunc = std::function< std::string(const size_t &)>
 
typedef Lin< CartesianConfiguration, CartesianConfigurationLinCart
 
typedef Lin< JointConfiguration, JointConfigurationLinJoint
 
typedef Lin< JointConfiguration, CartesianConfigurationLinJointCart
 
using MotionCmdUPtr = std::unique_ptr< MotionCmd >
 
typedef Ptp< CartesianConfiguration, CartesianConfigurationPtpCart
 
typedef Ptp< JointConfiguration, JointConfigurationPtpJoint
 
typedef Ptp< JointConfiguration, CartesianConfigurationPtpJointCart
 
using TestdataLoaderUPtr = std::unique_ptr< TestdataLoader >
 
using XmlTestDataLoaderUPtr = std::unique_ptr< TestdataLoader >
 

Functions

::testing::AssertionResult isAtExpectedPosition (const robot_state::RobotState &expected, const robot_state::RobotState &actual, const double epsilon)
 
std::ostream & operator<< (std::ostream &, const JointConfiguration &)
 
std::ostream & operator<< (std::ostream &, const CartesianConfiguration &)
 

Variables

const std::string ACC_STR {"acc"}
 
const std::string BLEND_RADIUS_PATH_STR {XML_ATTR_STR + ".blend_radius"}
 
const std::string BLEND_STR {"blend"}
 
const std::string CENTER_POS_STR {"centerPos"}
 
const std::string CIRC_STR {"circ"}
 
const std::string CIRCS_PATH_STR {"testdata." + CIRC_STR + "s"}
 
const std::string CMD_TYPE_PATH_STR {XML_ATTR_STR + ".type"}
 
static constexpr double DEFAULT_ACC {0.01}
 
static constexpr double DEFAULT_ACC_GRIPPER {0.8}
 
static constexpr double DEFAULT_BLEND_RADIUS {0.01}
 
static constexpr double DEFAULT_VEL {0.01}
 
static constexpr double DEFAULT_VEL_GRIPPER {0.5}
 
const std::string EMPTY_STR {}
 
const std::string END_POS_STR {"endPos"}
 
const std::string GRIPPER_STR {"gripper"}
 
const std::string GRIPPERS_PATH_STR {"testdata." + GRIPPER_STR + "s"}
 
const std::string GROUP_NAME_PATH_STR {XML_ATTR_STR + ".group_name"}
 
const std::string INTERMEDIATE_POS_STR {"intermediatePos"}
 
const std::string JOINT_STR {"joints"}
 
const std::string LIN_STR {"lin"}
 
const std::string LINK_NAME_PATH_STR {XML_ATTR_STR + ".link_name"}
 
const std::string LINS_PATH_STR {"testdata." + LIN_STR + "s"}
 
const std::string NAME_PATH_STR {XML_ATTR_STR + ".name"}
 
const std::string PLANNING_GROUP_STR {"planningGroup"}
 
const std::string POSE_STR {"pos"}
 
const std::string POSES_PATH_STR {"testdata.poses"}
 
const std::string PTP_STR {"ptp"}
 
const std::string PTPS_PATH_STR {"testdata." + PTP_STR + "s"}
 
const std::string SEED_STR {"seed"}
 
const std::string SEQUENCE_PATH_STR {"testdata.sequences"}
 
const std::string START_POS_STR {"startPos"}
 
const std::string TARGET_LINK_STR {"targetLink"}
 
const std::string VEL_STR {"vel"}
 
const std::string XML_ATTR_STR {"<xmlattr>"}
 
const std::string XYZ_EULER_STR {"xyzEuler"}
 
const std::string XYZ_QUAT_STR {"xyzQuat"}
 

Typedef Documentation

Definition at line 28 of file circ_auxiliary_types.h.

Definition at line 29 of file circ_auxiliary_types.h.

Definition at line 41 of file command_types_typedef.h.

Definition at line 42 of file command_types_typedef.h.

Definition at line 44 of file command_types_typedef.h.

Definition at line 45 of file command_types_typedef.h.

Definition at line 52 of file command_types_typedef.h.

using pilz_industrial_motion_testutils::CreateJointNameFunc = typedef std::function<std::string(const size_t&)>

Definition at line 42 of file jointconfiguration.h.

Definition at line 39 of file command_types_typedef.h.

Definition at line 37 of file command_types_typedef.h.

Definition at line 38 of file command_types_typedef.h.

Definition at line 74 of file motioncmd.h.

Definition at line 35 of file command_types_typedef.h.

Definition at line 33 of file command_types_typedef.h.

Definition at line 34 of file command_types_typedef.h.

Definition at line 98 of file testdata_loader.h.

Definition at line 215 of file xml_testdata_loader.h.

Function Documentation

::testing::AssertionResult pilz_industrial_motion_testutils::isAtExpectedPosition ( const robot_state::RobotState &  expected,
const robot_state::RobotState &  actual,
const double  epsilon 
)

Definition at line 26 of file checks.h.

std::ostream & pilz_industrial_motion_testutils::operator<< ( std::ostream &  os,
const JointConfiguration obj 
)

Definition at line 132 of file jointconfiguration.cpp.

std::ostream & pilz_industrial_motion_testutils::operator<< ( std::ostream &  os,
const CartesianConfiguration obj 
)

Definition at line 110 of file cartesianconfiguration.cpp.

Variable Documentation

const std::string pilz_industrial_motion_testutils::ACC_STR {"acc"}

Definition at line 47 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::BLEND_RADIUS_PATH_STR {XML_ATTR_STR + ".blend_radius"}

Definition at line 59 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::BLEND_STR {"blend"}

Definition at line 37 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::CENTER_POS_STR {"centerPos"}

Definition at line 45 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::CIRC_STR {"circ"}

Definition at line 36 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::CIRCS_PATH_STR {"testdata." + CIRC_STR + "s"}

Definition at line 53 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::CMD_TYPE_PATH_STR {XML_ATTR_STR + ".type"}

Definition at line 58 of file xml_constants.h.

constexpr double pilz_industrial_motion_testutils::DEFAULT_ACC {0.01}
static

Definition at line 27 of file default_values.h.

constexpr double pilz_industrial_motion_testutils::DEFAULT_ACC_GRIPPER {0.8}
static

Definition at line 31 of file default_values.h.

constexpr double pilz_industrial_motion_testutils::DEFAULT_BLEND_RADIUS {0.01}
static

Definition at line 28 of file default_values.h.

constexpr double pilz_industrial_motion_testutils::DEFAULT_VEL {0.01}
static

Definition at line 26 of file default_values.h.

constexpr double pilz_industrial_motion_testutils::DEFAULT_VEL_GRIPPER {0.5}
static

Definition at line 30 of file default_values.h.

const std::string pilz_industrial_motion_testutils::EMPTY_STR {}

Definition at line 25 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::END_POS_STR {"endPos"}

Definition at line 43 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::GRIPPER_STR {"gripper"}

Definition at line 38 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::GRIPPERS_PATH_STR {"testdata." + GRIPPER_STR + "s"}

Definition at line 55 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::GROUP_NAME_PATH_STR {XML_ATTR_STR + ".group_name"}

Definition at line 61 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::INTERMEDIATE_POS_STR {"intermediatePos"}

Definition at line 44 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::JOINT_STR {"joints"}

Definition at line 28 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::LIN_STR {"lin"}

Definition at line 35 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::LINK_NAME_PATH_STR {XML_ATTR_STR + ".link_name"}

Definition at line 60 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::LINS_PATH_STR {"testdata." + LIN_STR + "s"}

Definition at line 52 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::NAME_PATH_STR {XML_ATTR_STR + ".name"}

Definition at line 57 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::PLANNING_GROUP_STR {"planningGroup"}

Definition at line 40 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::POSE_STR {"pos"}

Definition at line 29 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::POSES_PATH_STR {"testdata.poses"}

Definition at line 50 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::PTP_STR {"ptp"}

Definition at line 34 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::PTPS_PATH_STR {"testdata." + PTP_STR + "s"}

Definition at line 51 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::SEED_STR {"seed"}

Definition at line 32 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::SEQUENCE_PATH_STR {"testdata.sequences"}

Definition at line 54 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::START_POS_STR {"startPos"}

Definition at line 42 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::TARGET_LINK_STR {"targetLink"}

Definition at line 41 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::VEL_STR {"vel"}

Definition at line 46 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::XML_ATTR_STR {"<xmlattr>"}

Definition at line 27 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::XYZ_EULER_STR {"xyzEuler"}

Definition at line 31 of file xml_constants.h.

const std::string pilz_industrial_motion_testutils::XYZ_QUAT_STR {"xyzQuat"}

Definition at line 30 of file xml_constants.h.



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