rviz::PointCloudTransformer Class Reference

#include <point_cloud_transformer.h>

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

List of all members.

Public Types

enum  SupportLevel { Support_None = 0, Support_XYZ = 1 << 1, Support_Color = 1 << 2, Support_Both = Support_XYZ|Support_Color }
 

Enumeration of support levels. Basic levels (Support_None, Support_XYZ, Support_Color) can be ored together to form a mask, Support_Both is provided as a convenience.

More...

Public Member Functions

void causeRetransform ()
virtual void createProperties (PropertyManager *property_man, const Property *&parent, const std::string &prefix, uint32_t mask, V_PropertyBaseWPtr &out_props)
 Create any properties necessary for this transformer. Will be called once when the transformer is loaded. All properties must be added to the out_props vector.
virtual void init (const RetransformFunc &retransform_func)
virtual void reset ()
 Reset any internal state used by this transformer.
virtual uint8_t score (const sensor_msgs::PointCloud2ConstPtr &cloud)
 "Score" a message for how well supported the message is. For example, a "flat color" transformer can support any cloud, but will return a score of 0 here since it should not be preferred over others that explicitly support fields in the message. This allows that "flat color" transformer to still be selectable, but generally not chosen automatically.
virtual uint8_t supports (const sensor_msgs::PointCloud2ConstPtr &cloud)=0
 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 &out)=0
 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().

Private Attributes

RetransformFunc retransform_func_

Detailed Description

Definition at line 63 of file point_cloud_transformer.h.


Member Enumeration Documentation

Enumeration of support levels. Basic levels (Support_None, Support_XYZ, Support_Color) can be ored together to form a mask, Support_Both is provided as a convenience.

Enumerator:
Support_None 
Support_XYZ 
Support_Color 
Support_Both 

Definition at line 74 of file point_cloud_transformer.h.


Member Function Documentation

void rviz::PointCloudTransformer::causeRetransform (  )  [inline]

Definition at line 66 of file point_cloud_transformer.h.

virtual void rviz::PointCloudTransformer::createProperties ( PropertyManager *  property_man,
const Property *&  parent,
const std::string &  prefix,
uint32_t  mask,
V_PropertyBaseWPtr &  out_props 
) [inline, virtual]

Create any properties necessary for this transformer. Will be called once when the transformer is loaded. All properties must be added to the out_props vector.

Reimplemented in rviz::IntensityPCTransformer, rviz::FlatColorPCTransformer, and rviz::AxisColorPCTransformer.

Definition at line 110 of file point_cloud_transformer.h.

virtual void rviz::PointCloudTransformer::init ( const RetransformFunc retransform_func  )  [inline, virtual]

Definition at line 68 of file point_cloud_transformer.h.

virtual void rviz::PointCloudTransformer::reset (  )  [inline, virtual]

Reset any internal state used by this transformer.

Reimplemented in rviz::IntensityPCTransformer.

Definition at line 103 of file point_cloud_transformer.h.

virtual uint8_t rviz::PointCloudTransformer::score ( const sensor_msgs::PointCloud2ConstPtr &  cloud  )  [inline, virtual]

"Score" a message for how well supported the message is. For example, a "flat color" transformer can support any cloud, but will return a score of 0 here since it should not be preferred over others that explicitly support fields in the message. This allows that "flat color" transformer to still be selectable, but generally not chosen automatically.

Reimplemented in rviz::IntensityPCTransformer, rviz::FlatColorPCTransformer, and rviz::AxisColorPCTransformer.

Definition at line 98 of file point_cloud_transformer.h.

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

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

Implemented in rviz::IntensityPCTransformer, rviz::XYZPCTransformer, rviz::RGB8PCTransformer, rviz::RGBF32PCTransformer, rviz::FlatColorPCTransformer, and rviz::AxisColorPCTransformer.

virtual bool rviz::PointCloudTransformer::transform ( const sensor_msgs::PointCloud2ConstPtr &  cloud,
uint32_t  mask,
const Ogre::Matrix4 &  transform,
V_PointCloudPoint out 
) [pure 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().

Implemented in rviz::IntensityPCTransformer, rviz::XYZPCTransformer, rviz::RGB8PCTransformer, rviz::RGBF32PCTransformer, rviz::FlatColorPCTransformer, and rviz::AxisColorPCTransformer.


Member Data Documentation

Reimplemented in rviz::IntensityPCTransformer.

Definition at line 117 of file point_cloud_transformer.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Wed Jun 6 11:25:48 2012