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 visualized. The combobox is used to select the type of visual for the sensor data.  
 More...
#include <VisualizeLidar.hh>
 | 
|   | VisualizeLidar () | 
|   | Constructor.  
  | 
|   | 
|   | ~VisualizeLidar () override | 
|   | Destructor.  
  | 
|   | 
| Q_INVOKABLE void  | DisplayVisual (bool _value) | 
|   | Set whether to display the lidar visual.  
  | 
|   | 
| 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.  
  | 
|   | 
| Q_INVOKABLE QString  | MaxRange () const | 
|   | Get the maximum range of the lidar sensor (in metres).  
  | 
|   | 
| Q_INVOKABLE QString  | MinRange () const | 
|   | Get the minimum range of the lidar sensor (in metres).  
  | 
|   | 
| Q_INVOKABLE void  | OnRefresh () | 
|   | Callback when refresh button is pressed.  
  | 
|   | 
| void  | OnScan (const msgs::LaserScan &_msg) | 
|   | Callback function to get data from the message.  
  | 
|   | 
| Q_INVOKABLE void  | OnTopic (const QString &_topicName) | 
|   | Set topic to subscribe for LidarSensor data.  
  | 
|   | 
| Q_INVOKABLE void  | SetTopicList (const QStringList &_topicList) | 
|   | Set the topic list from a string, for example 'gz.msgs.StringMsg'.  
  | 
|   | 
| Q_INVOKABLE QStringList  | TopicList () const | 
|   | Get the topic list as a string.  
  | 
|   | 
| 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.  
  | 
|   | 
| Q_INVOKABLE void  | UpdateNonHitting (bool _value) | 
|   | Set whether to display non-hitting rays.  
  | 
|   | 
| Q_INVOKABLE void  | UpdateSize (int _size) | 
|   | Set lidar visualization size.  
  | 
|   | 
| Q_INVOKABLE void  | UpdateType (int _type) | 
|   | Set visual type of LidarVisual.  
  | 
|   | 
|   | 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 | 
|   | 
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 visualized. The combobox is used to select the type of visual for the sensor data. 
 
◆ VisualizeLidar()
◆ ~VisualizeLidar()
◆ DisplayVisual()
      
        
          | Q_INVOKABLE void DisplayVisual  | 
          ( | 
          bool  | 
          _value | ) | 
           | 
        
      
 
Set whether to display the lidar visual. 
- Parameters
 - 
  
    | [in] | _value | Boolean value for displaying the visual  | 
  
   
 
 
◆ eventFilter()
  
  
      
        
          | bool eventFilter  | 
          ( | 
          QObject *  | 
          _obj,  | 
         
        
           | 
           | 
          QEvent *  | 
          _event  | 
         
        
           | 
          ) | 
           |  | 
         
       
   | 
  
override   | 
  
 
 
◆ LoadConfig()
  
  
      
        
          | void LoadConfig  | 
          ( | 
          const tinyxml2::XMLElement *  | 
          _pluginElem | ) | 
           | 
         
       
   | 
  
overridevirtual   | 
  
 
 
◆ 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
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
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
 - 
  
  
 
LidarSensor message 
 
 
◆ OnTopic()
      
        
          | Q_INVOKABLE void OnTopic  | 
          ( | 
          const QString &  | 
          _topicName | ) | 
           | 
        
      
 
Set topic to subscribe for LidarSensor data. 
- Parameters
 - 
  
    | [in] | _topicName | Name 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] | _topicList | Message 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()
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] | _info | Current simulation information, such as time.  | 
    | [in] | _ecm | Mutable 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] | _value | Boolean value for displaying non hitting rays  | 
  
   
 
 
◆ UpdateSize()
      
        
          | Q_INVOKABLE void UpdateSize  | 
          ( | 
          int  | 
          _size | ) | 
           | 
        
      
 
Set lidar visualization size. 
- Parameters
 - 
  
    | [in] | _size | Size of lidar visualization  | 
  
   
 
 
◆ UpdateType()
      
        
          | Q_INVOKABLE void UpdateType  | 
          ( | 
          int  | 
          _type | ) | 
           | 
        
      
 
Set visual type of LidarVisual. 
- Parameters
 - 
  
    | [in] | _type | Index of selected visual type  | 
  
   
 
 
◆ maxRange
◆ minRange
◆ topicList
The documentation for this class was generated from the following file: