Namespaces | Functions
transforms.h File Reference
#include <sensor_msgs/PointCloud2.h>
#include <pcl/common/transforms.h>
#include <tf/transform_datatypes.h>
#include <tf/transform_listener.h>
Include dependency graph for transforms.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18