kdl_msg.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Adam Leeper
30  */
31 
32 #ifndef CONVERSIONS_KDL_MSG_H
33 #define CONVERSIONS_KDL_MSG_H
34 
35 #include "kdl/frames.hpp"
36 #include <geometry_msgs/Point.h>
37 #include <geometry_msgs/Pose.h>
38 #include <geometry_msgs/Quaternion.h>
39 #include <geometry_msgs/Transform.h>
40 #include <geometry_msgs/Twist.h>
41 #include <geometry_msgs/Vector3.h>
42 #include <geometry_msgs/Wrench.h>
43 
44 
45 namespace tf {
47 
49 void pointMsgToKDL(const geometry_msgs::Point &m, KDL::Vector &k);
50 
52 void pointKDLToMsg(const KDL::Vector &k, geometry_msgs::Point &m);
53 
55 void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k);
56 
58 void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m);
59 
61 void quaternionMsgToKDL(const geometry_msgs::Quaternion &m, KDL::Rotation &k);
62 
64 void quaternionKDLToMsg(const KDL::Rotation &k, geometry_msgs::Quaternion &m);
65 
67 void transformMsgToKDL(const geometry_msgs::Transform &m, KDL::Frame &k);
68 
70 void transformKDLToMsg(const KDL::Frame &k, geometry_msgs::Transform &m);
71 
73 void twistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k);
74 
76 void twistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m);
77 
79 void vectorMsgToKDL(const geometry_msgs::Vector3 &m, KDL::Vector &k);
80 
82 void vectorKDLToMsg(const KDL::Vector &k, geometry_msgs::Vector3 &m);
83 
85 void wrenchMsgToKDL(const geometry_msgs::Wrench &m, KDL::Wrench &k);
86 
88 void wrenchKDLToMsg(const KDL::Wrench &k, geometry_msgs::Wrench &m);
89 
90 
91 //Deprecated methods use above:
93 void PoseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)__attribute__((deprecated));
94 
96 void PoseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m) __attribute__((deprecated));
97 
98 
99 
101 void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k) __attribute__((deprecated));
102 
104 void TwistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m) __attribute__((deprecated));
105 
106 
107 
108 }
109 
110 
111 #endif
112 
113 
114 
void vectorKDLToMsg(const KDL::Vector &k, geometry_msgs::Vector3 &m)
Converts a KDL Vector into a Vector3 message.
Definition: kdl_msg.cpp:121
void transformKDLToMsg(const KDL::Frame &k, geometry_msgs::Transform &m)
Converts a KDL Frame into a Transform message.
Definition: kdl_msg.cpp:85
void twistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k)
Converts a Twist message into a KDL Twist.
Definition: kdl_msg.cpp:104
Definition: kdl_msg.h:45
void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k) __attribute__((deprecated))
Converts a Twist message into a KDL Twist.
Definition: kdl_msg.cpp:158
void quaternionMsgToKDL(const geometry_msgs::Quaternion &m, KDL::Rotation &k)
Converts a quaternion message into a KDL Rotation.
Definition: kdl_msg.cpp:66
void transformMsgToKDL(const geometry_msgs::Transform &m, KDL::Frame &k)
Converts a Transform message into a KDL Frame.
Definition: kdl_msg.cpp:76
void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)
Converts a Pose message into a KDL Frame.
Definition: kdl_msg.cpp:48
void twistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m)
Converts a KDL Twist into a Twist message.
Definition: kdl_msg.cpp:94
void PoseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m) __attribute__((deprecated))
Converts a KDL Frame into a Pose message.
Definition: kdl_msg.cpp:155
void wrenchMsgToKDL(const geometry_msgs::Wrench &m, KDL::Wrench &k)
Converts a Wrench message into a KDL Wrench.
Definition: kdl_msg.cpp:128
void quaternionKDLToMsg(const KDL::Rotation &k, geometry_msgs::Quaternion &m)
Converts a KDL Rotation into a message quaternion.
Definition: kdl_msg.cpp:71
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
Converts a KDL Frame into a Pose message.
Definition: kdl_msg.cpp:57
void pointKDLToMsg(const KDL::Vector &k, geometry_msgs::Point &m)
Converts a KDL Vector into a geometry_msgs Vector3.
Definition: kdl_msg.cpp:41
void pointMsgToKDL(const geometry_msgs::Point &m, KDL::Vector &k)
Conversion functions from/to the corresponding KDL and geometry_msgs types.
Definition: kdl_msg.cpp:34
void PoseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k) __attribute__((deprecated))
Converts a Pose message into a KDL Frame.
Definition: kdl_msg.cpp:152
void wrenchKDLToMsg(const KDL::Wrench &k, geometry_msgs::Wrench &m)
Converts a KDL Wrench into a Wrench message.
Definition: kdl_msg.cpp:138
void TwistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m) __attribute__((deprecated))
Converts a KDL Twist into a Twist message.
Definition: kdl_msg.cpp:161
void vectorMsgToKDL(const geometry_msgs::Vector3 &m, KDL::Vector &k)
Converts a Vector3 message into a KDL Vector.
Definition: kdl_msg.cpp:114


kdl_conversions
Author(s): Adam Leeper
autogenerated on Mon Jun 10 2019 12:25:24