37 #include <sensor_msgs/PointCloud2.h> 
   50   if (in.header.frame_id == target_frame)
 
   61     tf_listener.
lookupTransform (target_frame, in.header.frame_id, in.header.stamp, transform);
 
   70   Eigen::Matrix4f eigen_transform;
 
   75   out.header.frame_id = target_frame;
 
   84   if (in.header.frame_id == target_frame)
 
   91   geometry_msgs::TransformStamped transform;
 
   94     transform = tf_buffer.
lookupTransform (target_frame, in.header.frame_id, in.header.stamp);
 
  114                      const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out)
 
  116   if (in.header.frame_id == target_frame)
 
  123   Eigen::Matrix4f transform;
 
  128   out.header.frame_id = target_frame;
 
  134                      const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out)
 
  136   if (in.header.frame_id == target_frame)
 
  143   Eigen::Matrix4f transform;
 
  148   out.header.frame_id = target_frame;
 
  154                      sensor_msgs::PointCloud2 &out)
 
  161   if (x_idx == -1 || y_idx == -1 || z_idx == -1)
 
  163     ROS_ERROR (
"Input dataset has no X-Y-Z coordinates! Cannot convert to Eigen format.");
 
  167   if (in.fields[x_idx].datatype != sensor_msgs::PointField::FLOAT32 || 
 
  168       in.fields[y_idx].datatype != sensor_msgs::PointField::FLOAT32 || 
 
  169       in.fields[z_idx].datatype != sensor_msgs::PointField::FLOAT32)
 
  171     ROS_ERROR (
"X-Y-Z coordinates not floats. Currently only floats are supported.");
 
  181     out.header = in.header;
 
  182     out.height = in.height;
 
  183     out.width  = in.width;
 
  184     out.fields = in.fields;
 
  185     out.is_bigendian = in.is_bigendian;
 
  186     out.point_step   = in.point_step;
 
  187     out.row_step     = in.row_step;
 
  188     out.is_dense     = in.is_dense;
 
  189     out.data.resize (in.data.size ());
 
  191     memcpy (out.data.data (), in.data.data (), in.data.size ());
 
  194   Eigen::Array4i xyz_offset (in.fields[x_idx].offset, in.fields[y_idx].offset, in.fields[z_idx].offset, 0);
 
  196   for (
size_t i = 0; i < in.width * in.height; ++i)
 
  198     Eigen::Vector4f pt (*(
float*)&in.data[xyz_offset[0]], *(
float*)&in.data[xyz_offset[1]], *(
float*)&in.data[xyz_offset[2]], 1);
 
  199     Eigen::Vector4f pt_out;
 
  201     bool max_range_point = 
false;
 
  202     int distance_ptr_offset = (dist_idx < 0 ? -1 : (i*in.point_step + in.fields[dist_idx].offset)); 
 
  203     float* distance_ptr = (dist_idx < 0 ? NULL : (
float*)(&in.data[distance_ptr_offset]));
 
  204     if (!std::isfinite (pt[0]) || !std::isfinite (pt[1]) || !std::isfinite (pt[2]))
 
  206       if (distance_ptr==NULL || !std::isfinite(*distance_ptr))  
 
  212         pt[0] = *distance_ptr;  
 
  213         pt_out = transform * pt;
 
  214         max_range_point = 
