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

#include <point_cloud_transformers.h>

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

Public Member Functions

void createProperties (Property *parent_property, uint32_t mask, QList< Property *> &out_props) override
 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...
 
uint8_t score (const sensor_msgs::PointCloud2ConstPtr &cloud) override
 "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...
 
uint8_t supports (const sensor_msgs::PointCloud2ConstPtr &cloud) override
 Returns a level of support for a specific cloud. This level of support is a mask using the SupportLevel enum. More...
 
bool transform (const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t mask, const Ogre::Matrix4 &transform, V_PointCloudPoint &points_out) override
 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...
 
void updateChannels (const sensor_msgs::PointCloud2ConstPtr &cloud)
 
- Public Member Functions inherited from rviz::PointCloudTransformer
virtual void init ()
 

Private Slots

void updateAutoComputeIntensityBounds ()
 
void updateUseRainbow ()
 

Private Attributes

BoolPropertyauto_compute_intensity_bounds_property_
 
V_string available_channels_
 
EditableEnumPropertychannel_name_property_
 
BoolPropertyinvert_rainbow_property_
 
ColorPropertymax_color_property_
 
FloatPropertymax_intensity_property_
 
ColorPropertymin_color_property_
 
FloatPropertymin_intensity_property_
 
BoolPropertyuse_rainbow_property_
 

Additional Inherited Members

- 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...
 
- 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 116 of file point_cloud_transformers.h.

Member Function Documentation

◆ createProperties()

void rviz::IntensityPCTransformer::createProperties ( Property ,
uint32_t  ,
QList< Property *> &   
)
overridevirtual

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 180 of file point_cloud_transformers.cpp.

◆ score()

uint8_t rviz::IntensityPCTransformer::score ( const sensor_msgs::PointCloud2ConstPtr &  )
overridevirtual

"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 77 of file point_cloud_transformers.cpp.

◆ supports()

uint8_t rviz::IntensityPCTransformer::supports ( const sensor_msgs::PointCloud2ConstPtr &  cloud)
overridevirtual

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 71 of file point_cloud_transformers.cpp.

◆ transform()

bool rviz::IntensityPCTransformer::transform ( const sensor_msgs::PointCloud2ConstPtr &  cloud,
uint32_t  mask,
const Ogre::Matrix4 &  transform,
V_PointCloudPoint out 
)
overridevirtual

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 82 of file point_cloud_transformers.cpp.

◆ updateAutoComputeIntensityBounds

void rviz::IntensityPCTransformer::updateAutoComputeIntensityBounds ( )
privateslot

Definition at line 263 of file point_cloud_transformers.cpp.

◆ updateChannels()

void rviz::IntensityPCTransformer::updateChannels ( const sensor_msgs::PointCloud2ConstPtr &  cloud)

Definition at line 238 of file point_cloud_transformers.cpp.

◆ updateUseRainbow

void rviz::IntensityPCTransformer::updateUseRainbow ( )
privateslot

Definition at line 281 of file point_cloud_transformers.cpp.

Member Data Documentation

◆ auto_compute_intensity_bounds_property_

BoolProperty* rviz::IntensityPCTransformer::auto_compute_intensity_bounds_property_
private

Definition at line 138 of file point_cloud_transformers.h.

◆ available_channels_

V_string rviz::IntensityPCTransformer::available_channels_
private

Definition at line 134 of file point_cloud_transformers.h.

◆ channel_name_property_

EditableEnumProperty* rviz::IntensityPCTransformer::channel_name_property_
private

Definition at line 143 of file point_cloud_transformers.h.

◆ invert_rainbow_property_

BoolProperty* rviz::IntensityPCTransformer::invert_rainbow_property_
private

Definition at line 140 of file point_cloud_transformers.h.

◆ max_color_property_

ColorProperty* rviz::IntensityPCTransformer::max_color_property_
private

Definition at line 137 of file point_cloud_transformers.h.

◆ max_intensity_property_

FloatProperty* rviz::IntensityPCTransformer::max_intensity_property_
private

Definition at line 142 of file point_cloud_transformers.h.

◆ min_color_property_

ColorProperty* rviz::IntensityPCTransformer::min_color_property_
private

Definition at line 136 of file point_cloud_transformers.h.

◆ min_intensity_property_

FloatProperty* rviz::IntensityPCTransformer::min_intensity_property_
private

Definition at line 141 of file point_cloud_transformers.h.

◆ use_rainbow_property_

BoolProperty* rviz::IntensityPCTransformer::use_rainbow_property_
private

Definition at line 139 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 Sat May 27 2023 02:06:26