37 #ifndef pcl_ROS_TRANSFORMS_H_ 38 #define pcl_ROS_TRANSFORMS_H_ 40 #include <sensor_msgs/PointCloud2.h> 41 #include <pcl/common/transforms.h> 53 template <
typename Po
intT>
void 55 pcl::PointCloud <PointT> &cloud_out,
64 template <
typename Po
intT>
bool 66 const pcl::PointCloud <PointT> &cloud_in,
67 pcl::PointCloud <PointT> &cloud_out,
78 template <
typename Po
intT>
bool 81 const pcl::PointCloud <PointT> &cloud_in,
82 const std::string &fixed_frame,
83 pcl::PointCloud <PointT> &cloud_out,
92 template <
typename Po
intT>
void 94 pcl::PointCloud <PointT> &cloud_out,
103 template <
typename Po
intT>
bool 105 const pcl::PointCloud <PointT> &cloud_in,
106 pcl::PointCloud <PointT> &cloud_out,
117 template <
typename Po
intT>
bool 119 const pcl::PointCloud <PointT> &cloud_in,
120 const std::string &fixed_frame,
121 pcl::PointCloud <PointT> &cloud_out,
132 const sensor_msgs::PointCloud2 &in,
133 sensor_msgs::PointCloud2 &out,
145 const sensor_msgs::PointCloud2 &in,
146 sensor_msgs::PointCloud2 &out);
155 const sensor_msgs::PointCloud2 &in,
156 sensor_msgs::PointCloud2 &out);
166 #endif // PCL_ROS_TRANSFORMS_H_
void transformPointCloudWithNormals(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
Transform a point cloud and rotate its normals using an Eigen transform.
void transformAsMatrix(const tf::Transform &bt, Eigen::Matrix4f &out_mat)
Obtain the transformation matrix from TF into an Eigen form.
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
Apply a rigid transform defined by a 3D offset and a quaternion.