Template Function pcl_ros::transformPointCloud(const std::string&, const rclcpp::Time&, const pcl::PointCloud<PointT>&, const std::string&, pcl::PointCloud<PointT>&, const tf2_ros::Buffer&)

Function Documentation

template<typename PointT>
bool pcl_ros::transformPointCloud(const std::string &target_frame, const rclcpp::Time &target_time, const pcl::PointCloud<PointT> &cloud_in, const std::string &fixed_frame, pcl::PointCloud<PointT> &cloud_out, const tf2_ros::Buffer &tf_buffer)

Transforms a point cloud in a given target TF frame using a TransformListener.

Parameters:
  • target_frame – the target TF frame the point cloud should be transformed to

  • target_time – the target timestamp

  • cloud_in – the input point cloud

  • fixed_frame – fixed TF frame

  • cloud_out – the input point cloud

  • tf_buffer – a TF buffer object