true;
 
  220       pt_out = transform * pt;
 
  226       *(
float*)(&out.data[distance_ptr_offset]) = pt_out[0];
 
  227       pt_out[0] = std::numeric_limits<float>::quiet_NaN();
 
  230     memcpy (&out.data[xyz_offset[0]], &pt_out[0], sizeof (
float));
 
  231     memcpy (&out.data[xyz_offset[1]], &pt_out[1], sizeof (
float));
 
  232     memcpy (&out.data[xyz_offset[2]], &pt_out[2], sizeof (
float));
 
  235     xyz_offset += in.point_step;
 
  243     for (
size_t i = 0; i < out.width * out.height; ++i)
 
  245       float *pstep = (
float*)&out.data[i * out.point_step + out.fields[vp_idx].offset];
 
  247       Eigen::Vector4f vp_in (pstep[0], pstep[1], pstep[2], 1);
 
  248       Eigen::Vector4f vp_out = transform * vp_in;
 
  250       pstep[0] = vp_out[0];
 
  251       pstep[1] = vp_out[1];
 
  252       pstep[2] = vp_out[2];
 
  266   out_mat (0, 0) = mv[0]; out_mat (0, 1) = mv[4]; out_mat (0, 2) = mv[8];
 
  267   out_mat (1, 0) = mv[1]; out_mat (1, 1) = mv[5]; out_mat (1, 2) = mv[9];
 
  268   out_mat (2, 0) = mv[2]; out_mat (2, 1) = mv[6]; out_mat (2, 2) = mv[10];
 
  270   out_mat (3, 0) = out_mat (3, 1) = out_mat (3, 2) = 0; out_mat (3, 3) = 1;
 
  271   out_mat (0, 3) = origin.x ();
 
  272   out_mat (1, 3) = origin.y ();
 
  273   out_mat (2, 3) = origin.z ();
 
  286 template void pcl_ros::transformPointCloudWithNormals<pcl::PointNormal> (
const pcl::PointCloud <pcl::PointNormal> &, pcl::PointCloud <pcl::PointNormal> &, 
const tf::Transform &);
 
  287 template void pcl_ros::transformPointCloudWithNormals<pcl::PointXYZRGBNormal> (
const pcl::PointCloud <pcl::PointXYZRGBNormal> &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const tf::Transform &);
 
  288 template void pcl_ros::transformPointCloudWithNormals<pcl::PointXYZINormal> (
const pcl::PointCloud <pcl::PointXYZINormal> &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const tf::Transform &);
 
  291 template void pcl_ros::transformPointCloudWithNormals<pcl::PointNormal> (
const pcl::PointCloud <pcl::PointNormal> &, pcl::PointCloud <pcl::PointNormal> &, 
const geometry_msgs::Transform &);
 
  292 template void pcl_ros::transformPointCloudWithNormals<pcl::PointXYZRGBNormal> (
const pcl::PointCloud <pcl::PointXYZRGBNormal> &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const geometry_msgs::Transform &);
 
  293 template void pcl_ros::transformPointCloudWithNormals<pcl::PointXYZINormal> (
const pcl::PointCloud <pcl::PointXYZINormal> &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const geometry_msgs::Transform &);
 
  296 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointNormal> (
const std::string &, 
const pcl::PointCloud<pcl::PointNormal> &, pcl::PointCloud<pcl::PointNormal> &, 
const tf::TransformListener &);
 
  297 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointXYZRGBNormal> (
const std::string &, 
const pcl::PointCloud<pcl::PointXYZRGBNormal> &, pcl::PointCloud<pcl::PointXYZRGBNormal> &, 
const tf::TransformListener &);
 
  298 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointXYZINormal> (
const std::string &, 
const pcl::PointCloud<pcl::PointXYZINormal> &, pcl::PointCloud<pcl::PointXYZINormal> &, 
const tf::TransformListener &);
 
  300 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointNormal> (
const std::string &, 
const pcl::PointCloud<pcl::PointNormal> &, pcl::PointCloud<pcl::PointNormal> &, 
const tf2_ros::Buffer &);
 
  301 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointXYZRGBNormal> (
const std::string &, 
const pcl::PointCloud<pcl::PointXYZRGBNormal> &, pcl::PointCloud<pcl::PointXYZRGBNormal> &, 
const tf2_ros::Buffer &);
 
  302 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointXYZINormal> (
const std::string &, 
const pcl::PointCloud<pcl::PointXYZINormal> &, pcl::PointCloud<pcl::PointXYZINormal> &, 
const tf2_ros::Buffer &);
 
  305 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointNormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud<pcl::PointNormal> &, 
const std::string &, pcl::PointCloud <pcl::PointNormal> &, 
const tf::TransformListener &);
 
  306 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointXYZRGBNormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud<pcl::PointXYZRGBNormal> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const tf::TransformListener &);
 
  307 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointXYZINormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud<pcl::PointXYZINormal> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const tf::TransformListener &);
 
  310 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointNormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud<pcl::PointNormal> &, 
