Public Types | Public Member Functions | Private Slots | Private Attributes | List of all members
rviz::AxisColorPCTransformer Class Reference

#include <point_cloud_transformers.h>

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

Public Types

enum  Axis { AXIS_X, AXIS_Y, AXIS_Z }
 
- Public Types inherited from rviz::PointCloudTransformer
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

virtual void createProperties (Property *parent_property, uint32_t mask, QList< Property * > &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. More...
 
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. More...
 
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. More...
 
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() More...
 
- Public Member Functions inherited from rviz::PointCloudTransformer
virtual void init ()
 

Private Slots

void updateAutoComputeBounds ()
 

Private Attributes

BoolPropertyauto_compute_bounds_property_
 
EnumPropertyaxis_property_
 
FloatPropertymax_value_property_
 
FloatPropertymin_value_property_
 
BoolPropertyuse_fixed_frame_property_
 

Additional Inherited Members

- Signals inherited from rviz::PointCloudTransformer
void needRetransform ()
 Subclasses should emit this signal whenever they think the points should be re-transformed. More...
 

Detailed Description

Definition at line 195 of file point_cloud_transformers.h.

Member Enumeration Documentation

Enumerator
AXIS_X 
AXIS_Y 
AXIS_Z 

Definition at line 204 of file point_cloud_transformers.h.

Member Function Documentation

void rviz::AxisColorPCTransformer::createProperties ( Property parent_property,
uint32_t  mask,
QList< Property * > &  out_props 
)
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 from rviz::PointCloudTransformer.

Definition at line 620 of file point_cloud_transformers.cpp.

uint8_t rviz::AxisColorPCTransformer::score ( const sensor_msgs::PointCloud2ConstPtr &  cloud)
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 from rviz::PointCloudTransformer.

Definition at line 532 of file point_cloud_transformers.cpp.

uint8_t rviz::AxisColorPCTransformer::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 527 of file point_cloud_transformers.cpp.

bool rviz::AxisColorPCTransformer::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 537 of file point_cloud_transformers.cpp.

void rviz::AxisColorPCTransformer::updateAutoComputeBounds ( )
privateslot

Definition at line 655 of file point_cloud_transformers.cpp.

Member Data Documentation

BoolProperty* rviz::AxisColorPCTransformer::auto_compute_bounds_property_
private

Definition at line 215 of file point_cloud_transformers.h.

EnumProperty* rviz::AxisColorPCTransformer::axis_property_
private

Definition at line 218 of file point_cloud_transformers.h.

FloatProperty* rviz::AxisColorPCTransformer::max_value_property_
private

Definition at line 217 of file point_cloud_transformers.h.

FloatProperty* rviz::AxisColorPCTransformer::min_value_property_
private

Definition at line 216 of file point_cloud_transformers.h.

BoolProperty* rviz::AxisColorPCTransformer::use_fixed_frame_property_
private

Definition at line 219 of file point_cloud_transformers.h.


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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:52