Go to the documentation of this file.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 
00027 
00028 
00029 
00032 #ifndef TF2_BULLET_H
00033 #define TF2_BULLET_H
00034 
00035 #include <tf2_ros/buffer.h>
00036 #include <LinearMath/btTransform.h>
00037 #include <geometry_msgs/PointStamped.h>
00038 
00039 
00040 namespace tf2
00041 {
00042     
00043 btTransform transformToBullet(const geometry_msgs::TransformStamped& t)
00044   {
00045     return btTransform(btQuaternion(t.transform.rotation.x, t.transform.rotation.y, 
00046                                     t.transform.rotation.z, t.transform.rotation.w),
00047                        btVector3(t.transform.translation.x, t.transform.translation.y, t.transform.translation.z));
00048   }
00049 
00050 
00051 
00052 template <>
00053   void doTransform(const tf2::Stamped<btVector3>& t_in, tf2::Stamped<btVector3>& t_out, const geometry_msgs::TransformStamped& transform)
00054   {
00055     t_out = tf2::Stamped<btVector3>(transformToBullet(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00056   }
00057 
00058 
00059 geometry_msgs::PointStamped toMsg(const tf2::Stamped<btVector3>& in)
00060 {
00061   geometry_msgs::PointStamped msg;
00062   msg.header.stamp = in.stamp_;
00063   msg.header.frame_id = in.frame_id_;
00064   msg.point.x = in[0];
00065   msg.point.y = in[1];
00066   msg.point.z = in[2];
00067   return msg;
00068 }
00069 
00070 void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped<btVector3>& out)
00071 {
00072   out.stamp_ = msg.header.stamp;
00073   out.frame_id_ = msg.header.frame_id;
00074   out[0] = msg.point.x;
00075   out[1] = msg.point.y;
00076   out[2] = msg.point.z;
00077 }
00078 
00079 
00080 
00081 template <>
00082   void doTransform(const tf2::Stamped<btTransform>& t_in, tf2::Stamped<btTransform>& t_out, const geometry_msgs::TransformStamped& transform)
00083   {
00084     t_out = tf2::Stamped<btTransform>(transformToBullet(transform) * t_in, transform.header.stamp, transform.header.frame_id);
00085   }
00086 
00087 
00088 } 
00089 
00090 #endif // TF2_BULLET_H