37 #ifndef pcl_ROS_TRANSFORMS_H_ 
   38 #define pcl_ROS_TRANSFORMS_H_ 
   40 #include <sensor_msgs/PointCloud2.h> 
   41 #include <pcl/common/transforms.h> 
   54   template <
typename Po
intT> 
void  
   56                                   pcl::PointCloud <PointT> &cloud_out, 
 
   65   template <
typename Po
intT> 
void 
   67                                   pcl::PointCloud <PointT> &cloud_out,
 
   68                                   const geometry_msgs::Transform &transform);
 
   76   template <
typename Po
intT> 
bool  
   78                                   const pcl::PointCloud <PointT> &cloud_in, 
 
   79                                   pcl::PointCloud <PointT> &cloud_out, 
 
   88   template <
typename Po
intT> 
bool 
   90                                   const pcl::PointCloud <PointT> &cloud_in,
 
   91                                   pcl::PointCloud <PointT> &cloud_out,
 
  102    template <
typename Po
intT> 
bool  
  105                                    const pcl::PointCloud <PointT> &cloud_in, 
 
  106                                    const std::string &fixed_frame, 
 
  107                                    pcl::PointCloud <PointT> &cloud_out, 
 
  118    template <
typename Po
intT> 
bool 
  121                                    const pcl::PointCloud <PointT> &cloud_in,
 
  122                                    const std::string &fixed_frame,
 
  123                                    pcl::PointCloud <PointT> &cloud_out,
 
  132   template <
typename Po
intT> 
void  
  134                        pcl::PointCloud <PointT> &cloud_out, 
 
  143   template <
typename Po
intT> 
void 
  145                        pcl::PointCloud <PointT> &cloud_out,
 
  146                        const geometry_msgs::Transform &transform);
 
  154   template <
typename Po
intT> 
bool  
  156                        const pcl::PointCloud <PointT> &cloud_in, 
 
  157                        pcl::PointCloud <PointT> &cloud_out, 
 
  166   template <
typename Po
intT> 
bool 
  168                        const pcl::PointCloud <PointT> &cloud_in,
 
  169                        pcl::PointCloud <PointT> &cloud_out,
 
  180   template <
typename Po
intT> 
bool  
  182                        const pcl::PointCloud <PointT> &cloud_in, 
 
  183                        const std::string &fixed_frame, 
 
  184                        pcl::PointCloud <PointT> &cloud_out, 
 
  195   template <
typename Po
intT> 
bool 
  197                        const pcl::PointCloud <PointT> &cloud_in,
 
  198                        const std::string &fixed_frame,
 
  199                        pcl::PointCloud <PointT> &cloud_out,
 
  210                        const sensor_msgs::PointCloud2 &in, 
 
  211                        sensor_msgs::PointCloud2 &out, 
 
  222                        const sensor_msgs::PointCloud2 &in,
 
  223                        sensor_msgs::PointCloud2 &out,
 
  235                        const sensor_msgs::PointCloud2 &in, 
 
  236                        sensor_msgs::PointCloud2 &out);
 
  246                        const geometry_msgs::Transform &net_transform,
 
  247                        const sensor_msgs::PointCloud2 &in,
 
  248                        sensor_msgs::PointCloud2 &out);
 
  257                        const sensor_msgs::PointCloud2 &in, 
 
  258                        sensor_msgs::PointCloud2 &out);
 
  272   transformAsMatrix (
const geometry_msgs::Transform& bt, Eigen::Matrix4f &out_mat);
 
  275 #endif // PCL_ROS_TRANSFORMS_H_