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 
00030 #ifndef TF2_SENSOR_MSGS_H
00031 #define TF2_SENSOR_MSGS_H
00032 
00033 #include <tf2/convert.h>
00034 #include <sensor_msgs/PointCloud2.h>
00035 #include <sensor_msgs/point_cloud2_iterator.h>
00036 #include <Eigen/Eigen>
00037 #include <Eigen/Geometry>
00038 
00039 namespace tf2
00040 {
00041 
00042 
00044 
00045 
00052 template <>
00053 inline
00054 const ros::Time& getTimestamp(const sensor_msgs::PointCloud2& p) {return p.header.stamp;}
00055 
00062 template <>
00063 inline
00064 const std::string& getFrameId(const sensor_msgs::PointCloud2 &p) {return p.header.frame_id;}
00065 
00066 
00067 template <>
00068 inline
00069 void doTransform(const sensor_msgs::PointCloud2 &p_in, sensor_msgs::PointCloud2 &p_out, const geometry_msgs::TransformStamped& t_in)
00070 {
00071   p_out = p_in;
00072   p_out.header = t_in.header;
00073   Eigen::Transform<float,3,Eigen::Affine> t = Eigen::Translation3f(t_in.transform.translation.x, t_in.transform.translation.y,
00074                                                                    t_in.transform.translation.z) * Eigen::Quaternion<float>(
00075                                                                      t_in.transform.rotation.w, t_in.transform.rotation.x,
00076                                                                      t_in.transform.rotation.y, t_in.transform.rotation.z);
00077 
00078   sensor_msgs::PointCloud2ConstIterator<float> x_in(p_in, "x");
00079   sensor_msgs::PointCloud2ConstIterator<float> y_in(p_in, "y");
00080   sensor_msgs::PointCloud2ConstIterator<float> z_in(p_in, "z");
00081 
00082   sensor_msgs::PointCloud2Iterator<float> x_out(p_out, "x");
00083   sensor_msgs::PointCloud2Iterator<float> y_out(p_out, "y");
00084   sensor_msgs::PointCloud2Iterator<float> z_out(p_out, "z");
00085 
00086   Eigen::Vector3f point;
00087   for(; x_in != x_in.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out) {
00088     point = t * Eigen::Vector3f(*x_in, *y_in, *z_in);
00089     *x_out = point.x();
00090     *y_out = point.y();
00091     *z_out = point.z();
00092   }
00093 }
00094 inline
00095 sensor_msgs::PointCloud2 toMsg(const sensor_msgs::PointCloud2 &in)
00096 {
00097   return in;
00098 }
00099 inline
00100 void fromMsg(const sensor_msgs::PointCloud2 &msg, sensor_msgs::PointCloud2 &out)
00101 {
00102   out = msg;
00103 }
00104 
00105 } 
00106 
00107 #endif // TF2_SENSOR_MSGS_H