Gazebo Sim

API Reference

8.6.0
VisualizeLidar Class Reference

Visualize the LaserScan message returned by the sensors. Use the checkbox to turn visualization of non-hitting rays on or off and the textfield to select the message to be visualised. The combobox is used to select the type of visual for the sensor data. More...

#include <VisualizeLidar.hh>

Signals

void MaxRangeChanged ()
 Notify that maximum range has changed. More...
 
void MinRangeChanged ()
 Notify that minimum range has changed. More...
 
void TopicListChanged ()
 Notify that topic list has changed. More...
 

Public Member Functions

 VisualizeLidar ()
 Constructor. More...
 
 ~VisualizeLidar () override
 Destructor. More...
 
Q_INVOKABLE void DisplayVisual (bool _value)
 Set whether to display the lidar visual. More...
 
bool eventFilter (QObject *_obj, QEvent *_event) override
 
void LoadConfig (const tinyxml2::XMLElement *_pluginElem) override
 
void LoadLidar ()
 Load the scene and attach LidarVisual to the scene. More...
 
Q_INVOKABLE QString MaxRange () const
 Get the maximum range of the lidar sensor (in metres). More...
 
Q_INVOKABLE QString MinRange () const
 Get the minimum range of the lidar sensor (in metres). More...
 
Q_INVOKABLE void OnRefresh ()
 Callback when refresh button is pressed. More...
 
void OnScan (const msgs::LaserScan &_msg)
 Callback function to get data from the message. More...
 
Q_INVOKABLE void OnTopic (const QString &_topicName)
 Set topic to subscribe for LidarSensor data. More...
 
Q_INVOKABLE void SetTopicList (const QStringList &_topicList)
 Set the topic list from a string, for example 'gz.msgs.StringMsg'. More...
 
Q_INVOKABLE QStringList TopicList () const
 Get the topic list as a string. More...
 
void Update (const UpdateInfo &, EntityComponentManager &_ecm) override
 Update callback called every time the system is stepped. This is called at a Gazebo Transport thread, so any interaction with Qt should be done through signals and slots. More...
 
Q_INVOKABLE void UpdateNonHitting (bool _value)
 Set whether to display non-hitting rays. More...
 
Q_INVOKABLE void UpdateSize (int _size)
 Set lidar visualization size. More...
 
Q_INVOKABLE void UpdateType (int _type)
 Set visual type of LidarVisual. More...
 
- Public Member Functions inherited from Plugin
 Plugin ()
 
virtual ~Plugin ()
 
QQuickItem * CardItem () const
 
virtual std::string ConfigStr ()
 
QQmlContext * Context () const
 
bool DeleteLaterRequested () const
 
void Load (const tinyxml2::XMLElement *_pluginElem)
 
QQuickItem * PluginItem () const
 
void PostParentChanges ()
 
virtual std::string Title () const
 

Properties

QString maxRange
 Max Range. More...
 
QString minRange
 Min Range. More...
 
QStringList topicList
 Topic list. More...
 

Additional Inherited Members

- Protected Member Functions inherited from Plugin
void DeleteLater ()
 
- Protected Attributes inherited from Plugin
std::string configStr
 
std::string title
 

Detailed Description

Visualize the LaserScan message returned by the sensors. Use the checkbox to turn visualization of non-hitting rays on or off and the textfield to select the message to be visualised. The combobox is used to select the type of visual for the sensor data.

Constructor & Destructor Documentation

◆ VisualizeLidar()

Constructor.

◆ ~VisualizeLidar()

~VisualizeLidar ( )
override

Destructor.

Member Function Documentation

◆ DisplayVisual()

Q_INVOKABLE void DisplayVisual ( bool  _value)

Set whether to display the lidar visual.

Parameters
[in]_valueBoolean value for displaying the visual

◆ eventFilter()

bool eventFilter ( QObject *  _obj,
QEvent *  _event 
)
override

◆ LoadConfig()

void LoadConfig ( const tinyxml2::XMLElement *  _pluginElem)
overridevirtual

Reimplemented from Plugin.

◆ LoadLidar()

void LoadLidar ( )

Load the scene and attach LidarVisual to the scene.

◆ MaxRange()

Q_INVOKABLE QString MaxRange ( ) const

Get the maximum range of the lidar sensor (in metres).

Returns
Range, the maximum distance sensed by the sensor.

◆ MaxRangeChanged

void MaxRangeChanged ( )
signal

Notify that maximum range has changed.

◆ MinRange()

Q_INVOKABLE QString MinRange ( ) const

Get the minimum range of the lidar sensor (in metres).

Returns
Range, the minimum distance sensed by the sensor.

◆ MinRangeChanged

void MinRangeChanged ( )
signal

Notify that minimum range has changed.

◆ OnRefresh()

Q_INVOKABLE void OnRefresh ( )

Callback when refresh button is pressed.

◆ OnScan()

void OnScan ( const msgs::LaserScan &  _msg)

Callback function to get data from the message.

Parameters
[in]

◆ OnTopic()

Q_INVOKABLE void OnTopic ( const QString &  _topicName)

Set topic to subscribe for LidarSensor data.

Parameters
[in]_topicNameName of selected topic

◆ SetTopicList()

Q_INVOKABLE void SetTopicList ( const QStringList &  _topicList)

Set the topic list from a string, for example 'gz.msgs.StringMsg'.

Parameters
[in]_topicListMessage type

◆ TopicList()

Q_INVOKABLE QStringList TopicList ( ) const

Get the topic list as a string.

Returns
Message type

◆ TopicListChanged

void TopicListChanged ( )
signal

Notify that topic list has changed.

◆ Update()

void Update ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Update callback called every time the system is stepped. This is called at a Gazebo Transport thread, so any interaction with Qt should be done through signals and slots.

Parameters
[in]_infoCurrent simulation information, such as time.
[in]_ecmMutable reference to the ECM, so the system can read and write entities and their components.

Reimplemented from GuiSystem.

◆ UpdateNonHitting()

Q_INVOKABLE void UpdateNonHitting ( bool  _value)

Set whether to display non-hitting rays.

Parameters
[in]_valueBoolean value for displaying non hitting rays

◆ UpdateSize()

Q_INVOKABLE void UpdateSize ( int  _size)

Set lidar visualization size.

Parameters
[in]_sizeSize of lidar visualization

◆ UpdateType()

Q_INVOKABLE void UpdateType ( int  _type)

Set visual type of LidarVisual.

Parameters
[in]_typeIndex of selected visual type

Property Documentation

◆ maxRange

QString maxRange
read

Max Range.

◆ minRange

QString minRange
read

Min Range.

◆ topicList

QStringList topicList
readwrite

Topic list.


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