A system that monitors the kinetic energy of a link in a model and publishes when there is a lost of kinetic energy during a timestep that surpasses a specific threshold. This system can be used to detect when a model could be damaged. More...
#include <KineticEnergyMonitor.hh>
Public Member Functions | |
KineticEnergyMonitor () | |
Constructor. More... | |
~KineticEnergyMonitor () final | |
Destructor. More... | |
void | Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) final |
Configure the system. More... | |
void | PostUpdate (const UpdateInfo &_info, const EntityComponentManager &_ecm) final |
Public Member Functions inherited from System | |
System ()=default | |
Constructor. More... | |
virtual | ~System ()=default |
Destructor. More... | |
Detailed Description
A system that monitors the kinetic energy of a link in a model and publishes when there is a lost of kinetic energy during a timestep that surpasses a specific threshold. This system can be used to detect when a model could be damaged.
System Parameters
<link_name>
: Name of the link to monitor. This name must match a name of link within the model.
<kinetic_energy_threshold>
: Threshold, in Joule (J), after which a message is generated on <topic>
with the kinetic energy value that surpassed the threshold.
<topic>
: Custom topic that this system will publish to when kinetic energy surpasses the threshold. This element if optional, and the default value is /model/{name_of_model}/kinetic_energy
.
Example Usage
<model name="sphere"> <pose>0 0 5 0 0 0</pose> <link name="sphere_link"> <inertial> <inertia> <ixx>3</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>3</iyy> <iyz>0</iyz> <izz>3</izz> </inertia> <mass>3.0</mass> </inertial> <collision name="sphere_collision"> <geometry> <sphere> <radius>0.5</radius> </sphere> </geometry> </collision> <visual name="sphere_visual"> <geometry> <sphere> <radius>0.5</radius> </sphere> </geometry> <material> <ambient>0 0 1 1</ambient> <diffuse>0 0 1 1</diffuse> <specular>0 0 1 1</specular> </material> </visual> </link> <plugin filename="ignition-gazebo-kinetic-energy-monitor-system" name="gz::sim::systems::KineticEnergyMonitor"> <base_link_name>sphere_link</base_link_name> <kinetic_energy_threshold>100</kinetic_energy_threshold> </plugin> </model>
Constructor & Destructor Documentation
◆ KineticEnergyMonitor()
Constructor.
◆ ~KineticEnergyMonitor()
|
final |
Destructor.
Member Function Documentation
◆ Configure()
|
finalvirtual |
Configure the system.
- Parameters
-
[in] _entity The entity this plugin is attached to. [in] _sdf The SDF Element associated with this system plugin. [in] _ecm The EntityComponentManager of the given simulation instance. [in] _eventMgr The EventManager of the given simulation instance.
Implements ISystemConfigure.
◆ PostUpdate()
|
finalvirtual |
Implements ISystemPostUpdate.
The documentation for this class was generated from the following file: