moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
xml_testdata_loader.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2018 Pilz GmbH & Co. KG
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35#pragma once
36
37#include <string>
38#include <vector>
39#include <functional>
40#include <map>
41#include <memory>
42
43#include <boost/property_tree/ptree.hpp>
44
46
47namespace pt = boost::property_tree;
49{
120{
121public:
122 XmlTestdataLoader(const std::string& path_filename);
123 XmlTestdataLoader(const std::string& path_filename, const moveit::core::RobotModelConstPtr& robot_model);
124 ~XmlTestdataLoader() override;
125
126public:
127 JointConfiguration getJoints(const std::string& pos_name, const std::string& group_name) const override;
128
129 CartesianConfiguration getPose(const std::string& pos_name, const std::string& group_name) const override;
130
131 PtpJoint getPtpJoint(const std::string& cmd_name) const override;
132 PtpCart getPtpCart(const std::string& cmd_name) const override;
133 PtpJointCart getPtpJointCart(const std::string& cmd_name) const override;
134
135 LinJoint getLinJoint(const std::string& cmd_name) const override;
136 LinCart getLinCart(const std::string& cmd_name) const override;
137 LinJointCart getLinJointCart(const std::string& cmd_name) const override;
138
139 CircCenterCart getCircCartCenterCart(const std::string& cmd_name) const override;
140 CircInterimCart getCircCartInterimCart(const std::string& cmd_name) const override;
141 CircJointCenterCart getCircJointCenterCart(const std::string& cmd_name) const override;
142 CircJointInterimCart getCircJointInterimCart(const std::string& cmd_name) const override;
143
144 Sequence getSequence(const std::string& cmd_name) const override;
145
146 Gripper getGripper(const std::string& cmd_name) const override;
147
148private:
156 const pt::ptree::value_type& findNodeWithName(const boost::property_tree::ptree& tree, const std::string& name,
157 const std::string& key, const std::string& path = "") const;
158
162 const pt::ptree::value_type& findCmd(const std::string& cmd_name, const std::string& cmd_path,
163 const std::string& cmd_key) const;
164
165 CartesianCenter getCartesianCenter(const std::string& cmd_name, const std::string& planning_group) const;
166
167 CartesianInterim getCartesianInterim(const std::string& cmd_name, const std::string& planning_group) const;
168
169private:
170 JointConfiguration getJoints(const boost::property_tree::ptree& joints_tree, const std::string& group_name) const;
171
172private:
176 static inline std::vector<double> strVec2doubleVec(std::vector<std::string>& strVec);
177
178public:
196
197private:
198 std::string path_filename_;
199 pt::ptree tree_{};
200
201 using AbstractCmdGetterUPtr = std::unique_ptr<AbstractCmdGetterAdapter>;
202
208 std::map<std::string, AbstractCmdGetterUPtr> cmd_getter_funcs_;
209
210private:
211 const pt::ptree::value_type empty_value_type_{};
212 const pt::ptree empty_tree_{};
213};
214
215std::vector<double> XmlTestdataLoader::strVec2doubleVec(std::vector<std::string>& strVec)
216{
217 std::vector<double> vec;
218
219 vec.resize(strVec.size());
220 std::transform(strVec.begin(), strVec.end(), vec.begin(), [](const std::string& val) { return std::stod(val); });
221
222 return vec;
223}
224
225using XmlTestDataLoaderUPtr = std::unique_ptr<TestdataLoader>;
226} // namespace pilz_industrial_motion_planner_testutils
Class to define a robot configuration in space with the help of cartesian coordinates.
Class to define the center point of the circle on which the robot is supposed to move via circ comman...
Definition center.h:47
Data class storing all information regarding a Circ command.
Definition circ.h:49
Class to define a point on the circle on which the robot is supposed to move via circ command.
Definition interim.h:47
Class to define a robot configuration in space with the help of joint values.
Data class storing all information regarding a linear command.
Definition lin.h:48
Data class storing all information regarding a Sequence command.
Definition sequence.h:54
Abstract base class describing the interface to access test data like robot poses and robot commands.
Abstract base class providing a GENERIC getter-function signature which can be used to load DIFFERENT...
AbstractCmdGetterAdapter & operator=(AbstractCmdGetterAdapter &&)=default
AbstractCmdGetterAdapter & operator=(const AbstractCmdGetterAdapter &)=default
Implements a test data loader which uses a xml file to store the test data.
CircCenterCart getCircCartCenterCart(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
JointConfiguration getJoints(const std::string &pos_name, const std::string &group_name) const override
LinJointCart getLinJointCart(const std::string &cmd_name) const override
PtpCart getPtpCart(const std::string &cmd_name) const override
CircInterimCart getCircCartInterimCart(const std::string &cmd_name) const override
CartesianConfiguration getPose(const std::string &pos_name, const std::string &group_name) const override
PtpJointCart getPtpJointCart(const std::string &cmd_name) const override
LinCart getLinCart(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.
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.
Gripper getGripper(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
PtpJoint getPtpJoint(const std::string &cmd_name) const override
Returns the command with the specified name from the test data.
std::variant< PtpJoint, PtpJointCart, PtpCart, LinJoint, LinCart, CircCenterCart, CircInterimCart, CircJointCenterCart, CircJointInterimCart, Gripper > CmdVariant
std::unique_ptr< TestdataLoader > XmlTestDataLoaderUPtr