Ignition Gazebo

API Reference

6.9.0

Plot the trajectory of an entity into the 3D scene. More...

#include <Plot3D.hh>

Signals

void ColorChanged ()
 Notify that the color has changed. More...
 
void LockedChanged ()
 Notify that locked has changed. More...
 
void MaxPointsChanged ()
 Notify that the maximum points has changed. More...
 
void MinDistanceChanged ()
 Notify that the minimum distance has changed. More...
 
void OffsetChanged ()
 Notify that the offset has changed. More...
 
void TargetEntityChanged ()
 Notify that entity has changed. More...
 
void TargetNameChanged ()
 Notify that target name has changed. More...
 

Public Member Functions

 Plot3D ()
 Constructor. More...
 
 ~Plot3D () override
 Destructor. More...
 
Q_INVOKABLE QVector3D Color () const
 Get the color of the plot. More...
 
void LoadConfig (const tinyxml2::XMLElement *_pluginElem) override
 
Q_INVOKABLE bool Locked () const
 Get whether the plugin is currently locked on a target. More...
 
Q_INVOKABLE int MaxPoints () const
 Get the maximum number of points. More...
 
Q_INVOKABLE double MinDistance () const
 Get the minimum distance between points. More...
 
Q_INVOKABLE QVector3D Offset () const
 Get the offset in the target's frame. More...
 
Q_INVOKABLE void SetColor (const QVector3D &_color)
 Set the color of the plot. More...
 
Q_INVOKABLE void SetLocked (bool _locked)
 Set whether the plugin is currently locked on a target. More...
 
Q_INVOKABLE void SetMaxPoints (int _maxPoints)
 Set the maximum number of points. If the plot has more than this number, older points start being removed. More...
 
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. More...
 
Q_INVOKABLE void SetOffset (const QVector3D &_offset)
 Set the offset. More...
 
Q_INVOKABLE void SetTargetEntity (Entity _entity)
 Set the target currently controlled. More...
 
Q_INVOKABLE void SetTargetName (const QString &_name)
 Set the name of target currently controlled. More...
 
Q_INVOKABLE Entity TargetEntity () const
 Get the target currently controlled. More...
 
Q_INVOKABLE QString TargetName () const
 Get the name of target currently controlled. More...
 
void Update (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 Update callback called every time the system is stepped. This is called at an Ignition transport thread, so any interaction with Qt should be done through signals and slots. More...
 

Protected Member Functions

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

Properties

QVector3D color
 Plot line color. More...
 
bool locked
 Whether the plugin is locked on an entity. More...
 
int maxPoints
 Maximum number of total points on the plot. More...
 
double minDistance
 Minimum distance between plot points. More...
 
QVector3D offset
 XYZ offset to the entity's origin to plot. More...
 
Entity targetEntity
 Target entity. More...
 
QString targetName
 Target entity scoped name. More...
 

Detailed Description

Plot the trajectory of an entity into the 3D scene.

This plugin can be instantiated multiple times to plot various entities.

The plugin is automatically attached to the currently selected entity, unless it is locked on an entity.

Configuration

  • <entity_name> (optional): Plot the given entity at startup. Accepts names scoped with ::, for example my_model::my_link. If not provided, the plugin starts not attached to any entity, and will attach to the next selected entity.
  • <color> (optional): RGB color of line, defaults to blue.
  • <offset> (optional): XYZ offset from the entity's origin to plot from, expressed in the entity's frame. Defaults to zero.
  • <minimum_distance> (optional): The minimum distance between points to plot. A new point will not be plotted until the entity has moved beyond this distance from the previous point. Defaults to 0.05 m.
  • <maximum_points> (optional): Maximum number of points on the plot. After this number is reached, the older points start being deleted. Defaults to 1000.

Constructor & Destructor Documentation

◆ Plot3D()

Plot3D ( )

Constructor.

◆ ~Plot3D()

~Plot3D ( )
override

Destructor.

Member Function Documentation

◆ Color()

Q_INVOKABLE QVector3D Color ( ) const

Get the color of the plot.

Returns
The current color.

◆ ColorChanged

void ColorChanged ( )
signal

Notify that the color has changed.

◆ eventFilter()

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

◆ LoadConfig()

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

◆ Locked()

Q_INVOKABLE bool Locked ( ) const

Get whether the plugin is currently locked on a target.

Returns
True for locked

◆ LockedChanged

void LockedChanged ( )
signal

Notify that locked has changed.

◆ MaxPoints()

Q_INVOKABLE int MaxPoints ( ) const

Get the maximum number of points.

Returns
The current maximum points.

◆ MaxPointsChanged

void MaxPointsChanged ( )
signal

Notify that the maximum points has changed.

◆ MinDistance()

Q_INVOKABLE double MinDistance ( ) const

Get the minimum distance between points.

Returns
The current minimum distance.

◆ MinDistanceChanged

void MinDistanceChanged ( )
signal

Notify that the minimum distance has changed.

◆ Offset()

Q_INVOKABLE QVector3D Offset ( ) const

Get the offset in the target's frame.

Returns
The current offset.

◆ OffsetChanged

void OffsetChanged ( )
signal

Notify that the offset has changed.

◆ SetColor()

Q_INVOKABLE void SetColor ( const QVector3D &  _color)

Set the color of the plot.

Parameters
[in]_colorNew color.

◆ SetLocked()

Q_INVOKABLE void SetLocked ( bool  _locked)

Set whether the plugin is currently locked on a target.

Parameters
[in]_lockedTrue for locked.

◆ SetMaxPoints()

Q_INVOKABLE void SetMaxPoints ( int  _maxPoints)

Set the maximum number of points. If the plot has more than this number, older points start being removed.

Parameters
[in]_maxPointsMaximum number of points.

◆ SetMinDistance()

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.

Parameters
[in]_minDistanceNew distance.

◆ SetOffset()

Q_INVOKABLE void SetOffset ( const QVector3D &  _offset)

Set the offset.

Parameters
[in]_offsetThe offset in the target's frame

◆ SetTargetEntity()

Q_INVOKABLE void SetTargetEntity ( Entity  _entity)

Set the target currently controlled.

Parameters
[in]_entityTarget entity ID.

◆ SetTargetName()

Q_INVOKABLE void SetTargetName ( const QString &  _name)

Set the name of target currently controlled.

Parameters
[in]_nameTargetName, such as 'world' or 'target'.

◆ TargetEntity()

Q_INVOKABLE Entity TargetEntity ( ) const

Get the target currently controlled.

Returns
Target entity ID.

◆ TargetEntityChanged

void TargetEntityChanged ( )
signal

Notify that entity has changed.

◆ TargetName()

Q_INVOKABLE QString TargetName ( ) const

Get the name of target currently controlled.

Returns
TargetName, such as 'world' or 'target'

◆ TargetNameChanged

void TargetNameChanged ( )
signal

Notify that target name has changed.

◆ Update()

void Update ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Update callback called every time the system is stepped. This is called at an Ignition 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.

Property Documentation

◆ color

QVector3D color
readwrite

Plot line color.

◆ locked

bool locked
readwrite

Whether the plugin is locked on an entity.

◆ maxPoints

int maxPoints
readwrite

Maximum number of total points on the plot.

◆ minDistance

double minDistance
readwrite

Minimum distance between plot points.

◆ offset

QVector3D offset
readwrite

XYZ offset to the entity's origin to plot.

◆ targetEntity

Entity targetEntity
readwrite

Target entity.

◆ targetName

QString targetName
readwrite

Target entity scoped name.


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