#include <point_cloud_transformer.h>
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... | |
Signals | |
void | needRetransform () |
Subclasses should emit this signal whenever they think the points should be re-transformed. 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 void | init () |
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)=0 |
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 &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() More... | |
Definition at line 60 of file point_cloud_transformer.h.
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 70 of file point_cloud_transformer.h.
|
inlinevirtual |
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::AxisColorPCTransformer, rviz::FlatColorPCTransformer, and rviz::IntensityPCTransformer.
Definition at line 101 of file point_cloud_transformer.h.
|
inlinevirtual |
Definition at line 64 of file point_cloud_transformer.h.
|
signal |
Subclasses should emit this signal whenever they think the points should be re-transformed.
|
inlinevirtual |
"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::AxisColorPCTransformer, rviz::FlatColorPCTransformer, and rviz::IntensityPCTransformer.
Definition at line 94 of file point_cloud_transformer.h.
|
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::AxisColorPCTransformer, rviz::FlatColorPCTransformer, rviz::RGBF32PCTransformer, rviz::RGB8PCTransformer, rviz::XYZPCTransformer, and rviz::IntensityPCTransformer.
|
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::AxisColorPCTransformer, rviz::FlatColorPCTransformer, rviz::RGBF32PCTransformer, rviz::MONO8PCTransformer, rviz::RGB8PCTransformer, rviz::XYZPCTransformer, and rviz::IntensityPCTransformer.