VisualizeLidar.hh
Go to the documentation of this file.
50 )
57 )
64 )
Q_INVOKABLE QStringList TopicList() const
Get the topic list as a string.
bool eventFilter(QObject *_obj, QEvent *_event) override
Q_INVOKABLE void SetTopicList(const QStringList &_topicList)
Set the topic list from a string, for example 'ignition.msgs.StringMsg'.
STL namespace.
Q_INVOKABLE void DisplayVisual(bool _value)
Set whether to display the lidar visual.
QStringList topicList
Topic list.
Definition: VisualizeLidar.hh:50
Q_INVOKABLE void OnTopic(const QString &_topicName)
Set topic to subscribe for LidarSensor data.
The EntityComponentManager constructs, deletes, and returns components and entities. A component can be of any class which inherits from components::BaseComponent.
Definition: EntityComponentManager.hh:66
Q_INVOKABLE QString MaxRange() const
Get the maximum range of the lidar sensor (in metres).
Q_INVOKABLE void UpdateType(int _type)
Set visual type of LidarVisual.
Q_INVOKABLE void UpdateSize(int _size)
Set lidar visualization size.
QString minRange
Min Range.
Definition: VisualizeLidar.hh:57
Q_INVOKABLE QString MinRange() const
Get the minimum range of the lidar sensor (in metres).
Q_INVOKABLE void UpdateNonHitting(bool _value)
Set whether to display non-hitting rays.
void Update(const UpdateInfo &, EntityComponentManager &_ecm) override
Update callback called every time the system is stepped. This is called at an Ignition transport thre...
void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override
This library is part of the Ignition Robotics project.
void OnScan(const msgs::LaserScan &_msg)
Callback function to get data from the message.
QString maxRange
Max Range.
Definition: VisualizeLidar.hh:64