const std::string &, pcl::PointCloud <pcl::PointNormal> &, 
const tf2_ros::Buffer &);
 
  311 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointXYZRGBNormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud<pcl::PointXYZRGBNormal> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const tf2_ros::Buffer &);
 
  312 template bool pcl_ros::transformPointCloudWithNormals<pcl::PointXYZINormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud<pcl::PointXYZINormal> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const tf2_ros::Buffer &);
 
  315 template void pcl_ros::transformPointCloud<pcl::PointXYZ> (
const pcl::PointCloud <pcl::PointXYZ> &, pcl::PointCloud <pcl::PointXYZ> &, 
const tf::Transform &);
 
  316 template void pcl_ros::transformPointCloud<pcl::PointXYZI> (
const pcl::PointCloud <pcl::PointXYZI> &, pcl::PointCloud <pcl::PointXYZI> &, 
const tf::Transform &);
 
  317 template void pcl_ros::transformPointCloud<pcl::PointXYZRGBA> (
const pcl::PointCloud <pcl::PointXYZRGBA> &, pcl::PointCloud <pcl::PointXYZRGBA> &, 
const tf::Transform &);
 
  318 template void pcl_ros::transformPointCloud<pcl::PointXYZRGB> (
const pcl::PointCloud <pcl::PointXYZRGB> &, pcl::PointCloud <pcl::PointXYZRGB> &, 
const tf::Transform &);
 
  319 template void pcl_ros::transformPointCloud<pcl::InterestPoint> (
const pcl::PointCloud <pcl::InterestPoint> &, pcl::PointCloud <pcl::InterestPoint> &, 
const tf::Transform &);
 
  320 template void pcl_ros::transformPointCloud<pcl::PointNormal> (
const pcl::PointCloud <pcl::PointNormal> &, pcl::PointCloud <pcl::PointNormal> &, 
const tf::Transform &);
 
  321 template void pcl_ros::transformPointCloud<pcl::PointXYZRGBNormal> (
const pcl::PointCloud <pcl::PointXYZRGBNormal> &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const tf::Transform &);
 
  322 template void pcl_ros::transformPointCloud<pcl::PointXYZINormal> (
const pcl::PointCloud <pcl::PointXYZINormal> &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const tf::Transform &);
 
  323 template void pcl_ros::transformPointCloud<pcl::PointWithRange> (
const pcl::PointCloud <pcl::PointWithRange> &, pcl::PointCloud <pcl::PointWithRange> &, 
const tf::Transform &);
 
  324 template void pcl_ros::transformPointCloud<pcl::PointWithViewpoint> (
const pcl::PointCloud <pcl::PointWithViewpoint> &, pcl::PointCloud <pcl::PointWithViewpoint> &, 
const tf::Transform &);
 
  327 template void pcl_ros::transformPointCloud<pcl::PointXYZ> (
const pcl::PointCloud <pcl::PointXYZ> &, pcl::PointCloud <pcl::PointXYZ> &, 
const geometry_msgs::Transform &);
 
  328 template void pcl_ros::transformPointCloud<pcl::PointXYZI> (
const pcl::PointCloud <pcl::PointXYZI> &, pcl::PointCloud <pcl::PointXYZI> &, 
const geometry_msgs::Transform &);
 
  329 template void pcl_ros::transformPointCloud<pcl::PointXYZRGBA> (
const pcl::PointCloud <pcl::PointXYZRGBA> &, pcl::PointCloud <pcl::PointXYZRGBA> &, 
const geometry_msgs::Transform &);
 
  330 template void pcl_ros::transformPointCloud<pcl::PointXYZRGB> (
const pcl::PointCloud <pcl::PointXYZRGB> &, pcl::PointCloud <pcl::PointXYZRGB> &, 
const geometry_msgs::Transform &);
 
  331 template void pcl_ros::transformPointCloud<pcl::InterestPoint> (
const pcl::PointCloud <pcl::InterestPoint> &, pcl::PointCloud <pcl::InterestPoint> &, 
const geometry_msgs::Transform &);
 
  332 template void pcl_ros::transformPointCloud<pcl::PointNormal> (
const pcl::PointCloud <pcl::PointNormal> &, pcl::PointCloud <pcl::PointNormal> &, 
const geometry_msgs::Transform &);
 
  333 template void pcl_ros::transformPointCloud<pcl::PointXYZRGBNormal> (
const pcl::PointCloud <pcl::PointXYZRGBNormal> &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const geometry_msgs::Transform &);
 
  334 template void pcl_ros::transformPointCloud<pcl::PointXYZINormal> (
const pcl::PointCloud <pcl::PointXYZINormal> &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const geometry_msgs::Transform &);
 
  335 template void pcl_ros::transformPointCloud<pcl::PointWithRange> (
const pcl::PointCloud <pcl::PointWithRange> &, pcl::PointCloud <pcl::PointWithRange> &, 
const geometry_msgs::Transform &);
 
  336 template void pcl_ros::transformPointCloud<pcl::PointWithViewpoint> (
const pcl::PointCloud <pcl::PointWithViewpoint> &, pcl::PointCloud <pcl::PointWithViewpoint> &, 
const geometry_msgs::Transform &);
 
  339 template bool pcl_ros::transformPointCloud<pcl::PointXYZ> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZ> &, pcl::PointCloud <pcl::PointXYZ> &, 
const tf::TransformListener &);
 
  340 template bool pcl_ros::transformPointCloud<pcl::PointXYZI> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZI> &, pcl::PointCloud <pcl::PointXYZI> &, 
const tf::TransformListener &);
 
  341 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGBA> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZRGBA> &, pcl::PointCloud <pcl::PointXYZRGBA> &, 
const tf::TransformListener &);
 
  342 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGB> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZRGB> &, pcl::PointCloud <pcl::PointXYZRGB> &, 
const tf::TransformListener &);
 
  343 template bool pcl_ros::transformPointCloud<pcl::InterestPoint> (
const std::string &, 
const pcl::PointCloud <pcl::InterestPoint> &, pcl::PointCloud <pcl::InterestPoint> &, 
const tf::TransformListener &);
 
  344 template bool pcl_ros::transformPointCloud<pcl::PointNormal> (
const std::string &, 
const pcl::PointCloud <pcl::PointNormal> &, pcl::PointCloud <pcl::PointNormal> &, 
const tf::TransformListener &);
 
  345 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGBNormal> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZRGBNormal> &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const tf::TransformListener &);
 
  346 template bool pcl_ros::transformPointCloud<pcl::PointXYZINormal> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZINormal> &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const tf::TransformListener &);
 
  347 template bool pcl_ros::transformPointCloud<pcl::PointWithRange> (
const std::string &, 
const pcl::PointCloud <pcl::PointWithRange> &, pcl::PointCloud <pcl::PointWithRange> &, 
const tf::TransformListener &);
 
  348 template bool pcl_ros::transformPointCloud<pcl::PointWithViewpoint> (
const std::string &, 
const pcl::PointCloud <pcl::PointWithViewpoint> &, pcl::PointCloud <pcl::PointWithViewpoint> &, 
const tf::TransformListener &);
 
  351 template bool pcl_ros::transformPointCloud<pcl::PointXYZ> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZ> &, pcl::PointCloud <pcl::PointXYZ> &, 
const tf2_ros::Buffer &);
 
  352 template bool pcl_ros::transformPointCloud<pcl::PointXYZI> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZI> &, pcl::PointCloud <pcl::PointXYZI> &, 
const tf2_ros::Buffer &);
 
  353 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGBA> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZRGBA> &, pcl::PointCloud <pcl::PointXYZRGBA> &, 
const tf2_ros::Buffer &);
 
  354 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGB> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZRGB> &, pcl::PointCloud <pcl::PointXYZRGB> &, 
