Gazebo Gazebo

API Reference

3.15.2
Plot3D.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2021 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef GZ_GAZEBO_GUI_3DPLOT_HH_
19 #define GZ_GAZEBO_GUI_3DPLOT_HH_
20 
21 #include <memory>
22 
23 #include <gz/sim/gui/GuiSystem.hh>
24 
25 #include "gz/gui/qt.h"
26 
27 namespace ignition
28 {
29 namespace gazebo
30 {
31 namespace gui
32 {
33  class Plot3DPrivate;
34 
63  {
64  Q_OBJECT
65 
67  Q_PROPERTY(
69  READ TargetEntity
70  WRITE SetTargetEntity
71  NOTIFY TargetEntityChanged
72  )
73 
74 
75  Q_PROPERTY(
76  QString targetName
77  READ TargetName
78  WRITE SetTargetName
79  NOTIFY TargetNameChanged
80  )
81 
83  Q_PROPERTY(
84  bool locked
85  READ Locked
86  WRITE SetLocked
87  NOTIFY LockedChanged
88  )
89 
91  Q_PROPERTY(
92  QVector3D offset
93  READ Offset
94  WRITE SetOffset
95  NOTIFY OffsetChanged
96  )
97 
99  Q_PROPERTY(
100  QVector3D color
101  READ Color
102  WRITE SetColor
103  NOTIFY ColorChanged
104  )
105 
107  Q_PROPERTY(
108  double minDistance
109  READ MinDistance
110  WRITE SetMinDistance
111  NOTIFY MinDistanceChanged
112  )
113 
115  Q_PROPERTY(
116  int maxPoints
117  READ MaxPoints
118  WRITE SetMaxPoints
119  NOTIFY MaxPointsChanged
120  )
121 
123  public: Plot3D();
124 
126  public: ~Plot3D() override;
127 
128  // Documentation inherited
129  public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override;
130 
131  // Documentation inherited
132  public: void Update(const UpdateInfo &_info,
133  EntityComponentManager &_ecm) override;
134 
137  public: Q_INVOKABLE Entity TargetEntity() const;
138 
141  public: Q_INVOKABLE void SetTargetEntity(Entity _entity);
142 
144  signals: void TargetEntityChanged();
145 
148  public: Q_INVOKABLE QString TargetName() const;
149 
152  public: Q_INVOKABLE void SetTargetName(const QString &_name);
153 
155  signals: void TargetNameChanged();
156 
159  public: Q_INVOKABLE bool Locked() const;
160 
163  public: Q_INVOKABLE void SetLocked(bool _locked);
164 
166  signals: void LockedChanged();
167 
170  public: Q_INVOKABLE QVector3D Offset() const;
171 
174  public: Q_INVOKABLE void SetOffset(const QVector3D &_offset);
175 
177  signals: void OffsetChanged();
178 
181  public: Q_INVOKABLE QVector3D Color() const;
182 
185  public: Q_INVOKABLE void SetColor(const QVector3D &_color);
186 
188  signals: void ColorChanged();
189 
192  public: Q_INVOKABLE double MinDistance() const;
193 
197  public: Q_INVOKABLE void SetMinDistance(double _minDistance);
198 
200  signals: void MinDistanceChanged();
201 
204  public: Q_INVOKABLE int MaxPoints() const;
205 
209  public: Q_INVOKABLE void SetMaxPoints(int _maxPoints);
210 
212  signals: void MaxPointsChanged();
213 
214  // Documentation inherited
215  protected: bool eventFilter(QObject *_obj, QEvent *_event) override;
216 
218  private: void ClearPlot();
219 
222  private: std::unique_ptr<Plot3DPrivate> dataPtr;
223  };
224 }
225 }
226 }
227 
228 #endif
Base class for a GUI System.
Definition: gz/sim/gui/GuiSystem.hh:44
int maxPoints
Maximum number of total points on the plot.
Definition: Plot3D.hh:120
Q_INVOKABLE void SetColor(const QVector3D &_color)
Set the color of the plot.
uint64_t Entity
An Entity identifies a single object in simulation such as a model, link, or light....
Definition: gz/sim/Entity.hh:59
This library is part of the Ignition Robotics project.
The EntityComponentManager constructs, deletes, and returns components and entities....
Definition: gz/sim/EntityComponentManager.hh:65
Q_INVOKABLE bool Locked() const
Get whether the plugin is currently locked on a target.
Q_INVOKABLE void SetOffset(const QVector3D &_offset)
Set the offset.
Plot the trajectory of an entity into the 3D scene.
Definition: Plot3D.hh:62
QVector3D color
Plot line color.
Definition: Plot3D.hh:104
Q_INVOKABLE void SetLocked(bool _locked)
Set whether the plugin is currently locked on a target.
void MaxPointsChanged()
Notify that the maximum points has changed.
Q_INVOKABLE void SetMinDistance(double _minDistance)
Set the minimum distance between points. If the target moved less than this distance,...
Q_INVOKABLE void SetTargetEntity(Entity _entity)
Set the target currently controlled.
void MinDistanceChanged()
Notify that the minimum distance has changed.
Information passed to systems on the update callback.
Definition: include/gz/sim/Types.hh:37
Q_INVOKABLE double MinDistance() const
Get the minimum distance between points.
Q_INVOKABLE Entity TargetEntity() const
Get the target currently controlled.
void TargetEntityChanged()
Notify that entity has changed.
void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override
Q_INVOKABLE int MaxPoints() const
Get the maximum number of points.
void ColorChanged()
Notify that the color has changed.
double minDistance
Minimum distance between plot points.
Definition: Plot3D.hh:112
Q_INVOKABLE QVector3D Offset() const
Get the offset in the target's frame.
Q_INVOKABLE QString TargetName() const
Get the name of target currently controlled.
QVector3D offset
XYZ offset to the entity's origin to plot.
Definition: Plot3D.hh:96
Entity targetEntity
Target entity.
Definition: Plot3D.hh:72
QString targetName
Target entity scoped name.
Definition: Plot3D.hh:80
bool locked
Whether the plugin is locked on an entity.
Definition: Plot3D.hh:88
bool eventFilter(QObject *_obj, QEvent *_event) override
void OffsetChanged()
Notify that the offset has changed.
void Update(const UpdateInfo &_info, EntityComponentManager &_ecm) override
Update callback called every time the system is stepped. This is called at an Ignition transport thre...
STL namespace.
void TargetNameChanged()
Notify that target name has changed.
Q_INVOKABLE void SetTargetName(const QString &_name)
Set the name of target currently controlled.
Q_INVOKABLE QVector3D Color() const
Get the color of the plot.
void LockedChanged()
Notify that locked has changed.
Q_INVOKABLE void SetMaxPoints(int _maxPoints)
Set the maximum number of points. If the plot has more than this number, older points start being rem...