Robowflex  v0.1
Making MoveIt Easy
yaml.h
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
3 #ifndef ROBOWFLEX_YAML_
4 #define ROBOWFLEX_YAML_
5 
6 #include <ros/time.h>
7 #include <ros/duration.h>
8 
9 #include <std_msgs/Header.h>
10 #include <std_msgs/ColorRGBA.h>
11 
12 #include <geometry_msgs/Vector3.h>
13 #include <geometry_msgs/Point.h>
14 #include <geometry_msgs/Quaternion.h>
15 #include <geometry_msgs/Pose.h>
16 #include <geometry_msgs/Transform.h>
17 #include <geometry_msgs/Twist.h>
18 #include <geometry_msgs/Wrench.h>
19 #include <geometry_msgs/PoseStamped.h>
20 #include <geometry_msgs/TransformStamped.h>
21 
22 #include <shape_msgs/SolidPrimitive.h>
23 #include <shape_msgs/MeshTriangle.h>
24 #include <shape_msgs/Mesh.h>
25 #include <shape_msgs/Plane.h>
26 
27 #include <sensor_msgs/JointState.h>
28 #include <sensor_msgs/MultiDOFJointState.h>
29 
30 #include <octomap_msgs/Octomap.h>
31 #include <octomap_msgs/OctomapWithPose.h>
32 
33 #include <trajectory_msgs/JointTrajectory.h>
34 #include <trajectory_msgs/JointTrajectoryPoint.h>
35 #include <trajectory_msgs/MultiDOFJointTrajectory.h>
36 #include <trajectory_msgs/MultiDOFJointTrajectoryPoint.h>
37 
38 #include <object_recognition_msgs/ObjectType.h>
39 
40 #include <moveit_msgs/LinkPadding.h>
41 #include <moveit_msgs/LinkScale.h>
42 #include <moveit_msgs/ObjectColor.h>
43 #include <moveit_msgs/RobotState.h>
44 #include <moveit_msgs/WorkspaceParameters.h>
45 #include <moveit_msgs/BoundingVolume.h>
46 #include <moveit_msgs/JointConstraint.h>
47 #include <moveit_msgs/PositionConstraint.h>
48 #include <moveit_msgs/OrientationConstraint.h>
49 #include <moveit_msgs/VisibilityConstraint.h>
50 #include <moveit_msgs/TrajectoryConstraints.h>
51 #include <moveit_msgs/RobotTrajectory.h>
52 #include <moveit_msgs/Constraints.h>
53 #include <moveit_msgs/CollisionObject.h>
54 #include <moveit_msgs/AttachedCollisionObject.h>
55 #include <moveit_msgs/AllowedCollisionEntry.h>
56 #include <moveit_msgs/AllowedCollisionMatrix.h>
57 #include <moveit_msgs/PlanningScene.h>
58 #include <moveit_msgs/PlanningSceneWorld.h>
59 #include <moveit_msgs/MotionPlanRequest.h>
60 
61 #include <moveit_msgs/MoveGroupGoal.h>
62 #include <moveit_msgs/MoveGroupResult.h>
63 
64 #include <yaml-cpp/yaml.h>
65 
67 
68 /** \cond IGNORE */
69 namespace YAML
70 {
71 #if ROBOWFLEX_AT_LEAST_KINETIC
72 #else
73  template <>
74  struct convert<signed char>
75  {
76  static Node encode(const signed char &rhs);
77  static bool decode(const Node &node, signed char &rhs);
78  };
79 #endif
80 
81  template <>
82  struct convert<moveit_msgs::PlanningScene>
83  {
84  static Node encode(const moveit_msgs::PlanningScene &rhs);
85  static bool decode(const Node &node, moveit_msgs::PlanningScene &rhs);
86  };
87 
88  template <>
89  struct convert<moveit_msgs::RobotState>
90  {
91  static Node encode(const moveit_msgs::RobotState &rhs);
92  static bool decode(const Node &node, moveit_msgs::RobotState &rhs);
93  };
94 
95  template <>
96  struct convert<geometry_msgs::TransformStamped>
97  {
98  static Node encode(const geometry_msgs::TransformStamped &rhs);
99  static bool decode(const Node &node, geometry_msgs::TransformStamped &rhs);
100  };
101 
102  template <>
103  struct convert<std_msgs::Header>
104  {
105  static Node encode(const std_msgs::Header &rhs);
106  static bool decode(const Node &node, std_msgs::Header &rhs);
107  };
108 
109  template <>
110  struct convert<geometry_msgs::Pose>
111  {
112  static Node encode(const geometry_msgs::Pose &rhs);
113  static bool decode(const Node &node, geometry_msgs::Pose &rhs);
114  };
115 
116  template <>
117  struct convert<geometry_msgs::PoseStamped>
118  {
119  static Node encode(const geometry_msgs::PoseStamped &rhs);
120  static bool decode(const Node &node, geometry_msgs::PoseStamped &rhs);
121  };
122 
123  template <>
124  struct convert<geometry_msgs::Transform>
125  {
126  static Node encode(const geometry_msgs::Transform &rhs);
127  static bool decode(const Node &node, geometry_msgs::Transform &rhs);
128  };
129 
130  template <>
131  struct convert<geometry_msgs::Vector3>
132  {
133  static Node encode(const geometry_msgs::Vector3 &rhs);
134  static bool decode(const Node &node, geometry_msgs::Vector3 &rhs);
135  };
136 
137  template <>
138  struct convert<geometry_msgs::Point>
139  {
140  static Node encode(const geometry_msgs::Point &rhs);
141  static bool decode(const Node &node, geometry_msgs::Point &rhs);
142  };
143 
144  template <>
145  struct convert<geometry_msgs::Quaternion>
146  {
147  static Node encode(const geometry_msgs::Quaternion &rhs);
148  static bool decode(const Node &node, geometry_msgs::Quaternion &rhs);
149  };
150 
151  template <>
152  struct convert<geometry_msgs::Twist>
153  {
154  static Node encode(const geometry_msgs::Twist &rhs);
155  static bool decode(const Node &node, geometry_msgs::Twist &rhs);
156  };
157 
158  template <>
159  struct convert<geometry_msgs::Wrench>
160  {
161  static Node encode(const geometry_msgs::Wrench &rhs);
162  static bool decode(const Node &node, geometry_msgs::Wrench &rhs);
163  };
164 
165  template <>
166  struct convert<sensor_msgs::JointState>
167  {
168  static Node encode(const sensor_msgs::JointState &rhs);
169  static bool decode(const Node &node, sensor_msgs::JointState &rhs);
170  };
171 
172  template <>
173  struct convert<sensor_msgs::MultiDOFJointState>
174  {
175  static Node encode(const sensor_msgs::MultiDOFJointState &rhs);
176  static bool decode(const Node &node, sensor_msgs::MultiDOFJointState &rhs);
177  };
178 
179  template <>
180  struct convert<moveit_msgs::AttachedCollisionObject>
181  {
182  static Node encode(const moveit_msgs::AttachedCollisionObject &rhs);
183  static bool decode(const Node &node, moveit_msgs::AttachedCollisionObject &rhs);
184  };
185 
186  template <>
187  struct convert<trajectory_msgs::JointTrajectory>
188  {
189  static Node encode(const trajectory_msgs::JointTrajectory &rhs);
190  static bool decode(const Node &node, trajectory_msgs::JointTrajectory &rhs);
191  };
192 
193  template <>
194  struct convert<trajectory_msgs::JointTrajectoryPoint>
195  {
196  static Node encode(const trajectory_msgs::JointTrajectoryPoint &rhs);
197  static bool decode(const Node &node, trajectory_msgs::JointTrajectoryPoint &rhs);
198  };
199 
200  template <>
201  struct convert<moveit_msgs::CollisionObject>
202  {
203  static Node encode(const moveit_msgs::CollisionObject &rhs);
204  static bool decode(const Node &node, moveit_msgs::CollisionObject &rhs);
205  };
206 
207  template <>
208  struct convert<object_recognition_msgs::ObjectType>
209  {
210  static Node encode(const object_recognition_msgs::ObjectType &rhs);
211  static bool decode(const Node &node, object_recognition_msgs::ObjectType &rhs);
212  };
213 
214  template <>
215  struct convert<moveit_msgs::LinkPadding>
216  {
217  static Node encode(const moveit_msgs::LinkPadding &rhs);
218  static bool decode(const Node &node, moveit_msgs::LinkPadding &rhs);
219  };
220 
221  template <>
222  struct convert<moveit_msgs::LinkScale>
223  {
224  static Node encode(const moveit_msgs::LinkScale &rhs);
225  static bool decode(const Node &node, moveit_msgs::LinkScale &rhs);
226  };
227 
228  template <>
229  struct convert<moveit_msgs::AllowedCollisionMatrix>
230  {
231  static Node encode(const moveit_msgs::AllowedCollisionMatrix &rhs);
232  static bool decode(const Node &node, moveit_msgs::AllowedCollisionMatrix &rhs);
233  };
234 
235  template <>
236  struct convert<moveit_msgs::AllowedCollisionEntry>
237  {
238  static Node encode(const moveit_msgs::AllowedCollisionEntry &rhs);
239  static bool decode(const Node &node, moveit_msgs::AllowedCollisionEntry &rhs);
240  };
241 
242  template <>
243  struct convert<moveit_msgs::PlanningSceneWorld>
244  {
245  static Node encode(const moveit_msgs::PlanningSceneWorld &rhs);
246  static bool decode(const Node &node, moveit_msgs::PlanningSceneWorld &rhs);
247  };
248 
249  template <>
250  struct convert<moveit_msgs::ObjectColor>
251  {
252  static Node encode(const moveit_msgs::ObjectColor &rhs);
253  static bool decode(const Node &node, moveit_msgs::ObjectColor &rhs);
254  };
255 
256  template <>
257  struct convert<std_msgs::ColorRGBA>
258  {
259  static Node encode(const std_msgs::ColorRGBA &rhs);
260  static bool decode(const Node &node, std_msgs::ColorRGBA &rhs);
261  };
262 
263  template <>
264  struct convert<octomap_msgs::Octomap>
265  {
266  static Node encode(const octomap_msgs::Octomap &rhs);
267  static bool decode(const Node &node, octomap_msgs::Octomap &rhs);
268  };
269 
270  template <>
271  struct convert<octomap_msgs::OctomapWithPose>
272  {
273  static Node encode(const octomap_msgs::OctomapWithPose &rhs);
274  static bool decode(const Node &node, octomap_msgs::OctomapWithPose &rhs);
275  };
276 
277  template <>
278  struct convert<ros::Time>
279  {
280  static Node encode(const ros::Time &rhs);
281  static bool decode(const Node &node, ros::Time &rhs);
282  };
283 
284  template <>
285  struct convert<ros::Duration>
286  {
287  static Node encode(const ros::Duration &rhs);
288  static bool decode(const Node &node, ros::Duration &rhs);
289  };
290 
291  template <>
292  struct convert<shape_msgs::SolidPrimitive>
293  {
294  static Node encode(const shape_msgs::SolidPrimitive &rhs);
295  static bool decode(const Node &node, shape_msgs::SolidPrimitive &rhs);
296  };
297 
298  template <>
299  struct convert<shape_msgs::Mesh>
300  {
301  static Node encode(const shape_msgs::Mesh &rhs);
302  static bool decode(const Node &node, shape_msgs::Mesh &rhs);
303  };
304 
305  template <>
306  struct convert<shape_msgs::MeshTriangle>
307  {
308  static Node encode(const shape_msgs::MeshTriangle &rhs);
309  static bool decode(const Node &node, shape_msgs::MeshTriangle &rhs);
310  };
311 
312  template <>
313  struct convert<shape_msgs::Plane>
314  {
315  static Node encode(const shape_msgs::Plane &rhs);
316  static bool decode(const Node &node, shape_msgs::Plane &rhs);
317  };
318 
319  template <>
320  struct convert<moveit_msgs::WorkspaceParameters>
321  {
322  static Node encode(const moveit_msgs::WorkspaceParameters &rhs);
323  static bool decode(const Node &node, moveit_msgs::WorkspaceParameters &rhs);
324  };
325 
326  template <>
327  struct convert<moveit_msgs::Constraints>
328  {
329  static Node encode(const moveit_msgs::Constraints &rhs);
330  static bool decode(const Node &node, moveit_msgs::Constraints &rhs);
331  };
332 
333  template <>
334  struct convert<moveit_msgs::JointConstraint>
335  {
336  static Node encode(const moveit_msgs::JointConstraint &rhs);
337  static bool decode(const Node &node, moveit_msgs::JointConstraint &rhs);
338  };
339 
340  template <>
341  struct convert<moveit_msgs::PositionConstraint>
342  {
343  static Node encode(const moveit_msgs::PositionConstraint &rhs);
344  static bool decode(const Node &node, moveit_msgs::PositionConstraint &rhs);
345  };
346 
347  template <>
348  struct convert<moveit_msgs::OrientationConstraint>
349  {
350  static Node encode(const moveit_msgs::OrientationConstraint &rhs);
351  static bool decode(const Node &node, moveit_msgs::OrientationConstraint &rhs);
352  };
353 
354  template <>
355  struct convert<moveit_msgs::VisibilityConstraint>
356  {
357  static Node encode(const moveit_msgs::VisibilityConstraint &rhs);
358  static bool decode(const Node &node, moveit_msgs::VisibilityConstraint &rhs);
359  };
360 
361  template <>
362  struct convert<moveit_msgs::TrajectoryConstraints>
363  {
364  static Node encode(const moveit_msgs::TrajectoryConstraints &rhs);
365  static bool decode(const Node &node, moveit_msgs::TrajectoryConstraints &rhs);
366  };
367 
368  template <>
369  struct convert<moveit_msgs::BoundingVolume>
370  {
371  static Node encode(const moveit_msgs::BoundingVolume &rhs);
372  static bool decode(const Node &node, moveit_msgs::BoundingVolume &rhs);
373  };
374 
375  template <>
376  struct convert<moveit_msgs::MotionPlanRequest>
377  {
378  static Node encode(const moveit_msgs::MotionPlanRequest &rhs);
379  static bool decode(const Node &node, moveit_msgs::MotionPlanRequest &rhs);
380  };
381 
382  template <>
383  struct convert<trajectory_msgs::MultiDOFJointTrajectory>
384  {
385  static Node encode(const trajectory_msgs::MultiDOFJointTrajectory &rhs);
386  static bool decode(const Node &node, trajectory_msgs::MultiDOFJointTrajectory &rhs);
387  };
388 
389  template <>
390  struct convert<trajectory_msgs::MultiDOFJointTrajectoryPoint>
391  {
392  static Node encode(const trajectory_msgs::MultiDOFJointTrajectoryPoint &rhs);
393  static bool decode(const Node &node, trajectory_msgs::MultiDOFJointTrajectoryPoint &rhs);
394  };
395 
396  template <>
397  struct convert<moveit_msgs::RobotTrajectory>
398  {
399  static Node encode(const moveit_msgs::RobotTrajectory &rhs);
400  static bool decode(const Node &node, moveit_msgs::RobotTrajectory &rhs);
401  };
402 } // namespace YAML
403 /* \endcond */
404 
405 #endif
Definition: yaml.cpp:174
moveit_msgs::MotionPlanRequest MotionPlanRequest