#include <point_cloud_transformers.h>
|
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) |
|
virtual void | init () |
|
Definition at line 116 of file point_cloud_transformers.h.
◆ createProperties()
void rviz::IntensityPCTransformer::createProperties |
( |
Property * |
, |
|
|
uint32_t |
, |
|
|
QList< Property *> & |
|
|
) |
| |
|
overridevirtual |
◆ 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 |
◆ transform()
bool rviz::IntensityPCTransformer::transform |
( |
const sensor_msgs::PointCloud2ConstPtr & |
cloud, |
|
|
uint32_t |
mask, |
|
|
const Ogre::Matrix4 & |
transform, |
|
|
V_PointCloudPoint & |
out |
|
) |
| |
|
overridevirtual |
◆ updateAutoComputeIntensityBounds
void rviz::IntensityPCTransformer::updateAutoComputeIntensityBounds |
( |
| ) |
|
|
privateslot |
◆ updateChannels()
void rviz::IntensityPCTransformer::updateChannels |
( |
const sensor_msgs::PointCloud2ConstPtr & |
cloud | ) |
|
◆ updateUseRainbow
void rviz::IntensityPCTransformer::updateUseRainbow |
( |
| ) |
|
|
privateslot |
◆ auto_compute_intensity_bounds_property_
BoolProperty* rviz::IntensityPCTransformer::auto_compute_intensity_bounds_property_ |
|
private |
◆ available_channels_
V_string rviz::IntensityPCTransformer::available_channels_ |
|
private |
◆ channel_name_property_
◆ invert_rainbow_property_
BoolProperty* rviz::IntensityPCTransformer::invert_rainbow_property_ |
|
private |
◆ max_color_property_
◆ max_intensity_property_
FloatProperty* rviz::IntensityPCTransformer::max_intensity_property_ |
|
private |
◆ min_color_property_
◆ min_intensity_property_
FloatProperty* rviz::IntensityPCTransformer::min_intensity_property_ |
|
private |
◆ use_rainbow_property_
BoolProperty* rviz::IntensityPCTransformer::use_rainbow_property_ |
|
private |
The documentation for this class was generated from the following files: