Plot3D.hh
Go to the documentation of this file.
72 )
80 )
88 )
96 )
104 )
112 )
120 )
Q_INVOKABLE int MaxPoints() const
Get the maximum number of points.
Q_INVOKABLE bool Locked() const
Get whether the plugin is currently locked on a target.
Q_INVOKABLE QString TargetName() const
Get the name of target currently controlled.
int maxPoints
Maximum number of total points on the plot.
Definition: Plot3D.hh:120
Q_INVOKABLE void SetOffset(const QVector3D &_offset)
Set the offset.
STL namespace.
Q_INVOKABLE void SetMinDistance(double _minDistance)
Set the minimum distance between points. If the target moved less than this distance, the latest position won't be plotted.
void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override
Information passed to systems on the update callback.
Definition: Types.hh:36
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...
Entity targetEntity
Target entity.
Definition: Plot3D.hh:72
Q_INVOKABLE void SetColor(const QVector3D &_color)
Set the color of the plot.
The EntityComponentManager constructs, deletes, and returns components and entities. A component can be of any class which inherits from components::BaseComponent.
Definition: EntityComponentManager.hh:65
bool eventFilter(QObject *_obj, QEvent *_event) override
Q_INVOKABLE void SetTargetName(const QString &_name)
Set the name of target currently controlled.
Q_INVOKABLE void SetTargetEntity(Entity _entity)
Set the target currently controlled.
Q_INVOKABLE double MinDistance() const
Get the minimum distance between points.
Q_INVOKABLE QVector3D Offset() const
Get the offset in the target's frame.
QString targetName
Target entity scoped name.
Definition: Plot3D.hh:80
bool locked
Whether the plugin is locked on an entity.
Definition: Plot3D.hh:88
Q_INVOKABLE void SetLocked(bool _locked)
Set whether the plugin is currently locked on a target.
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...
QVector3D offset
XYZ offset to the entity's origin to plot.
Definition: Plot3D.hh:96
This library is part of the Ignition Robotics project.
uint64_t Entity
An Entity identifies a single object in simulation such as a model, link, or light. At its core, an Entity is just an identifier.
Definition: Entity.hh:59
Q_INVOKABLE Entity TargetEntity() const
Get the target currently controlled.
double minDistance
Minimum distance between plot points.
Definition: Plot3D.hh:112