$search

pcl_ros Namespace Reference

Classes

class  BAGReader
 BAG PointCloud file format reader. More...
class  BasePublisher
class  BoundaryEstimation
 BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. The code makes use of the estimated surface normals at each point in the input dataset. More...
class  ConvexHull2D
 ConvexHull2D represents a 2D ConvexHull implementation. More...
class  EuclideanClusterExtraction
 EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. More...
class  ExtractIndices
 ExtractIndices extracts a set of indices from a PointCloud as a separate PointCloud. More...
class  ExtractPolygonalPrismData
 ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it. More...
class  Feature
 Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods. More...
class  FeatureFromNormals
class  Filter
 Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods. More...
class  FPFHEstimation
 FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals. More...
class  FPFHEstimationOMP
 FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals, in parallel, using the OpenMP standard. More...
class  MomentInvariantsEstimation
 MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point. More...
class  MovingLeastSquares
 MovingLeastSquares represents a nodelet using the MovingLeastSquares implementation. The type of the output is the same as the input, it only smooths the XYZ coordinates according to the parameters. Normals are estimated at each point as well and published on a separate topic. More...
class  NormalEstimation
 NormalEstimation estimates local surface properties at each 3D point, such as surface normals and curvatures. More...
class  NormalEstimationOMP
 NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and curvatures, in parallel, using the OpenMP standard. More...
class  NormalEstimationTBB
 NormalEstimationTBB estimates local surface properties at each 3D point, such as surface normals and curvatures, in parallel, using Intel's Threading Building Blocks library. More...
class  PassThrough
 PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. More...
class  PCDReader
 Point Cloud Data (PCD) file format reader. More...
class  PCDWriter
 Point Cloud Data (PCD) file format writer. More...
class  PCLNodelet
 PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class. More...
class  PFHEstimation
 PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset containing points and normals. More...
class  PointCloudConcatenateDataSynchronizer
 PointCloudConcatenateFieldsSynchronizer is a special form of data synchronizer: it listens for a set of input PointCloud messages on the same topic, checks their timestamps, and concatenates their fields together into a single PointCloud output message. More...
class  PointCloudConcatenateFieldsSynchronizer
 PointCloudConcatenateFieldsSynchronizer is a special form of data synchronizer: it listens for a set of input PointCloud messages on the same topic, checks their timestamps, and concatenates their fields together into a single PointCloud output message. More...
class  PrincipalCurvaturesEstimation
 PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of principal surface curvatures for a given point cloud dataset containing points and normals. More...
class  ProjectInliers
 ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud. More...
class  Publisher
class  Publisher< sensor_msgs::PointCloud2 >
class  RadiusOutlierRemoval
 RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain search radius is smaller than a given K. More...
class  SACSegmentation
 SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models, in the sense that it just creates a Nodelet wrapper for generic-purpose SAC-based segmentation. More...
class  SACSegmentationFromNormals
 SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation. More...
class  SegmentDifferences
 SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold. More...
class  StatisticalOutlierRemoval
 StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check: More...
class  TestListener
class  TestPingPong
class  TestTalker
class  VFHEstimation
 VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud dataset containing points and normals. More...
class  VoxelGrid
 VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...

Functions

void transformAsMatrix (const tf::Transform &bt, Eigen::Matrix4f &out_mat)
 Obtain the transformation matrix from TF into an Eigen form.
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.
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.
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.
template<typename PointT >
bool 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 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 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 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 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 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.

Detailed Description

Author:
Radu Bogdan Rusu
Patrick Mihelich

Publisher represents a ROS publisher for the templated PointCloud implementation.


Function Documentation

void pcl_ros::transformAsMatrix ( const tf::Transform bt,
Eigen::Matrix4f &  out_mat 
)

Obtain the transformation matrix from TF into an Eigen form.

Parameters:
bt the TF transformation
out_mat the Eigen transformation

Definition at line 211 of file transforms.cpp.

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.

Parameters:
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.

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.

Parameters:
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.

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.

Parameters:
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.

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 
) [inline]

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_listener a TF listener object
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 
) [inline]

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
cloud_in the input point cloud
cloud_out the input point cloud
tf_listener a TF listener object
template<typename PointT >
void pcl_ros::transformPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
pcl::PointCloud< PointT > &  cloud_out,
const tf::Transform transform 
) [inline]

Apply a rigid transform defined by a 3D offset and a quaternion.

Parameters:
cloud_in the input point cloud
cloud_out the input point cloud
transform a rigid transformation from tf
Note:
calls the Eigen version
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 
) [inline]

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_listener a TF listener object
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 
) [inline]

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
cloud_in the input point cloud
cloud_out the input point cloud
tf_listener a TF listener object
template<typename PointT >
void pcl_ros::transformPointCloudWithNormals ( const pcl::PointCloud< PointT > &  cloud_in,
pcl::PointCloud< PointT > &  cloud_out,
const tf::Transform transform 
) [inline]

Transform a point cloud and rotate its normals using an Eigen transform.

Parameters:
cloud_in the input point cloud
cloud_out the input point cloud
transform a rigid transformation from tf
Note:
calls the Eigen version
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pcl_ros
Author(s): Maintained by Radu Bogdan Rusu
autogenerated on Fri Mar 1 16:26:34 2013