3535#include < tf2/convert.h>
3636#include < tf2/LinearMath/Quaternion.h>
3737#include < tf2/LinearMath/Transform.h>
38+ #include < tf2/LinearMath/Vector3.h>
3839#include < tf2_ros/buffer_interface.h>
3940#include < geometry_msgs/msg/point_stamped.hpp>
4041#include < geometry_msgs/msg/quaternion_stamped.hpp>
@@ -60,6 +61,35 @@ KDL::Frame gmTransformToKDL(const geometry_msgs::msg::TransformStamped& t)
6061 KDL::Vector (t.transform .translation .x , t.transform .translation .y , t.transform .translation .z ));
6162 }
6263
64+ /* ************/
65+ /* * Vector3 **/
66+ /* ************/
67+
68+ /* * \brief Convert a tf2 Vector3 type to its equivalent geometry_msgs representation.
69+ * This function is a specialization of the toMsg template defined in tf2/convert.h.
70+ * \param in A tf2 Vector3 object.
71+ * \return The Vector3 converted to a geometry_msgs message type.
72+ */
73+ inline
74+ geometry_msgs::msg::Vector3 toMsg (const tf2::Vector3& in)
75+ {
76+ geometry_msgs::msg::Vector3 out;
77+ out.x = in.getX ();
78+ out.y = in.getY ();
79+ out.z = in.getZ ();
80+ return out;
81+ }
82+
83+ /* * \brief Convert a Vector3 message to its equivalent tf2 representation.
84+ * This function is a specialization of the fromMsg template defined in tf2/convert.h.
85+ * \param in A Vector3 message type.
86+ * \param out The Vector3 converted to a tf2 type.
87+ */
88+ inline
89+ void fromMsg (const geometry_msgs::msg::Vector3& in, tf2::Vector3& out)
90+ {
91+ out = tf2::Vector3 (in.x , in.y , in.z );
92+ }
6393
6494/* *******************/
6595/* * Vector3Stamped **/
@@ -124,6 +154,35 @@ void fromMsg(const geometry_msgs::msg::Vector3Stamped& msg, geometry_msgs::msg::
124154}
125155
126156
157+ /* **********/
158+ /* * Point **/
159+ /* **********/
160+
161+ /* * \brief Convert a tf2 Vector3 type to its equivalent geometry_msgs representation.
162+ * This function is a specialization of the toMsg template defined in tf2/convert.h.
163+ * \param in A tf2 Vector3 object.
164+ * \return The Vector3 converted to a geometry_msgs message type.
165+ */
166+ inline
167+ geometry_msgs::msg::Point& toMsg (const tf2::Vector3& in, geometry_msgs::msg::Point& out)
168+ {
169+ out.x = in.getX ();
170+ out.y = in.getY ();
171+ out.z = in.getZ ();
172+ return out;
173+ }
174+
175+ /* * \brief Convert a Vector3 message to its equivalent tf2 representation.
176+ * This function is a specialization of the fromMsg template defined in tf2/convert.h.
177+ * \param in A Vector3 message type.
178+ * \param out The Vector3 converted to a tf2 type.
179+ */
180+ inline
181+ void fromMsg (const geometry_msgs::msg::Point& in, tf2::Vector3& out)
182+ {
183+ out = tf2::Vector3 (in.x , in.y , in.z );
184+ }
185+
127186
128187/* *****************/
129188/* * PointStamped **/
0 commit comments