21 #include <boost/property_tree/xml_parser.hpp> 22 #include <boost/algorithm/string.hpp> 23 #include <boost/optional.hpp> 29 namespace pt = boost::property_tree;
102 template<
class CmdType>
106 using FuncType = std::function<CmdType(const std::string&)>;
109 : AbstractCmdGetterAdapter()
126 , path_filename_(path_filename)
131 using std::placeholders::_1;
147 const moveit::core::RobotModelConstPtr& robot_model)
160 const std::string &name,
161 const std::string &key,
162 const std::string& path)
const 167 for (
const pt::ptree::value_type& val : tree)
172 if (val.first != key) {
continue;}
174 const auto& node {val.second.get_child(path_str,
empty_tree_)};
176 if (node.data() == name) {
return val; }
180 msg.append(
"Node of type \"").append(key).append(
"\" with ").
181 append(path_str).append(
"=\"").append(name).append(
"\" not found.");
186 const std::string &group_name)
const 198 const std::string &group_name)
const 207 std::vector<std::string> strs;
208 boost::split(strs, joint_node.second.data(), boost::is_any_of(
" "));
213 const std::string &group_name)
const 229 std::string
data {xyz_quat_tree.data()};
232 std::vector<std::string> pos_ori_str;
233 boost::split(pos_ori_str,
data, boost::is_any_of(
" "));
342 const std::string& cmd_path,
343 const std::string &cmd_key)
const 346 const boost::property_tree::ptree& cmds_tree {
tree_.get_child(cmd_path,
empty_tree_)};
356 const std::string &planning_group)
const 359 std::string aux_pos_name;
375 const std::string &planning_group)
const 378 std::string aux_pos_name;
467 for (
const pt::ptree::value_type& seq_cmd : sequence_cmd_tree)
479 const std::string& cmd_name {cmd_name_attr.data()};
487 const std::string& cmd_type {type_name_attr.data()};
static std::vector< double > strVec2doubleVec(std::vector< std::string > &strVec)
Converts string vector to double vector.
static constexpr double DEFAULT_VEL
virtual CircInterimCart getCircCartInterimCart(const std::string &cmd_name) const override
std::map< std::string, AbstractCmdGetterUPtr > cmd_getter_funcs_
CartesianInterim getCartesianInterim(const std::string &cmd_name, const std::string &planning_group) const
virtual LinCart getLinCart(const std::string &cmd_name) const override
const std::string NAME_PATH_STR
const pt::ptree empty_tree_
const std::string CMD_TYPE_PATH_STR
static constexpr double DEFAULT_ACC
virtual CircCenterCart getCircCartCenterCart(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
static constexpr double DEFAULT_VEL_GRIPPER
Data class storing all information regarding a Circ command.
double getAccelerationScale() const
virtual LinJoint getLinJoint(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
virtual PtpCart getPtpCart(const std::string &cmd_name) const override
virtual LinJointCart getLinJointCart(const std::string &cmd_name) const override
boost::variant< PtpJoint, PtpJointCart, PtpCart, LinJoint, LinCart, CircCenterCart, CircInterimCart, CircJointCenterCart, CircJointInterimCart, Gripper > CmdVariant
const std::string ACC_STR
const std::string JOINT_STR
Implements a test data loader which uses a xml file to store the test data.
const std::string GRIPPER_STR
void setGoalConfiguration(GoalType goal)
const std::string BLEND_RADIUS_PATH_STR
Data class storing all information regarding a linear command.
const std::string CIRC_STR
void setAuxiliaryConfiguration(AuxiliaryType auxiliary)
void setStartConfiguration(StartType start)
Abstract base class providing a GENERIC getter-function signature which can be used to load DIFFERENT...
double getVelocityScale() const
void setPlanningGroup(const std::string &planning_group)
Class to define a robot configuration in space with the help of joint values.
const std::string CIRCS_PATH_STR
virtual JointConfiguration getJoints(const std::string &pos_name, const std::string &group_name) const override
const std::string XML_ATTR_STR
const std::string GROUP_NAME_PATH_STR
virtual Sequence getSequence(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
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.
void setConfiguration(const ConfigType &auxiliary_config)
std::string path_filename_
const std::string LIN_STR
const std::string BLEND_STR
const std::string PTPS_PATH_STR
const std::string CENTER_POS_STR
Data class storing all information regarding a Sequence command.
std::string getStartPoseName() const
virtual CircJointCenterCart getCircJointCenterCart(const std::string &cmd_name) const override
const std::string PLANNING_GROUP_STR
const std::string SEQUENCE_PATH_STR
double default_velocity_scale_
const std::string LINK_NAME_PATH_STR
CmdReader & setDefaultAccelerationScale(double scale)
void add(const CmdVariant &cmd, const double blend_radius=0.)
Adds a command to the end of the sequence.
moveit::core::RobotModelConstPtr robot_model_
virtual CircJointInterimCart getCircJointInterimCart(const std::string &cmd_name) const override
CmdVariant getCmd(const std::string &cmd_name) const override
CmdGetterAdapter(FuncType func)
double default_acceleration_scale_
const std::string GRIPPERS_PATH_STR
const std::string PTP_STR
Abstract base class describing the interface to access test data like robot poses and robot commands...
void setAccelerationScale(double acceleration_scale)
void setRobotModel(moveit::core::RobotModelConstPtr robot_model)
const std::string VEL_STR
static constexpr double DEFAULT_ACC_GRIPPER
const std::string END_POS_STR
void setVelocityScale(double velocity_scale)
static constexpr double DEFAULT_BLEND_RADIUS
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.
Class to define a point on the circle on which the robot is supposed to move via circ command...
const std::string LINS_PATH_STR
const std::string POSES_PATH_STR
std::string getTargetLink() const
const std::string POSE_STR
virtual CartesianConfiguration getPose(const std::string &pos_name, const std::string &group_name) const override
Class to define a robot configuration in space with the help of cartesian coordinates.
std::string getEndPoseName() const
const std::string XYZ_QUAT_STR
const std::string TARGET_LINK_STR
Class to define the center point of the circle on which the robot is supposed to move via circ comman...
const pt::ptree::value_type & cmd_node_
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
virtual Gripper getGripper(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
XmlTestdataLoader(const std::string &path_filename)
const std::string SEED_STR
virtual PtpJointCart getPtpJointCart(const std::string &cmd_name) const override
std::string getPlanningGroup() const
CartesianCenter getCartesianCenter(const std::string &cmd_name, const std::string &planning_group) const
CmdReader & setDefaultVelocityScale(double scale)
std::function< CmdType(const std::string &)> FuncType
void setSeed(const JointConfiguration &config)
std::unique_ptr< AbstractCmdGetterAdapter > AbstractCmdGetterUPtr
CmdReader(const pt::ptree::value_type &node)
const std::string INTERMEDIATE_POS_STR
const std::string START_POS_STR
virtual PtpJoint getPtpJoint(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.