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
00031
00032
00033
00034
00035
00036
00037 #ifndef PCL_ROS_TRANSFORMS_H_
00038 #define PCL_ROS_TRANSFORMS_H_
00039
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include <pcl/registration/transforms.h>
00042 #include <tf/transform_datatypes.h>
00043 #include <tf/transform_listener.h>
00044
00045 namespace pcl_ros
00046 {
00053 template <typename PointT> void
00054 transformPointCloudWithNormals (const pcl::PointCloud <PointT> &cloud_in,
00055 pcl::PointCloud <PointT> &cloud_out,
00056 const tf::Transform &transform);
00057
00064 template <typename PointT> bool
00065 transformPointCloudWithNormals (const std::string &target_frame,
00066 const pcl::PointCloud <PointT> &cloud_in,
00067 pcl::PointCloud <PointT> &cloud_out,
00068 const tf::TransformListener &tf_listener);
00069
00078 template <typename PointT> bool
00079 transformPointCloudWithNormals (const std::string &target_frame,
00080 const ros::Time & target_time,
00081 const pcl::PointCloud <PointT> &cloud_in,
00082 const std::string &fixed_frame,
00083 pcl::PointCloud <PointT> &cloud_out,
00084 const tf::TransformListener &tf_listener);
00085
00092 template <typename PointT> void
00093 transformPointCloud (const pcl::PointCloud <PointT> &cloud_in,
00094 pcl::PointCloud <PointT> &cloud_out,
00095 const tf::Transform &transform);
00096
00103 template <typename PointT> bool
00104 transformPointCloud (const std::string &target_frame,
00105 const pcl::PointCloud <PointT> &cloud_in,
00106 pcl::PointCloud <PointT> &cloud_out,
00107 const tf::TransformListener &tf_listener);
00108
00117 template <typename PointT> bool
00118 transformPointCloud (const std::string &target_frame, const ros::Time & target_time,
00119 const pcl::PointCloud <PointT> &cloud_in,
00120 const std::string &fixed_frame,
00121 pcl::PointCloud <PointT> &cloud_out,
00122 const tf::TransformListener &tf_listener);
00123
00130 bool
00131 transformPointCloud (const std::string &target_frame,
00132 const sensor_msgs::PointCloud2 &in,
00133 sensor_msgs::PointCloud2 &out,
00134 const tf::TransformListener &tf_listener);
00135
00142 void
00143 transformPointCloud (const std::string &target_frame,
00144 const tf::Transform &net_transform,
00145 const sensor_msgs::PointCloud2 &in,
00146 sensor_msgs::PointCloud2 &out);
00147
00153 void
00154 transformPointCloud (const Eigen::Matrix4f &transform,
00155 const sensor_msgs::PointCloud2 &in,
00156 sensor_msgs::PointCloud2 &out);
00157
00162 void
00163 transformAsMatrix (const tf::Transform& bt, Eigen::Matrix4f &out_mat);
00164 }
00165
00166 #endif // PCL_ROS_TRANSFORMS_H_
00167