@@ -88,51 +88,9 @@ inline geometry_msgs::msg::TransformStamped eigenToTransform(const Eigen::Isomet
8888
8989namespace impl
9090{
91- /* * \brief Template for Eigen::Isometry3d and Eigen::Affine3d conversion.
92- * \tparam mode Mode argument for Eigen::Transform template
93- */
94- template <int mode>
95- struct EigenTransformImpl
96- {
97- /* * \brief Convert a Transform message to an Eigen type.
98- * \param[in] msg The message to convert.
99- * \param[out] out The converted message, as an Eigen type.
100- */
101- static void fromMsg (
102- const geometry_msgs::msg::Transform & msg, Eigen::Transform<double , 3 , mode> & out)
103- {
104- Eigen::Quaterniond q;
105- Eigen::Vector3d v;
106- tf2::fromMsg<>(msg.rotation , q);
107- tf2::fromMsg<>(msg.translation , v);
108- out = Eigen::Translation3d (v) * q;
109- }
110-
111- /* * \brief Convert an Eigen Transform to a Transform message.
112- * \param[in] in The Eigen Transform to convert.
113- * \param[out] msg The converted Transform, as a message.
114- */
115- static void toMsg (
116- const Eigen::Transform<double , 3 , mode> & in, geometry_msgs::msg::Transform & msg)
117- {
118- tf2::toMsg<>(Eigen::Quaterniond (in.linear ()), msg.rotation );
119- tf2::toMsg<>(Eigen::Vector3d (in.translation ()), msg.translation );
120- }
121- };
122-
123- // / \brief Conversion implementation for geometry_msgs::msg::Transform and Eigen::Affine3d.
124- template <>
125- struct ConversionImplementation <Eigen::Affine3d, geometry_msgs::msg::Transform>
126- : EigenTransformImpl<Eigen::Affine>
127- {
128- };
129-
130- // / \brief Conversion implementation for geometry_msgs::msg::Transform and Eigen::Isometry3d.
131- template <>
132- struct ConversionImplementation <Eigen::Isometry3d, geometry_msgs::msg::Transform>
133- : EigenTransformImpl<Eigen::Isometry>
134- {
135- };
91+ // ---------------------
92+ // Vector
93+ // ---------------------
13694
13795// / \brief Conversion implementation for geometry_msgs::msg::Point and Eigen::Vector3d.
13896template <>
@@ -164,6 +122,11 @@ struct DefaultMessageForDatatype<Eigen::Vector3d>
164122 using type = geometry_msgs::msg::Point;
165123};
166124
125+
126+ // ---------------------
127+ // Quaternion
128+ // ---------------------
129+
167130// / \brief Conversion implementation for geometry_msgs::msg::Quaternion and Eigen::Quaterniond.
168131template <>
169132struct ConversionImplementation <Eigen::Quaterniond, geometry_msgs::msg::Quaternion>
@@ -197,31 +160,57 @@ struct DefaultMessageForDatatype<Eigen::Quaterniond>
197160 // / \brief Default return type of tf2::toMsg() for Eigen::Quaterniond.
198161 using type = geometry_msgs::msg::Quaternion;
199162};
200- } // namespace impl
201163
202- /* * \brief Apply a geometry_msgs TransformStamped to an Eigen-specific Quaterniond type.
203- * This function is a specialization of the doTransform template defined in tf2/convert.h,
204- * although it can not be used in tf2_ros::BufferInterface::transform because this
205- * functions rely on the existence of a time stamp and a frame id in the type which should
206- * get transformed.
207- * \param[in] t_in The vector to transform, as a Eigen Quaterniond data type.
208- * \param[in,out] t_out The transformed vector, as a Eigen Quaterniond data type.
209- * \param[in] transform The timestamped transform to apply, as a TransformStamped message.
164+
165+ // ---------------------
166+ // Transform
167+ // ---------------------
168+
169+ /* * \brief Template for Eigen::Isometry3d and Eigen::Affine3d conversion.
170+ * \tparam mode Mode argument for Eigen::Transform template
210171 */
172+ template <int mode>
173+ struct EigenTransformImpl
174+ {
175+ /* * \brief Convert a Transform message to an Eigen type.
176+ * \param[in] msg The message to convert.
177+ * \param[out] out The converted message, as an Eigen type.
178+ */
179+ static void fromMsg (
180+ const geometry_msgs::msg::Transform & msg, Eigen::Transform<double , 3 , mode> & out)
181+ {
182+ Eigen::Quaterniond q;
183+ Eigen::Vector3d v;
184+ tf2::fromMsg<>(msg.rotation , q);
185+ tf2::fromMsg<>(msg.translation , v);
186+ out = Eigen::Translation3d (v) * q;
187+ }
188+
189+ /* * \brief Convert an Eigen Transform to a Transform message.
190+ * \param[in] in The Eigen Transform to convert.
191+ * \param[out] msg The converted Transform, as a message.
192+ */
193+ static void toMsg (
194+ const Eigen::Transform<double , 3 , mode> & in, geometry_msgs::msg::Transform & msg)
195+ {
196+ tf2::toMsg<>(Eigen::Quaterniond (in.linear ()), msg.rotation );
197+ tf2::toMsg<>(Eigen::Vector3d (in.translation ()), msg.translation );
198+ }
199+ };
200+
201+ // / \brief Conversion implementation for geometry_msgs::msg::Transform and Eigen::Affine3d.
211202template <>
212- inline
213- void doTransform (
214- const Eigen::Quaterniond & t_in,
215- Eigen::Quaterniond & t_out,
216- const geometry_msgs::msg::TransformStamped & transform)
203+ struct ConversionImplementation <Eigen::Affine3d, geometry_msgs::msg::Transform>
204+ : EigenTransformImpl<Eigen::Affine>
217205{
218- Eigen::Quaterniond t;
219- tf2::fromMsg<>(transform.transform .rotation , t);
220- t_out = Eigen::Quaterniond (t.toRotationMatrix () * t_in.toRotationMatrix ());
221- }
206+ };
222207
223- namespace impl
208+ // / \brief Conversion implementation for geometry_msgs::msg::Transform and Eigen::Isometry3d.
209+ template <>
210+ struct ConversionImplementation <Eigen::Isometry3d, geometry_msgs::msg::Transform>
211+ : EigenTransformImpl<Eigen::Isometry>
224212{
213+ };
225214
226215/* * \brief Pose conversion template for Eigen types.
227216 * \tparam T Eigen transform type.
@@ -285,6 +274,11 @@ struct DefaultMessageForDatatype<Eigen::Isometry3d>
285274 using type = geometry_msgs::msg::Pose;
286275};
287276
277+
278+ // ---------------------
279+ // Twist
280+ // ---------------------
281+
288282// / \brief Conversion implementation for geometry_msgs::msg::Twist and Eigen::Matrix<double, 6, 1>.
289283template <>
290284struct ConversionImplementation <Eigen::Matrix<double , 6 , 1 >, geometry_msgs::msg::Twist>
@@ -326,6 +320,11 @@ struct DefaultMessageForDatatype<Eigen::Matrix<double, 6, 1>>
326320 using type = geometry_msgs::msg::Twist;
327321};
328322
323+
324+ // ---------------------
325+ // Wrench
326+ // ---------------------
327+
329328// / \brief Conversion implementation for geometry_msgs::msg::Wrench and Eigen::Matrix<double, 6, 1>.
330329template <>
331330struct ConversionImplementation <Eigen::Matrix<double , 6 , 1 >, geometry_msgs::msg::Wrench>
@@ -393,6 +392,27 @@ inline geometry_msgs::msg::Vector3 toMsg2(const Eigen::Vector3d & in)
393392 msg.z = in[2 ];
394393 return msg;
395394}
395+
396+ /* * \brief Apply a geometry_msgs TransformStamped to an Eigen-specific Quaterniond type.
397+ * This function is a specialization of the doTransform template defined in tf2/convert.h,
398+ * although it can not be used in tf2_ros::BufferInterface::transform because this
399+ * functions rely on the existence of a time stamp and a frame id in the type which should
400+ * get transformed.
401+ * \param[in] t_in The vector to transform, as a Eigen Quaterniond data type.
402+ * \param[in,out] t_out The transformed vector, as a Eigen Quaterniond data type.
403+ * \param[in] transform The timestamped transform to apply, as a TransformStamped message.
404+ */
405+ template <>
406+ inline
407+ void doTransform (
408+ const Eigen::Quaterniond & t_in,
409+ Eigen::Quaterniond & t_out,
410+ const geometry_msgs::msg::TransformStamped & transform)
411+ {
412+ Eigen::Quaterniond t;
413+ tf2::fromMsg<>(transform.transform .rotation , t);
414+ t_out = Eigen::Quaterniond (t.toRotationMatrix () * t_in.toRotationMatrix ());
415+ }
396416} // namespace tf2
397417
398418#endif // TF2_EIGEN__TF2_EIGEN_H_
0 commit comments