Visualize gz::msgs::PointCloudPacked
messages in a 3D scene.
More...
#include <PointCloud.hh>
Signals | |
void | FloatVTopicListChanged () |
Notify that topic list has changed. More... | |
void | MaxColorChanged () |
Notify that maximum color has changed. More... | |
void | MaxFloatVChanged () |
Notify that maximum value has changed. More... | |
void | MinColorChanged () |
Notify that minimum color has changed. More... | |
void | MinFloatVChanged () |
Notify that minimum value has changed. More... | |
void | PointCloudTopicListChanged () |
Notify that topic list has changed. More... | |
void | PointSizeChanged () |
Notify that point size has changed. More... | |
Public Member Functions | |
PointCloud () | |
Constructor. More... | |
~PointCloud () override | |
Destructor. More... | |
Q_INVOKABLE QStringList | FloatVTopicList () const |
Get the topic list. More... | |
void | LoadConfig (const tinyxml2::XMLElement *_pluginElem) override |
Q_INVOKABLE QColor | MaxColor () const |
Get the maximum color. More... | |
Q_INVOKABLE float | MaxFloatV () const |
Get the maximum value. More... | |
Q_INVOKABLE QColor | MinColor () const |
Get the minimum color. More... | |
Q_INVOKABLE float | MinFloatV () const |
Get the minimum value. More... | |
void | OnFloatV (const msgs::Float_V &_msg) |
Callback function for float vector topic. More... | |
void | OnFloatVService (const msgs::Float_V &_msg, bool _result) |
Callback function for point cloud service. More... | |
Q_INVOKABLE void | OnFloatVTopic (const QString &_topicName) |
Set topic to subscribe to for float vectors. More... | |
void | OnPointCloud (const msgs::PointCloudPacked &_msg) |
Callback function for point cloud topic. More... | |
void | OnPointCloudService (const msgs::PointCloudPacked &_msg, bool _result) |
Callback function for point cloud service. More... | |
Q_INVOKABLE void | OnPointCloudTopic (const QString &_topicName) |
Set topic to subscribe to for point cloud. More... | |
Q_INVOKABLE void | OnRefresh () |
Callback when refresh button is pressed. More... | |
Q_INVOKABLE QStringList | PointCloudTopicList () const |
Get the topic list. More... | |
Q_INVOKABLE float | PointSize () const |
Get the point size. More... | |
Q_INVOKABLE void | SetFloatVTopicList (const QStringList &_floatVTopicList) |
Set the topic list from a string. More... | |
Q_INVOKABLE void | SetMaxColor (const QColor &_maxColor) |
Set the maximum color. More... | |
Q_INVOKABLE void | SetMaxFloatV (float _maxFloatV) |
Set the maximum value. More... | |
Q_INVOKABLE void | SetMinColor (const QColor &_minColor) |
Set the minimum color. More... | |
Q_INVOKABLE void | SetMinFloatV (float _minFloatV) |
Set the minimum value. More... | |
Q_INVOKABLE void | SetPointCloudTopicList (const QStringList &_pointCloudTopicList) |
Set the topic list from a string. More... | |
Q_INVOKABLE void | SetPointSize (float _pointSize) |
Set the point size. More... | |
Q_INVOKABLE void | Show (bool _show) |
Set whether to show the point cloud. More... | |
Properties | |
QStringList | floatVTopicList |
List of topics publishing FloatV messages. More... | |
QColor | maxColor |
Color for maximum value. More... | |
float | maxFloatV |
Maximum value. More... | |
QColor | minColor |
Color for minimum value. More... | |
float | minFloatV |
Minimum value. More... | |
QStringList | pointCloudTopicList |
List of topics publishing PointCloudPacked messages. More... | |
float | pointSize |
Point size. More... | |
Detailed Description
Visualize gz::msgs::PointCloudPacked
messages in a 3D scene.
By default, the whole cloud is displayed using a single color. Users can optionally choose a topic publishing gz::msgs::FloatV
messages which will be used to color all points with a color gradient according to their values. The float message must have the same number of elements as the point cloud and be indexed the same way. NaN values on the FloatV message aren't displayed.
Requirements:
- A plugin that loads a 3D scene, such as
MinimalScene
- The
MarkerManager
plugin
Parameters:
<point_cloud_topic>
: Topic to receivegz::msgs::PointCloudPacked
messages.<float_v_topic>
: Topic to receivegz::msgs::FloatV
messages.
Constructor & Destructor Documentation
◆ PointCloud()
PointCloud | ( | ) |
Constructor.
◆ ~PointCloud()
|
override |
Destructor.
Member Function Documentation
◆ FloatVTopicList()
Q_INVOKABLE QStringList FloatVTopicList | ( | ) | const |
Get the topic list.
- Returns
- List of topics
◆ FloatVTopicListChanged
|
signal |
Notify that topic list has changed.
◆ LoadConfig()
|
override |
◆ MaxColor()
Q_INVOKABLE QColor MaxColor | ( | ) | const |
Get the maximum color.
- Returns
- Maximum color
◆ MaxColorChanged
|
signal |
Notify that maximum color has changed.
◆ MaxFloatV()
Q_INVOKABLE float MaxFloatV | ( | ) | const |
Get the maximum value.
- Returns
- Maximum value
◆ MaxFloatVChanged
|
signal |
Notify that maximum value has changed.
◆ MinColor()
Q_INVOKABLE QColor MinColor | ( | ) | const |
Get the minimum color.
- Returns
- Minimum color
◆ MinColorChanged
|
signal |
Notify that minimum color has changed.
◆ MinFloatV()
Q_INVOKABLE float MinFloatV | ( | ) | const |
Get the minimum value.
- Returns
- Minimum value
◆ MinFloatVChanged
|
signal |
Notify that minimum value has changed.
◆ OnFloatV()
void OnFloatV | ( | const msgs::Float_V & | _msg | ) |
Callback function for float vector topic.
- Parameters
-
[in] _msg Float vector message
◆ OnFloatVService()
void OnFloatVService | ( | const msgs::Float_V & | _msg, |
bool | _result | ||
) |
Callback function for point cloud service.
- Parameters
-
[in] _msg Float vector message [out] _result True on success.
◆ OnFloatVTopic()
Q_INVOKABLE void OnFloatVTopic | ( | const QString & | _topicName | ) |
Set topic to subscribe to for float vectors.
- Parameters
-
[in] _topicName Name of selected topic
◆ OnPointCloud()
void OnPointCloud | ( | const msgs::PointCloudPacked & | _msg | ) |
Callback function for point cloud topic.
- Parameters
-
[in] _msg Point cloud message
◆ OnPointCloudService()
void OnPointCloudService | ( | const msgs::PointCloudPacked & | _msg, |
bool | _result | ||
) |
Callback function for point cloud service.
- Parameters
-
[in] _msg Point cloud message [out] _result True on success.
◆ OnPointCloudTopic()
Q_INVOKABLE void OnPointCloudTopic | ( | const QString & | _topicName | ) |
Set topic to subscribe to for point cloud.
- Parameters
-
[in] _topicName Name of selected topic
◆ OnRefresh()
Q_INVOKABLE void OnRefresh | ( | ) |
Callback when refresh button is pressed.
◆ PointCloudTopicList()
Q_INVOKABLE QStringList PointCloudTopicList | ( | ) | const |
Get the topic list.
- Returns
- List of topics
◆ PointCloudTopicListChanged
|
signal |
Notify that topic list has changed.
◆ PointSize()
Q_INVOKABLE float PointSize | ( | ) | const |
Get the point size.
- Returns
- Maximum value
◆ PointSizeChanged
|
signal |
Notify that point size has changed.
◆ SetFloatVTopicList()
Q_INVOKABLE void SetFloatVTopicList | ( | const QStringList & | _floatVTopicList | ) |
Set the topic list from a string.
- Parameters
-
[in] _floatVTopicList List of topics.
◆ SetMaxColor()
Q_INVOKABLE void SetMaxColor | ( | const QColor & | _maxColor | ) |
Set the maximum color.
- Parameters
-
[in] _maxColor Maximum color.
◆ SetMaxFloatV()
Q_INVOKABLE void SetMaxFloatV | ( | float | _maxFloatV | ) |
Set the maximum value.
- Parameters
-
[in] _maxFloatV Maximum value.
◆ SetMinColor()
Q_INVOKABLE void SetMinColor | ( | const QColor & | _minColor | ) |
Set the minimum color.
- Parameters
-
[in] _minColor Minimum color.
◆ SetMinFloatV()
Q_INVOKABLE void SetMinFloatV | ( | float | _minFloatV | ) |
Set the minimum value.
- Parameters
-
[in] _minFloatV Minimum value.
◆ SetPointCloudTopicList()
Q_INVOKABLE void SetPointCloudTopicList | ( | const QStringList & | _pointCloudTopicList | ) |
Set the topic list from a string.
- Parameters
-
[in] _pointCloudTopicList List of topics.
◆ SetPointSize()
Q_INVOKABLE void SetPointSize | ( | float | _pointSize | ) |
Set the point size.
- Parameters
-
[in] _pointSize Maximum value.
◆ Show()
Q_INVOKABLE void Show | ( | bool | _show | ) |
Set whether to show the point cloud.
- Parameters
-
[in] _show Boolean value for displaying the points.
Property Documentation
◆ floatVTopicList
|
readwrite |
List of topics publishing FloatV messages.
◆ maxColor
|
readwrite |
Color for maximum value.
◆ maxFloatV
|
readwrite |
Maximum value.
◆ minColor
|
readwrite |
Color for minimum value.
◆ minFloatV
|
readwrite |
Minimum value.
◆ pointCloudTopicList
|
readwrite |
List of topics publishing PointCloudPacked messages.
◆ pointSize
|
readwrite |
Point size.
The documentation for this class was generated from the following file: