#include <sensor_msgs/PointCloud2.h>#include <pcl/registration/transforms.h>#include <tf/transform_datatypes.h>#include <tf/transform_listener.h>

Go to the source code of this file.
Namespaces | |
| namespace | pcl_ros |
Functions | |
| void | pcl_ros::transformAsMatrix (const tf::Transform &bt, Eigen::Matrix4f &out_mat) |
| Obtain the transformation matrix from TF into an Eigen form. | |
| void | pcl_ros::transformPointCloud (const Eigen::Matrix4f &transform, const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out) |
| Transform a sensor_msgs::PointCloud2 dataset using an Eigen 4x4 matrix. | |
| void | pcl_ros::transformPointCloud (const std::string &target_frame, const tf::Transform &net_transform, const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out) |
| Transform a sensor_msgs::PointCloud2 dataset from its frame to a given TF target frame. | |
| bool | pcl_ros::transformPointCloud (const std::string &target_frame, const sensor_msgs::PointCloud2 &in, sensor_msgs::PointCloud2 &out, const tf::TransformListener &tf_listener) |
| Transform a sensor_msgs::PointCloud2 dataset from its frame to a given TF target frame. | |
| template<typename PointT > | |
| bool | pcl_ros::transformPointCloud (const std::string &target_frame, const ros::Time &target_time, const pcl::PointCloud< PointT > &cloud_in, const std::string &fixed_frame, pcl::PointCloud< PointT > &cloud_out, const tf::TransformListener &tf_listener) |
| Transforms a point cloud in a given target TF frame using a TransformListener. | |
| template<typename PointT > | |
| bool | pcl_ros::transformPointCloud (const std::string &target_frame, const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::TransformListener &tf_listener) |
| Transforms a point cloud in a given target TF frame using a TransformListener. | |
| template<typename PointT > | |
| void | pcl_ros::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. | |
| template<typename PointT > | |
| bool | pcl_ros::transformPointCloudWithNormals (const std::string &target_frame, const ros::Time &target_time, const pcl::PointCloud< PointT > &cloud_in, const std::string &fixed_frame, pcl::PointCloud< PointT > &cloud_out, const tf::TransformListener &tf_listener) |
| Transforms a point cloud in a given target TF frame using a TransformListener. | |
| template<typename PointT > | |
| bool | pcl_ros::transformPointCloudWithNormals (const std::string &target_frame, const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::TransformListener &tf_listener) |
| Transforms a point cloud in a given target TF frame using a TransformListener. | |
| template<typename PointT > | |
| void | pcl_ros::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. | |