Public Member Functions
rviz::RGBF32PCTransformer Class Reference

#include <point_cloud_transformers.h>

Inheritance diagram for rviz::RGBF32PCTransformer:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual uint8_t supports (const sensor_msgs::PointCloud2ConstPtr &cloud)
 Returns a level of support for a specific cloud. This level of support is a mask using the SupportLevel enum.
virtual bool transform (const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out)
 Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preallocated into the correct size. The mask determines which part of the cloud should be output (xyz or color). This method will only be called if supports() of the same cloud has returned a non-zero mask, and will only be called with masks compatible with the one returned from supports()

Detailed Description

Definition at line 162 of file point_cloud_transformers.h.


Member Function Documentation

uint8_t rviz::RGBF32PCTransformer::supports ( const sensor_msgs::PointCloud2ConstPtr &  cloud) [virtual]

Returns a level of support for a specific cloud. This level of support is a mask using the SupportLevel enum.

Implements rviz::PointCloudTransformer.

Definition at line 356 of file point_cloud_transformers.cpp.

bool rviz::RGBF32PCTransformer::transform ( const sensor_msgs::PointCloud2ConstPtr &  cloud,
uint32_t  mask,
const Ogre::Matrix4 &  transform,
V_PointCloudPoint out 
) [virtual]

Transforms a PointCloud2 into an rviz::PointCloud. The rviz::PointCloud is assumed to have been preallocated into the correct size. The mask determines which part of the cloud should be output (xyz or color). This method will only be called if supports() of the same cloud has returned a non-zero mask, and will only be called with masks compatible with the one returned from supports()

Implements rviz::PointCloudTransformer.

Definition at line 374 of file point_cloud_transformers.cpp.


The documentation for this class was generated from the following files:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:37