Functions | |
| void | transformAsMatrix (const tf::Transform &bt, Eigen::Matrix4f &out_mat) |
| Obtain the transformation matrix from TF into an Eigen form. | |
| template<typename PointT > | |
| void | transformPointCloud (const pcl16::PointCloud< PointT > &cloud_in, pcl16::PointCloud< PointT > &cloud_out, const tf::Transform &transform) |
| Apply a rigid transform defined by a 3D offset and a quaternion. | |
| template<typename PointT > | |
| bool | transformPointCloud (const std::string &target_frame, const pcl16::PointCloud< PointT > &cloud_in, pcl16::PointCloud< PointT > &cloud_out, const tf::TransformListener &tf_listener) |
| Transforms a point cloud in a given target TF frame using a TransformListener. | |
| bool | 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. | |
| void | 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. | |
| void | 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. | |
| template<typename PointT > | |
| bool | transformPointCloud (const std::string &target_frame, const ros::Time &target_time, const pcl16::PointCloud< PointT > &cloud_in, const std::string &fixed_frame, pcl16::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 | transformPointCloudWithNormals (const pcl16::PointCloud< PointT > &cloud_in, pcl16::PointCloud< PointT > &cloud_out, const tf::Transform &transform) |
| Transform a point cloud and rotate its normals using an Eigen transform. | |
| template<typename PointT > | |
| bool | transformPointCloudWithNormals (const std::string &target_frame, const pcl16::PointCloud< PointT > &cloud_in, pcl16::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 | transformPointCloudWithNormals (const std::string &target_frame, const ros::Time &target_time, const pcl16::PointCloud< PointT > &cloud_in, const std::string &fixed_frame, pcl16::PointCloud< PointT > &cloud_out, const tf::TransformListener &tf_listener) |
| Transforms a point cloud in a given target TF frame using a TransformListener. | |
| void pcl16_ros::transformAsMatrix | ( | const tf::Transform & | bt, |
| Eigen::Matrix4f & | out_mat | ||
| ) |
Obtain the transformation matrix from TF into an Eigen form.
| bt | the TF transformation |
| out_mat | the Eigen transformation |
Definition at line 211 of file transforms.cpp.
| void pcl16_ros::transformPointCloud | ( | const pcl16::PointCloud< PointT > & | cloud_in, |
| pcl16::PointCloud< PointT > & | cloud_out, | ||
| const tf::Transform & | transform | ||
| ) |
Apply a rigid transform defined by a 3D offset and a quaternion.
| cloud_in | the input point cloud |
| cloud_out | the input point cloud |
| transform | a rigid transformation from tf |
Definition at line 67 of file transforms.hpp.
| bool pcl16_ros::transformPointCloud | ( | const std::string & | target_frame, |
| const pcl16::PointCloud< PointT > & | cloud_in, | ||
| pcl16::PointCloud< PointT > & | cloud_out, | ||
| const tf::TransformListener & | tf_listener | ||
| ) |
Transforms a point cloud in a given target TF frame using a TransformListener.
| target_frame | the target TF frame the point cloud should be transformed to |
| cloud_in | the input point cloud |
| cloud_out | the input point cloud |
| tf_listener | a TF listener object |
Definition at line 122 of file transforms.hpp.
| bool pcl16_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.
| target_frame | the target TF frame |
| in | the input PointCloud2 dataset |
| out | the resultant transformed PointCloud2 dataset |
| tf_listener | a TF listener object |
Definition at line 47 of file transforms.cpp.
| void pcl16_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.
| target_frame | the target TF frame |
| net_transform | the TF transformer object |
| in | the input PointCloud2 dataset |
| out | the resultant transformed PointCloud2 dataset |
Definition at line 85 of file transforms.cpp.
| void pcl16_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.
| transform | the transformation to use on the points |
| in | the input PointCloud2 dataset |
| out | the resultant transformed PointCloud2 dataset |
Definition at line 105 of file transforms.cpp.
| bool pcl16_ros::transformPointCloud | ( | const std::string & | target_frame, |
| const ros::Time & | target_time, | ||
| const pcl16::PointCloud< PointT > & | cloud_in, | ||
| const std::string & | fixed_frame, | ||
| pcl16::PointCloud< PointT > & | cloud_out, | ||
| const tf::TransformListener & | tf_listener | ||
| ) |
Transforms a point cloud in a given target TF frame using a TransformListener.
| 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_listener | a TF listener object |
Definition at line 155 of file transforms.hpp.
| void pcl16_ros::transformPointCloudWithNormals | ( | const pcl16::PointCloud< PointT > & | cloud_in, |
| pcl16::PointCloud< PointT > & | cloud_out, | ||
| const tf::Transform & | transform | ||
| ) |
Transform a point cloud and rotate its normals using an Eigen transform.
| cloud_in | the input point cloud |
| cloud_out | the input point cloud |
| transform | a rigid transformation from tf |
Definition at line 46 of file transforms.hpp.
| bool pcl16_ros::transformPointCloudWithNormals | ( | const std::string & | target_frame, |
| const pcl16::PointCloud< PointT > & | cloud_in, | ||
| pcl16::PointCloud< PointT > & | cloud_out, | ||
| const tf::TransformListener & | tf_listener | ||
| ) |
Transforms a point cloud in a given target TF frame using a TransformListener.
| target_frame | the target TF frame the point cloud should be transformed to |
| cloud_in | the input point cloud |
| cloud_out | the input point cloud |
| tf_listener | a TF listener object |
Definition at line 88 of file transforms.hpp.
| bool pcl16_ros::transformPointCloudWithNormals | ( | const std::string & | target_frame, |
| const ros::Time & | target_time, | ||
| const pcl16::PointCloud< PointT > & | cloud_in, | ||
| const std::string & | fixed_frame, | ||
| pcl16::PointCloud< PointT > & | cloud_out, | ||
| const tf::TransformListener & | tf_listener | ||
| ) |
Transforms a point cloud in a given target TF frame using a TransformListener.
| 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_listener | a TF listener object |
Definition at line 186 of file transforms.hpp.