2929
3030/* * \author Wim Meeussen, Bjarne von Horn */
3131
32- #ifndef TF2_KDL_H
33- #define TF2_KDL_H
32+ #ifndef TF2_KDL__TF2_KDL_H_
33+ #define TF2_KDL__TF2_KDL_H_
3434
3535#include < tf2/convert.h>
3636#include < tf2/transform_datatypes.h>
4545
4646namespace Eigen
4747{
48- template <typename T, int , int , int , int , int >
48+ // / Forward declaration.
49+ template <typename T, int , int , int , int , int >
4950class Matrix ;
5051}
5152
5253namespace tf2
5354{
5455/* * \brief Convert a timestamped transform to the equivalent KDL data type.
55- * \param t The transform to convert, as a geometry_msgs TransformedStamped message.
56+ * \param[in] t The transform to convert, as a geometry_msgs TransformedStamped message.
5657 * \return The transform message converted to an KDL Frame.
5758 */
5859inline KDL::Frame transformToKDL (const geometry_msgs::msg::TransformStamped & t)
@@ -63,7 +64,7 @@ inline KDL::Frame transformToKDL(const geometry_msgs::msg::TransformStamped & t)
6364}
6465
6566/* * \brief Convert an KDL Frame to the equivalent geometry_msgs message type.
66- * \param k The transform to convert, as an KDL Frame.
67+ * \param[in] k The transform to convert, as an KDL Frame.
6768 * \return The transform converted to a TransformStamped message.
6869 */
6970inline geometry_msgs::msg::TransformStamped kdlToTransform (const KDL::Frame & k)
@@ -75,9 +76,14 @@ inline geometry_msgs::msg::TransformStamped kdlToTransform(const KDL::Frame & k)
7576
7677namespace impl
7778{
78- template <>
79+ // / \brief Conversion implementation for geometry_msgs::msg::Transform and KDL::Frame.
80+ template <>
7981struct ImplDetails <KDL::Frame, geometry_msgs::msg::Transform>
8082{
83+ /* * \brief Convert a Transform message type to a KDL Frame.
84+ * \param[in] in The Transform message to convert.
85+ * \param[out] out The transform converted to a KDL Frame.
86+ */
8187 static void fromMsg (geometry_msgs::msg::Transform const & in, KDL::Frame & out)
8288 {
8389 KDL::Rotation r;
@@ -87,32 +93,41 @@ struct ImplDetails<KDL::Frame, geometry_msgs::msg::Transform>
8793 out = KDL::Frame (r, v);
8894 }
8995
96+ /* * \brief Convert a KDL Frame type to a Transform message.
97+ * \param[in] in The KDL Frame to convert.
98+ * \param[out] out The KDL Frame converted to a Transform message.
99+ */
90100 static void toMsg (KDL::Frame const & in, geometry_msgs::msg::Transform & out)
91101 {
92102 tf2::toMsg<>(in.p , out.translation );
93103 tf2::toMsg<>(in.M , out.rotation );
94104 }
95105};
96106
97- template <>
107+ // / \brief Conversion implementation for geometry_msgs::msg::Vector3 and KDL::Vector.
108+ template <>
98109struct ImplDetails <KDL::Vector, geometry_msgs::msg::Vector3>
99- : DefaultVectorImpl<KDL::Vector, geometry_msgs::msg::Vector3>
110+ : DefaultVectorImpl<KDL::Vector, geometry_msgs::msg::Vector3>
100111{
101112};
102113
103- template <>
114+ // / \brief Conversion implementation for geometry_msgs::msg::Point and KDL::Vector.
115+ template <>
104116struct ImplDetails <KDL::Vector, geometry_msgs::msg::Point>
105- : DefaultVectorImpl<KDL::Vector, geometry_msgs::msg::Point>
117+ : DefaultVectorImpl<KDL::Vector, geometry_msgs::msg::Point>
106118{
107119};
108120
109- template <>
121+ // / \brief Default return type of tf2::toMsg() for KDL::Vector.
122+ template <>
110123struct defaultMessage <KDL::Vector>
111124{
125+ // / \brief Default return type of tf2::toMsg() for KDL::Vector.
112126 using type = geometry_msgs::msg::Point;
113127};
114128
115- template <>
129+ // / \brief Default Type for automatic tf2::doTransform() implementation for KDL::Frame.
130+ template <>
116131struct DefaultTransformType <KDL::Vector>
117132{
118133 using type = KDL::Frame;
@@ -122,24 +137,23 @@ struct DefaultTransformType<KDL::Vector>
122137// Twist
123138// ---------------------
124139
125- template <>
140+ // / \brief Conversion implementation for geometry_msgs::msg::Twist and KDL::Twist.
141+ template <>
126142struct ImplDetails <KDL::Twist, geometry_msgs::msg::Twist>
127143{
128- /* * \brief Convert a stamped KDL Twist type to a TwistStamped message.
129- * This function is a specialization of the toMsg template defined in tf2/convert.h.
130- * \param in The timestamped KDL Twist to convert.
131- * \return The twist converted to a TwistStamped message.
144+ /* * \brief Convert a KDL Twist type to a Twist message.
145+ * \param[in] in The KDL Twist to convert.
146+ * \param[out] msg The twist converted to a Twist message.
132147 */
133148 static void toMsg (const KDL::Twist & in, geometry_msgs::msg::Twist & msg)
134149 {
135150 tf2::toMsg<>(in.vel , msg.linear );
136151 tf2::toMsg<>(in.rot , msg.angular );
137152 }
138153
139- /* * \brief Convert a TwistStamped message type to a stamped KDL-specific Twist type.
140- * This function is a specialization of the fromMsg template defined in tf2/convert.h
141- * \param msg The TwistStamped message to convert.
142- * \param out The twist converted to a timestamped KDL Twist.
154+ /* * \brief Convert a Twistmessage type to a KDL-specific Twist type.
155+ * \param[in] msg The Twist message to convert.
156+ * \param[out] out The twist converted to a KDL Twist.
143157 */
144158 static void fromMsg (const geometry_msgs::msg::Twist & msg, KDL::Twist & out)
145159 {
@@ -148,40 +162,43 @@ struct ImplDetails<KDL::Twist, geometry_msgs::msg::Twist>
148162 }
149163};
150164
151- template <>
165+ // / \brief Default Type for automatic tf2::doTransform() implementation for KDL::Twist.
166+ template <>
152167struct DefaultTransformType <KDL::Twist>
153168{
169+ // / \brief Default Type for automatic tf2::doTransform() implementation for KDL::Twist.
154170 using type = KDL::Frame;
155171};
156172
157- template <>
173+ // / \brief Default return type of tf2::toMsg() for KDL::Twist.
174+ template <>
158175struct defaultMessage <KDL::Twist>
159176{
177+ // / \brief Default return type of tf2::toMsg() for KDL::Twist.
160178 using type = geometry_msgs::msg::Twist;
161179};
162180
163181// ---------------------
164182// Wrench
165183// ---------------------
166184
167- template <>
185+ // / \brief Conversion implementation for geometry_msgs::msg::Wrench and KDL::Wrench.
186+ template <>
168187struct ImplDetails <KDL::Wrench, geometry_msgs::msg::Wrench>
169188{
170- /* * \brief Convert a stamped KDL Wrench type to a WrenchStamped message.
171- * This function is a specialization of the toMsg template defined in tf2/convert.h.
172- * \param in The timestamped KDL Wrench to convert.
173- * \return The wrench converted to a WrenchStamped message.
189+ /* * \brief Convert a KDL Wrench type to a Wrench message.
190+ * \param[in] in The KDL Wrench to convert.
191+ * \param[out] msg The wrench converted to a Wrench message.
174192 */
175193 static void toMsg (const KDL::Wrench & in, geometry_msgs::msg::Wrench & msg)
176194 {
177195 tf2::toMsg<>(in.force , msg.force );
178196 tf2::toMsg<>(in.torque , msg.torque );
179197 }
180198
181- /* * \brief Convert a WrenchStamped message type to a stamped KDL-specific Wrench type.
182- * This function is a specialization of the fromMsg template defined in tf2/convert.h
183- * \param msg The WrenchStamped message to convert.
184- * \param out The wrench converted to a timestamped KDL Wrench.
199+ /* * \brief Convert a Wrench message type to a KDL-specific Wrench type.
200+ * \param[in] msg The Wrench message to convert.
201+ * \param[out] out The wrench converted to a KDL Wrench.
185202 */
186203 static void fromMsg (const geometry_msgs::msg::Wrench & msg, KDL::Wrench & out)
187204 {
@@ -190,20 +207,35 @@ struct ImplDetails<KDL::Wrench, geometry_msgs::msg::Wrench>
190207 }
191208};
192209
193- template <>
210+ // / \brief Default return type of tf2::toMsg() for KDL::Wrench.
211+ template <>
194212struct defaultMessage <KDL::Wrench>
195213{
214+ // / \brief Default return type of tf2::toMsg() for KDL::Wrench.
196215 using type = geometry_msgs::msg::Wrench;
197216};
198217
199- template <>
218+ // / \brief Default Type for automatic tf2::doTransform() implementation for KDL::Wrench.
219+ template <>
200220struct DefaultTransformType <KDL::Wrench>
201221{
222+ // / \brief Default Type for automatic tf2::doTransform() implementation for KDL::Wrench.
202223 using type = KDL::Frame;
203224};
204225} // namespace impl
205226
206- template <int options, int rows, int cols>
227+ /* * \brief Specialization of tf2::convert for Eigen::Matrix<double, 6, 1> and KDL::Wrench.
228+ *
229+ * This specialization of the template defined in tf2/convert.h
230+ * is for a Wrench represented in an Eigen matrix.
231+ * To avoid a dependency on Eigen, the Eigen::Matrix template is forward declared.
232+ * \param[in] in Wrench, as Eigen matrix
233+ * \param[out] out The Wrench as KDL::Wrench type
234+ * \tparam options Eigen::Matrix template parameter
235+ * \tparam row Eigen::Matrix template parameter
236+ * \tparam cols Eigen::Matrix template parameter
237+ */
238+ template <int options, int rows, int cols>
207239void convert (Eigen::Matrix<double , 6 , 1 , options, rows, cols> const & in, KDL::Wrench & out)
208240{
209241 const auto msg =
@@ -216,13 +248,13 @@ void convert(Eigen::Matrix<double, 6, 1, options, rows, cols> const & in, KDL::W
216248// ---------------------
217249namespace impl
218250{
219- template <>
251+ // / \brief Conversion implementation for geometry_msgs::msg::Pose and KDL::Frame.
252+ template <>
220253struct ImplDetails <KDL::Frame, geometry_msgs::msg::Pose>
221254{
222- /* * \brief Convert a stamped KDL Frame type to a Pose message.
223- * This function is a specialization of the toMsg template defined in tf2/convert.h.
224- * \param in The timestamped KDL Frame to convert.
225- * \return The frame converted to a Pose message.
255+ /* * \brief Convert a KDL Frame type to a Pose message.
256+ * \param[in] in The KDL Frame to convert.
257+ * \param[out] msg The frame converted to a Pose message.
226258 */
227259 static void toMsg (const KDL::Frame & in, geometry_msgs::msg::Pose & msg)
228260 {
@@ -231,9 +263,8 @@ struct ImplDetails<KDL::Frame, geometry_msgs::msg::Pose>
231263 }
232264
233265 /* * \brief Convert a Pose message type to a KDL Frame.
234- * This function is a specialization of the fromMsg template defined in tf2/convert.h.
235- * \param msg The Pose message to convert.
236- * \param out The pose converted to a KDL Frame.
266+ * \param[in] msg The Pose message to convert.
267+ * \param[out] out The pose converted to a KDL Frame.
237268 */
238269 static void fromMsg (const geometry_msgs::msg::Pose & msg, KDL::Frame & out)
239270 {
@@ -242,35 +273,50 @@ struct ImplDetails<KDL::Frame, geometry_msgs::msg::Pose>
242273 }
243274};
244275
245- template <>
276+ // / \brief Default return type of tf2::toMsg() for KDL::Frame.
277+ template <>
246278struct defaultMessage <KDL::Frame>
247279{
280+ // / \brief Default return type of tf2::toMsg() for KDL::Frame.
248281 using type = geometry_msgs::msg::Pose;
249282};
250283
251- template <>
284+ // / \brief Default Type for automatic tf2::doTransform() implementation for KDL::Frame.
285+ template <>
252286struct DefaultTransformType <KDL::Frame>
253287{
288+ // / \brief Default Type for automatic tf2::doTransform() implementation for KDL::Frame.
254289 using type = KDL::Frame;
255290};
256291
257- template <>
292+ // / \brief Conversion implementation for geometry_msgs::msg::Quaternion and KDL::Rotation.
293+ template <>
258294struct ImplDetails <KDL::Rotation, geometry_msgs::msg::Quaternion>
259295{
296+ /* * \brief Convert a KDL Rotation type to a Quaternion message.
297+ * \param[in] r The KDL Rotation to convert.
298+ * \param[out] q The frame converted to a Quaternion message.
299+ */
260300 static void toMsg (KDL::Rotation const & r, geometry_msgs::msg::Quaternion & q)
261301 {
262302 r.GetQuaternion (q.x , q.y , q.z , q.w );
263303 }
264304
305+ /* * \brief Convert a Quaternion message type to a KDL Rotation.
306+ * \param[in] q The Quaternion message to convert.
307+ * \param[out] r The quaternion converted to a KDL Rotation.
308+ */
265309 static void fromMsg (geometry_msgs::msg::Quaternion const & q, KDL::Rotation & r)
266310 {
267311 r = KDL::Rotation::Quaternion (q.x , q.y , q.z , q.w );
268312 }
269313};
270314
271- template <>
315+ // / \brief Default return type of tf2::toMsg() for KDL::Rotation.
316+ template <>
272317struct defaultMessage <KDL::Rotation>
273318{
319+ // / \brief Default return type of tf2::toMsg() for KDL::Rotation.
274320 using type = geometry_msgs::msg::Quaternion;
275321};
276322
@@ -279,11 +325,12 @@ struct defaultMessage<KDL::Rotation>
279325/* *
280326 * \brief Transform a KDL::Rotation
281327 *
282- * \param[in] data_in The data to be transformed.
283- * \param[in,out] data_out A reference to the output data.
328+ * \param[in] in The data to be transformed.
329+ * \param[in,out] out A reference to the output data.
284330 * \param[in] transform The transform to apply to data_in to fill data_out.
285331 */
286332template <>
333+ inline
287334void doTransform (
288335 const KDL::Rotation & in, KDL::Rotation & out,
289336 const geometry_msgs::msg::TransformStamped & transform)
@@ -295,4 +342,4 @@ void doTransform(
295342
296343} // namespace tf2
297344
298- #endif // TF2_KDL_H
345+ #endif // TF2_KDL__TF2_KDL_H_
0 commit comments