Ignition Gazebo

API Reference

6.9.0

Physics data plotting handler that keeps track of the registered components, update them and update the plot. More...

#include <Plotting.hh>

Public Slots

std::string ComponentName (const uint64_t &_typeId)
 Get Component Name based on its type Id. More...
 
void RegisterChartToComponent (uint64_t _entity, uint64_t _typeId, std::string _type, std::string _attribute, int _chart)
 Add a chart to a specefic component attribute. More...
 
void UnRegisterChartFromComponent (uint64_t _entity, uint64_t _typeId, std::string _attribute, int _chart)
 Remove a chart from a specefic component attribute. More...
 

Public Member Functions

 Plotting ()
 Constructor. More...
 
 ~Plotting ()
 Destructor. More...
 
void LoadConfig (const tinyxml2::XMLElement *) override
 
void SetData (std::string _Id, const ignition::math::Vector3d &_vector)
 Set the Component data of given id to the given vector. More...
 
void SetData (std::string _Id, const msgs::Light &_light)
 Set the Component data of given id to the given light. More...
 
void SetData (std::string _Id, const ignition::math::Pose3d &_pose)
 Set the Component data of given id to the given pose. More...
 
void SetData (std::string _Id, const math::SphericalCoordinates &_sc)
 Set the Component data of given id to the given spherical coordinates. More...
 
void SetData (std::string _Id, const sdf::Physics &_physics)
 Set the Component data of given id to the given physics properties. More...
 
void SetData (std::string _Id, const double &_value)
 Set the Component data of given id to the given number. 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...
 

Detailed Description

Physics data plotting handler that keeps track of the registered components, update them and update the plot.

Constructor & Destructor Documentation

◆ Plotting()

Plotting ( )

Constructor.

◆ ~Plotting()

~Plotting ( )

Destructor.

Member Function Documentation

◆ ComponentName

std::string ComponentName ( const uint64_t &  _typeId)
slot

Get Component Name based on its type Id.

Parameters
[in]_typeIdtype Id of the component
Returns
Component name

◆ LoadConfig()

void LoadConfig ( const tinyxml2::XMLElement *  )
override

◆ RegisterChartToComponent

void RegisterChartToComponent ( uint64_t  _entity,
uint64_t  _typeId,
std::string  _type,
std::string  _attribute,
int  _chart 
)
slot

Add a chart to a specefic component attribute.

Parameters
[in]_entityentity id in the simulation
[in]_typeIdtype identifier unique to each component type
[in]_typeComponent Datatype ("Pose3d","Vector3d","double")
[in]_attributecomponent attribute to add the chart to it ex: x attribute in Pose3d Component will be "x"
[in]_chartchart ID to be registered

◆ SetData() [1/6]

void SetData ( std::string  _Id,
const ignition::math::Vector3d _vector 
)

Set the Component data of given id to the given vector.

Parameters
[in]_IdComponent Key of the components map
[in]_vectorVector Data to be set to the component

◆ SetData() [2/6]

void SetData ( std::string  _Id,
const msgs::Light _light 
)

Set the Component data of given id to the given light.

Parameters
[in]_IdComponent Key of the components map
[in]_lightVector Data to be set to the component

◆ SetData() [3/6]

void SetData ( std::string  _Id,
const ignition::math::Pose3d _pose 
)

Set the Component data of given id to the given pose.

Parameters
[in]_IdComponent Key of the components map
[in]_posePosition Data to be set to the component

◆ SetData() [4/6]

void SetData ( std::string  _Id,
const math::SphericalCoordinates _sc 
)

Set the Component data of given id to the given spherical coordinates.

Parameters
[in]_IdComponent Key of the components map
[in]_scData to be set to the component

◆ SetData() [5/6]

void SetData ( std::string  _Id,
const sdf::Physics &  _physics 
)

Set the Component data of given id to the given physics properties.

Parameters
[in]_IdComponent Key of the components map
[in]_valuephysics Data to be set to the component

◆ SetData() [6/6]

void SetData ( std::string  _Id,
const double &  _value 
)

Set the Component data of given id to the given number.

Parameters
[in]_IdComponent Key of the components map
[in]_valuedouble Data to be set to the component valid for types (double, float, int, bool)

◆ UnRegisterChartFromComponent

void UnRegisterChartFromComponent ( uint64_t  _entity,
uint64_t  _typeId,
std::string  _attribute,
int  _chart 
)
slot

Remove a chart from a specefic component attribute.

Parameters
[in]_entityentity id in the simulation
[in]_typeIdtype identifier unique to each component type
[in]_attributecomponent attribute to remove the chart from it ex: x attribute in Pose3d Component will be "x"
[in]_chartchart ID to be unregistered

◆ 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.


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