00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
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
00038
00039 namespace tf2
00040 {
00041
00046 inline
00047 Eigen::Affine3d transformToEigen(const geometry_msgs::TransformStamped& t) {
00048 return Eigen::Affine3d(Eigen::Translation3d(t.transform.translation.x, t.transform.translation.y, t.transform.translation.z)
00049 * Eigen::Quaterniond(t.transform.rotation.w,
00050 t.transform.rotation.x, t.transform.rotation.y, t.transform.rotation.z));
00051 }
00052
00057 inline
00058 geometry_msgs::TransformStamped eigenToTransform(const Eigen::Affine3d& T)
00059 {
00060 geometry_msgs::TransformStamped t;
00061 t.transform.translation.x = T.translation().x();
00062 t.transform.translation.y = T.translation().y();
00063 t.transform.translation.z = T.translation().z();
00064
00065 Eigen::Quaterniond q(T.rotation());
00066 t.transform.rotation.x = q.x();
00067 t.transform.rotation.y = q.y();
00068 t.transform.rotation.z = q.z();
00069 t.transform.rotation.w = q.w();
00070
00071 return t;
00072 }
00073
00083 template <>
00084 inline
00085 void doTransform(const Eigen::Vector3d& t_in, Eigen::Vector3d& t_out, const geometry_msgs::TransformStamped& transform)
00086 {
00087 t_out = Eigen::Vector3d(transformToEigen(transform) * t_in);
00088 }
00089
00095 inline
00096 geometry_msgs::Point toMsg(const Eigen::Vector3d& in)
00097 {
00098 geometry_msgs::Point msg;
00099 msg.x = in.x();
00100 msg.y = in.y();
00101 msg.z = in.z();
00102 return msg;
00103 }
00104
00110 inline
00111 void fromMsg(const geometry_msgs::Point& msg, Eigen::Vector3d& out)
00112 {
00113 out.x() = msg.x;
00114 out.y() = msg.y;
00115 out.z() = msg.z;
00116 }
00117
00124 template <>
00125 inline
00126 void doTransform(const tf2::Stamped<Eigen::Vector3d>& t_in,
00127 tf2::Stamped<Eigen::Vector3d>& t_out,
00128 const geometry_msgs::TransformStamped& transform) {
00129 t_out = tf2::Stamped<Eigen::Vector3d>(transformToEigen(transform) * t_in,
00130 transform.header.stamp,
00131 transform.header.frame_id);
00132 }
00133
00139 inline
00140 geometry_msgs::PointStamped toMsg(const tf2::Stamped<Eigen::Vector3d>& in)
00141 {
00142 geometry_msgs::PointStamped msg;
00143 msg.header.stamp = in.stamp_;
00144 msg.header.frame_id = in.frame_id_;
00145 msg.point = toMsg(static_cast<const Eigen::Vector3d&>(in));
00146 return msg;
00147 }
00148
00154 inline
00155 void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped<Eigen::Vector3d>& out) {
00156 out.stamp_ = msg.header.stamp;
00157 out.frame_id_ = msg.header.frame_id;
00158 fromMsg(msg.point, static_cast<Eigen::Vector3d&>(out));
00159 }
00160
00170 template <>
00171 inline
00172 void doTransform(const Eigen::Affine3d& t_in,
00173 Eigen::Affine3d& t_out,
00174 const geometry_msgs::TransformStamped& transform) {
00175 t_out = Eigen::Affine3d(transformToEigen(transform) * t_in);
00176 }
00177
00183 inline
00184 geometry_msgs::Quaternion toMsg(const Eigen::Quaterniond& in) {
00185 geometry_msgs::Quaternion msg;
00186 msg.w = in.w();
00187 msg.x = in.x();
00188 msg.y = in.y();
00189 msg.z = in.z();
00190 return msg;
00191 }
00192
00198 inline
00199 void fromMsg(const geometry_msgs::Quaternion& msg, Eigen::Quaterniond& out) {
00200 out = Eigen::Quaterniond(msg.w, msg.x, msg.y, msg.z);
00201 }
00202
00212 template<>
00213 inline
00214 void doTransform(const Eigen::Quaterniond& t_in,
00215 Eigen::Quaterniond& t_out,
00216 const geometry_msgs::TransformStamped& transform) {
00217 Eigen::Quaterniond t;
00218 fromMsg(transform.transform.rotation, t);
00219 t_out = t.inverse() * t_in * t;
00220 }
00221
00227 inline
00228 geometry_msgs::QuaternionStamped toMsg(const Stamped<Eigen::Quaterniond>& in) {
00229 geometry_msgs::QuaternionStamped msg;
00230 msg.header.stamp = in.stamp_;
00231 msg.header.frame_id = in.frame_id_;
00232 msg.quaternion = toMsg(static_cast<const Eigen::Quaterniond&>(in));
00233 return msg;
00234 }
00235
00241 inline
00242 void fromMsg(const geometry_msgs::QuaternionStamped& msg, Stamped<Eigen::Quaterniond>& out) {
00243 out.frame_id_ = msg.header.frame_id;
00244 out.stamp_ = msg.header.stamp;
00245 fromMsg(msg.quaternion, static_cast<Eigen::Quaterniond&>(out));
00246 }
00247
00254 template <>
00255 inline
00256 void doTransform(const tf2::Stamped<Eigen::Quaterniond>& t_in,
00257 tf2::Stamped<Eigen::Quaterniond>& t_out,
00258 const geometry_msgs::TransformStamped& transform) {
00259 t_out.frame_id_ = transform.header.frame_id;
00260 t_out.stamp_ = transform.header.stamp;
00261 doTransform(static_cast<const Eigen::Quaterniond&>(t_in), static_cast<Eigen::Quaterniond&>(t_out), transform);
00262 }
00263
00269 inline
00270 geometry_msgs::Pose toMsg(const Eigen::Affine3d& in) {
00271 geometry_msgs::Pose msg;
00272 msg.position.x = in.translation().x();
00273 msg.position.y = in.translation().y();
00274 msg.position.z = in.translation().z();
00275 msg.orientation.x = Eigen::Quaterniond(in.rotation()).x();
00276 msg.orientation.y = Eigen::Quaterniond(in.rotation()).y();
00277 msg.orientation.z = Eigen::Quaterniond(in.rotation()).z();
00278 msg.orientation.w = Eigen::Quaterniond(in.rotation()).w();
00279 return msg;
00280 }
00281
00287 inline
00288 void fromMsg(const geometry_msgs::Pose& msg, Eigen::Affine3d& out) {
00289 out = Eigen::Affine3d(
00290 Eigen::Translation3d(msg.position.x, msg.position.y, msg.position.z) *
00291 Eigen::Quaterniond(msg.orientation.w,
00292 msg.orientation.x,
00293 msg.orientation.y,
00294 msg.orientation.z));
00295 }
00296
00306 template <>
00307 inline
00308 void doTransform(const tf2::Stamped<Eigen::Affine3d>& t_in,
00309 tf2::Stamped<Eigen::Affine3d>& t_out,
00310 const geometry_msgs::TransformStamped& transform) {
00311 t_out = tf2::Stamped<Eigen::Affine3d>(transformToEigen(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00312 }
00313
00319 inline
00320 geometry_msgs::PoseStamped toMsg(const tf2::Stamped<Eigen::Affine3d>& in)
00321 {
00322 geometry_msgs::PoseStamped msg;
00323 msg.header.stamp = in.stamp_;
00324 msg.header.frame_id = in.frame_id_;
00325 msg.pose = toMsg(static_cast<const Eigen::Affine3d&>(in));
00326 return msg;
00327 }
00328
00334 inline
00335 void fromMsg(const geometry_msgs::PoseStamped& msg, tf2::Stamped<Eigen::Affine3d>& out)
00336 {
00337 out.stamp_ = msg.header.stamp;
00338 out.frame_id_ = msg.header.frame_id;
00339 fromMsg(msg.pose, static_cast<Eigen::Affine3d&>(out));
00340 }
00341
00342 }
00343
00344
00345 namespace Eigen {
00346
00347
00348
00349
00350
00351
00352
00353
00354 inline
00355 geometry_msgs::Pose toMsg(const Eigen::Affine3d& in) {
00356 return tf2::toMsg(in);
00357 }
00358
00359 inline
00360 void fromMsg(const geometry_msgs::Point& msg, Eigen::Vector3d& out) {
00361 tf2::fromMsg(msg, out);
00362 }
00363
00364 inline
00365 geometry_msgs::Point toMsg(const Eigen::Vector3d& in) {
00366 return tf2::toMsg(in);
00367 }
00368
00369 inline
00370 void fromMsg(const geometry_msgs::Pose& msg, Eigen::Affine3d& out) {
00371 tf2::fromMsg(msg, out);
00372 }
00373
00374 inline
00375 geometry_msgs::Quaternion toMsg(const Eigen::Quaterniond& in) {
00376 return tf2::toMsg(in);
00377 }
00378
00379 inline
00380 void fromMsg(const geometry_msgs::Quaternion& msg, Eigen::Quaterniond& out) {
00381 tf2::fromMsg(msg, out);
00382 }
00383
00384 }
00385
00386 #endif // TF2_EIGEN_H