const tf2_ros::Buffer &);
 
  355 template bool pcl_ros::transformPointCloud<pcl::InterestPoint> (
const std::string &, 
const pcl::PointCloud <pcl::InterestPoint> &, pcl::PointCloud <pcl::InterestPoint> &, 
const tf2_ros::Buffer &);
 
  356 template bool pcl_ros::transformPointCloud<pcl::PointNormal> (
const std::string &, 
const pcl::PointCloud <pcl::PointNormal> &, pcl::PointCloud <pcl::PointNormal> &, 
const tf2_ros::Buffer &);
 
  357 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGBNormal> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZRGBNormal> &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const tf2_ros::Buffer &);
 
  358 template bool pcl_ros::transformPointCloud<pcl::PointXYZINormal> (
const std::string &, 
const pcl::PointCloud <pcl::PointXYZINormal> &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const tf2_ros::Buffer &);
 
  359 template bool pcl_ros::transformPointCloud<pcl::PointWithRange> (
const std::string &, 
const pcl::PointCloud <pcl::PointWithRange> &, pcl::PointCloud <pcl::PointWithRange> &, 
const tf2_ros::Buffer &);
 
  360 template bool pcl_ros::transformPointCloud<pcl::PointWithViewpoint> (
const std::string &, 
const pcl::PointCloud <pcl::PointWithViewpoint> &, pcl::PointCloud <pcl::PointWithViewpoint> &, 
const tf2_ros::Buffer &);
 
  363 template bool pcl_ros::transformPointCloud<pcl::PointXYZ> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZ> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZ> &, 
const tf::TransformListener &);
 
  364 template bool pcl_ros::transformPointCloud<pcl::PointXYZI> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZI> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZI> &, 
const tf::TransformListener &);
 
  365 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGBA> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZRGBA> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZRGBA> &, 
const tf::TransformListener &);
 
  366 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGB> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZRGB> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZRGB> &, 
const tf::TransformListener &);
 
  367 template bool pcl_ros::transformPointCloud<pcl::InterestPoint> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::InterestPoint> &, 
const std::string &, pcl::PointCloud <pcl::InterestPoint> &, 
const tf::TransformListener &);
 
  368 template bool pcl_ros::transformPointCloud<pcl::PointNormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointNormal> &, 
const std::string &, pcl::PointCloud <pcl::PointNormal> &, 
const tf::TransformListener &);
 
  369 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGBNormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const tf::TransformListener &);
 
  370 template bool pcl_ros::transformPointCloud<pcl::PointXYZINormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZINormal> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const tf::TransformListener &);
 
  371 template bool pcl_ros::transformPointCloud<pcl::PointWithRange> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointWithRange> &, 
const std::string &, pcl::PointCloud <pcl::PointWithRange> &, 
const tf::TransformListener &);
 
  372 template bool pcl_ros::transformPointCloud<pcl::PointWithViewpoint> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointWithViewpoint> &, 
const std::string &, pcl::PointCloud <pcl::PointWithViewpoint> &, 
const tf::TransformListener &);
 
  375 template bool pcl_ros::transformPointCloud<pcl::PointXYZ> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZ> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZ> &, 
const tf2_ros::Buffer &);
 
  376 template bool pcl_ros::transformPointCloud<pcl::PointXYZI> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZI> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZI> &, 
const tf2_ros::Buffer &);
 
  377 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGBA> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZRGBA> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZRGBA> &, 
const tf2_ros::Buffer &);
 
  378 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGB> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZRGB> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZRGB> &, 
const tf2_ros::Buffer &);
 
  379 template bool pcl_ros::transformPointCloud<pcl::InterestPoint> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::InterestPoint> &, 
const std::string &, pcl::PointCloud <pcl::InterestPoint> &, 
const tf2_ros::Buffer &);
 
  380 template bool pcl_ros::transformPointCloud<pcl::PointNormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointNormal> &, 
const std::string &, pcl::PointCloud <pcl::PointNormal> &, 
const tf2_ros::Buffer &);
 
  381 template bool pcl_ros::transformPointCloud<pcl::PointXYZRGBNormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZRGBNormal> &, 
const tf2_ros::Buffer &);
 
  382 template bool pcl_ros::transformPointCloud<pcl::PointXYZINormal> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointXYZINormal> &, 
const std::string &, pcl::PointCloud <pcl::PointXYZINormal> &, 
const tf2_ros::Buffer &);
 
  383 template bool pcl_ros::transformPointCloud<pcl::PointWithRange> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointWithRange> &, 
const std::string &, pcl::PointCloud <pcl::PointWithRange> &, 
const tf2_ros::Buffer &);
 
  384 template bool pcl_ros::transformPointCloud<pcl::PointWithViewpoint> (
const std::string &, 
const ros::Time &, 
const pcl::PointCloud <pcl::PointWithViewpoint> &, 
const std::string &, pcl::PointCloud <pcl::PointWithViewpoint> &, 
const tf2_ros::Buffer &);