tf2_eigen.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) Koji Terada
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *
00014  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00015  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00016  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00017  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00018  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00019  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00020  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00021  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00022  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00023  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00024  * POSSIBILITY OF SUCH DAMAGE.
00025  */
00026 
00029 #ifndef TF2_EIGEN_H
00030 #define TF2_EIGEN_H
00031 
00032 #include <tf2/convert.h>
00033 #include <Eigen/Geometry>
00034 #include <geometry_msgs/QuaternionStamped.h>
00035 #include <geometry_msgs/PointStamped.h>
00036 #include <geometry_msgs/PoseStamped.h>
00037 #include <geometry_msgs/Twist.h>
00038 
00039 
00040 namespace tf2
00041 {
00042 
00047  inline
00048  Eigen::Isometry3d transformToEigen(const geometry_msgs::Transform& t) {
00049  return Eigen::Isometry3d(Eigen::Translation3d(t.translation.x, t.translation.y, t.translation.z)
00050                          * Eigen::Quaterniond(t.rotation.w, t.rotation.x, t.rotation.y, t.rotation.z));
00051 }
00052 
00057 inline
00058 Eigen::Isometry3d transformToEigen(const geometry_msgs::TransformStamped& t) {
00059   return transformToEigen(t.transform);
00060 }
00061 
00066 inline
00067 geometry_msgs::TransformStamped eigenToTransform(const Eigen::Affine3d& T)
00068 {
00069   geometry_msgs::TransformStamped t;
00070   t.transform.translation.x = T.translation().x();
00071   t.transform.translation.y = T.translation().y();
00072   t.transform.translation.z = T.translation().z();
00073 
00074   Eigen::Quaterniond q(T.linear());  // assuming that upper 3x3 matrix is orthonormal
00075   t.transform.rotation.x = q.x();
00076   t.transform.rotation.y = q.y();
00077   t.transform.rotation.z = q.z();
00078   t.transform.rotation.w = q.w();
00079 
00080   return t;
00081 }
00082 
00087 inline
00088 geometry_msgs::TransformStamped eigenToTransform(const Eigen::Isometry3d& T)
00089 {
00090   geometry_msgs::TransformStamped t;
00091   t.transform.translation.x = T.translation().x();
00092   t.transform.translation.y = T.translation().y();
00093   t.transform.translation.z = T.translation().z();
00094 
00095   Eigen::Quaterniond q(T.rotation());
00096   t.transform.rotation.x = q.x();
00097   t.transform.rotation.y = q.y();
00098   t.transform.rotation.z = q.z();
00099   t.transform.rotation.w = q.w();
00100 
00101   return t;
00102 }
00103 
00113 template <>
00114 inline
00115 void doTransform(const Eigen::Vector3d& t_in, Eigen::Vector3d& t_out, const geometry_msgs::TransformStamped& transform)
00116 {
00117   t_out = Eigen::Vector3d(transformToEigen(transform) * t_in);
00118 }
00119 
00125 inline
00126 geometry_msgs::Point toMsg(const Eigen::Vector3d& in)
00127 {
00128   geometry_msgs::Point msg;
00129   msg.x = in.x();
00130   msg.y = in.y();
00131   msg.z = in.z();
00132   return msg;
00133 }
00134 
00140 inline
00141 void fromMsg(const geometry_msgs::Point& msg, Eigen::Vector3d& out)
00142 {
00143   out.x() = msg.x;
00144   out.y() = msg.y;
00145   out.z() = msg.z;
00146 }
00147 
00153 inline
00154 geometry_msgs::Vector3& toMsg(const Eigen::Vector3d& in, geometry_msgs::Vector3& out)
00155 {
00156   out.x = in.x();
00157   out.y = in.y();
00158   out.z = in.z();
00159   return out;
00160 }
00161 
00167 inline
00168 void fromMsg(const geometry_msgs::Vector3& msg, Eigen::Vector3d& out)
00169 {
00170   out.x() = msg.x;
00171   out.y() = msg.y;
00172   out.z() = msg.z;
00173 }
00174 
00181 template <>
00182 inline
00183 void doTransform(const tf2::Stamped<Eigen::Vector3d>& t_in,
00184                  tf2::Stamped<Eigen::Vector3d>& t_out,
00185                  const geometry_msgs::TransformStamped& transform) {
00186   t_out = tf2::Stamped<Eigen::Vector3d>(transformToEigen(transform) * t_in,
00187                                         transform.header.stamp,
00188                                         transform.header.frame_id);
00189 }
00190 
00196 inline
00197 geometry_msgs::PointStamped toMsg(const tf2::Stamped<Eigen::Vector3d>& in)
00198 {
00199   geometry_msgs::PointStamped msg;
00200   msg.header.stamp = in.stamp_;
00201   msg.header.frame_id = in.frame_id_;
00202   msg.point = toMsg(static_cast<const Eigen::Vector3d&>(in));
00203   return msg;
00204 }
00205 
00211 inline
00212 void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped<Eigen::Vector3d>& out) {
00213   out.stamp_ = msg.header.stamp;
00214   out.frame_id_ = msg.header.frame_id;
00215   fromMsg(msg.point, static_cast<Eigen::Vector3d&>(out));
00216 }
00217 
00227 template <>
00228 inline
00229 void doTransform(const Eigen::Affine3d& t_in,
00230                  Eigen::Affine3d& t_out,
00231                  const geometry_msgs::TransformStamped& transform) {
00232   t_out = Eigen::Affine3d(transformToEigen(transform) * t_in);
00233 }
00234 
00235 template <>
00236 inline
00237 void doTransform(const Eigen::Isometry3d& t_in,
00238                  Eigen::Isometry3d& t_out,
00239                  const geometry_msgs::TransformStamped& transform) {
00240   t_out = Eigen::Isometry3d(transformToEigen(transform) * t_in);
00241 }
00242 
00248 inline
00249 geometry_msgs::Quaternion toMsg(const Eigen::Quaterniond& in) {
00250  geometry_msgs::Quaternion msg;
00251  msg.w = in.w();
00252  msg.x = in.x();
00253  msg.y = in.y();
00254  msg.z = in.z();
00255  return msg;
00256 }
00257 
00263 inline
00264 void fromMsg(const geometry_msgs::Quaternion& msg, Eigen::Quaterniond& out) {
00265   out = Eigen::Quaterniond(msg.w, msg.x, msg.y, msg.z);
00266 }
00267 
00277 template<>
00278 inline
00279 void doTransform(const Eigen::Quaterniond& t_in,
00280                  Eigen::Quaterniond& t_out,
00281                  const geometry_msgs::TransformStamped& transform) {
00282   Eigen::Quaterniond t;
00283   fromMsg(transform.transform.rotation, t);
00284   t_out = t.inverse() * t_in * t;
00285 }
00286 
00292 inline
00293 geometry_msgs::QuaternionStamped toMsg(const Stamped<Eigen::Quaterniond>& in) {
00294   geometry_msgs::QuaternionStamped msg;
00295   msg.header.stamp = in.stamp_;
00296   msg.header.frame_id = in.frame_id_;
00297   msg.quaternion = toMsg(static_cast<const Eigen::Quaterniond&>(in));
00298   return msg;
00299 }
00300 
00306 inline
00307 void fromMsg(const geometry_msgs::QuaternionStamped& msg, Stamped<Eigen::Quaterniond>& out) {
00308   out.frame_id_ = msg.header.frame_id;
00309   out.stamp_ = msg.header.stamp;
00310   fromMsg(msg.quaternion, static_cast<Eigen::Quaterniond&>(out));
00311 }
00312 
00319 template <>
00320 inline
00321 void doTransform(const tf2::Stamped<Eigen::Quaterniond>& t_in,
00322      tf2::Stamped<Eigen::Quaterniond>& t_out,
00323      const geometry_msgs::TransformStamped& transform) {
00324   t_out.frame_id_ = transform.header.frame_id;
00325   t_out.stamp_ = transform.header.stamp;
00326   doTransform(static_cast<const Eigen::Quaterniond&>(t_in), static_cast<Eigen::Quaterniond&>(t_out), transform);
00327 }
00328 
00334 inline
00335 geometry_msgs::Pose toMsg(const Eigen::Affine3d& in) {
00336   geometry_msgs::Pose msg;
00337   msg.position.x = in.translation().x();
00338   msg.position.y = in.translation().y();
00339   msg.position.z = in.translation().z();
00340   Eigen::Quaterniond q(in.linear());
00341   msg.orientation.x = q.x();
00342   msg.orientation.y = q.y();
00343   msg.orientation.z = q.z();
00344   msg.orientation.w = q.w();
00345   if (msg.orientation.w < 0) {
00346     msg.orientation.x *= -1;
00347     msg.orientation.y *= -1;
00348     msg.orientation.z *= -1;
00349     msg.orientation.w *= -1;
00350   }
00351   return msg;
00352 }
00353 
00359 inline
00360 geometry_msgs::Pose toMsg(const Eigen::Isometry3d& in) {
00361   geometry_msgs::Pose msg;
00362   msg.position.x = in.translation().x();
00363   msg.position.y = in.translation().y();
00364   msg.position.z = in.translation().z();
00365   Eigen::Quaterniond q(in.linear());
00366   msg.orientation.x = q.x();
00367   msg.orientation.y = q.y();
00368   msg.orientation.z = q.z();
00369   msg.orientation.w = q.w();
00370   if (msg.orientation.w < 0) {
00371     msg.orientation.x *= -1;
00372     msg.orientation.y *= -1;
00373     msg.orientation.z *= -1;
00374     msg.orientation.w *= -1;
00375   }
00376   return msg;
00377 }
00378 
00384 inline
00385 void fromMsg(const geometry_msgs::Pose& msg, Eigen::Affine3d& out) {
00386   out = Eigen::Affine3d(
00387       Eigen::Translation3d(msg.position.x, msg.position.y, msg.position.z) *
00388       Eigen::Quaterniond(msg.orientation.w,
00389                          msg.orientation.x,
00390                          msg.orientation.y,
00391                          msg.orientation.z));
00392 }
00393 
00399 inline
00400 void fromMsg(const geometry_msgs::Pose& msg, Eigen::Isometry3d& out) {
00401   out = Eigen::Isometry3d(
00402       Eigen::Translation3d(msg.position.x, msg.position.y, msg.position.z) *
00403       Eigen::Quaterniond(msg.orientation.w,
00404                          msg.orientation.x,
00405                          msg.orientation.y,
00406                          msg.orientation.z));
00407 }
00408 
00414 inline
00415 geometry_msgs::Twist toMsg(const Eigen::Matrix<double,6,1>& in) {
00416   geometry_msgs::Twist msg;
00417   msg.linear.x = in[0];
00418   msg.linear.y = in[1];
00419   msg.linear.z = in[2];
00420   msg.angular.x = in[3];
00421   msg.angular.y = in[4];
00422   msg.angular.z = in[5];
00423   return msg;
00424 }
00425 
00431 inline
00432 void fromMsg(const geometry_msgs::Twist &msg, Eigen::Matrix<double,6,1>& out) {
00433   out[0] = msg.linear.x;
00434   out[1] = msg.linear.y;
00435   out[2] = msg.linear.z;
00436   out[3] = msg.angular.x;
00437   out[4] = msg.angular.y;
00438   out[5] = msg.angular.z;
00439 }
00440 
00450 template <>
00451 inline
00452 void doTransform(const tf2::Stamped<Eigen::Affine3d>& t_in,
00453                  tf2::Stamped<Eigen::Affine3d>& t_out,
00454                  const geometry_msgs::TransformStamped& transform) {
00455   t_out = tf2::Stamped<Eigen::Affine3d>(transformToEigen(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00456 }
00457 
00467 template <>
00468 inline
00469 void doTransform(const tf2::Stamped<Eigen::Isometry3d>& t_in,
00470                  tf2::Stamped<Eigen::Isometry3d>& t_out,
00471                  const geometry_msgs::TransformStamped& transform) {
00472   t_out = tf2::Stamped<Eigen::Isometry3d>(transformToEigen(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00473 }
00474 
00480 inline
00481 geometry_msgs::PoseStamped toMsg(const tf2::Stamped<Eigen::Affine3d>& in)
00482 {
00483   geometry_msgs::PoseStamped msg;
00484   msg.header.stamp = in.stamp_;
00485   msg.header.frame_id = in.frame_id_;
00486   msg.pose = toMsg(static_cast<const Eigen::Affine3d&>(in));
00487   return msg;
00488 }
00489 
00490 inline
00491 geometry_msgs::PoseStamped toMsg(const tf2::Stamped<Eigen::Isometry3d>& in)
00492 {
00493   geometry_msgs::PoseStamped msg;
00494   msg.header.stamp = in.stamp_;
00495   msg.header.frame_id = in.frame_id_;
00496   msg.pose = toMsg(static_cast<const Eigen::Isometry3d&>(in));
00497   return msg;
00498 }
00499 
00505 inline
00506 void fromMsg(const geometry_msgs::PoseStamped& msg, tf2::Stamped<Eigen::Affine3d>& out)
00507 {
00508   out.stamp_ = msg.header.stamp;
00509   out.frame_id_ = msg.header.frame_id;
00510   fromMsg(msg.pose, static_cast<Eigen::Affine3d&>(out));
00511 }
00512 
00513 inline
00514 void fromMsg(const geometry_msgs::PoseStamped& msg, tf2::Stamped<Eigen::Isometry3d>& out)
00515 {
00516   out.stamp_ = msg.header.stamp;
00517   out.frame_id_ = msg.header.frame_id;
00518   fromMsg(msg.pose, static_cast<Eigen::Isometry3d&>(out));
00519 }
00520 
00521 } // namespace
00522 
00523 
00524 namespace Eigen {
00525 // This is needed to make the usage of the following conversion functions usable in tf2::convert().
00526 // According to clangs error note 'fromMsg'/'toMsg' should be declared prior to the call site or
00527 // in an associated namespace of one of its arguments. The stamped versions of this conversion
00528 // functions work because they have tf2::Stamped as an argument which is the same namespace as
00529 // which 'fromMsg'/'toMsg' is defined in. The non-stamped versions have no argument which is
00530 // defined in tf2, so it take the following definitions in Eigen namespace to make them usable in
00531 // tf2::convert().
00532 
00533 inline
00534 geometry_msgs::Pose toMsg(const Eigen::Affine3d& in) {
00535   return tf2::toMsg(in);
00536 }
00537 
00538 inline
00539 geometry_msgs::Pose toMsg(const Eigen::Isometry3d& in) {
00540   return tf2::toMsg(in);
00541 }
00542 
00543 inline
00544 void fromMsg(const geometry_msgs::Point& msg, Eigen::Vector3d& out) {
00545   tf2::fromMsg(msg, out);
00546 }
00547 
00548 inline
00549 geometry_msgs::Point toMsg(const Eigen::Vector3d& in) {
00550   return tf2::toMsg(in);
00551 }
00552 
00553 inline
00554 void fromMsg(const geometry_msgs::Pose& msg, Eigen::Affine3d& out) {
00555   tf2::fromMsg(msg, out);
00556 }
00557 
00558 inline
00559 void fromMsg(const geometry_msgs::Pose& msg, Eigen::Isometry3d& out) {
00560   tf2::fromMsg(msg, out);
00561 }
00562 
00563 inline
00564 geometry_msgs::Quaternion toMsg(const Eigen::Quaterniond& in) {
00565   return tf2::toMsg(in);
00566 }
00567 
00568 inline
00569 void fromMsg(const geometry_msgs::Quaternion& msg, Eigen::Quaterniond& out) {
00570   tf2::fromMsg(msg, out);
00571 }
00572 
00573 inline
00574 geometry_msgs::Twist toMsg(const Eigen::Matrix<double,6,1>& in) {
00575   return tf2::toMsg(in);
00576 }
00577 
00578 inline
00579 void fromMsg(const geometry_msgs::Twist &msg, Eigen::Matrix<double,6,1>& out) {
00580   tf2::fromMsg(msg, out);
00581 }
00582 
00583 } // namespace
00584 
00585 #endif // TF2_EIGEN_H


tf2_eigen
Author(s): Koji Terada
autogenerated on Thu Jun 6 2019 20:22:58