Skip to content

ThrusterPlugin

class gazebo::ThrusterPlugin

class gazebo::ThrusterPlugin
  : public ModelPlugin

Class for the thruster plugin.

Summary
Members Descriptions
publicThrusterPlugin() Constructor.
public virtual~ThrusterPlugin() Destructor.
public virtual voidLoad(physics::ModelPtr _model,sdf::ElementPtr _sdf)
public virtual voidInit()
public virtual voidReset() Custom plugin reset behavior.
public voidUpdate(const common::UpdateInfo & _info) Update the simulation state.
protected std::shared_ptr<Dynamics>thrusterDynamics Thruster dynamic model.
protected std::shared_ptr<ConversionFunction>conversionFunction Thruster conversion function.
protected event::ConnectionPtrupdateConnection Update event.
protected physics::LinkPtrthrusterLink Pointer to the thruster link.
protected transport::NodePtrnode Gazebo node.
protected transport::SubscriberPtrcommandSubscriber Subscriber to the reference signal topic.
protected transport::PublisherPtrthrustTopicPublisher Publisher to the output thrust topic.
protected doubleinputCommand Input command, typically desired angular velocity of the rotor.
protected doublethrustForce Latest thrust force in [N].
protected common::TimethrustForceStamp Time stamp of latest thrust force.
protected physics::JointPtrjoint Optional: The rotor joint, used for visualization.
protected doubleclampMin : Optional: Commands less than this value will be clamped.
protected doubleclampMax : Optional: Commands greater than this value will be clamped.
protected doublethrustMin : Optional: Minimum thrust force output
protected doublethrustMax : Optional: Maximum thrust force output
protected intthrusterID Thruster ID, used to generated topic names automatically.
protected std::stringtopicPrefix Thruster topics prefix.
protected doublegain : Optional: Gain factor: Desired angular velocity = command * gain
protected boolisOn Optional: Flag to indicate if the thruster is turned on or off.
protected doublethrustEfficiency Optional: Output thrust efficiency factor of the thruster.
protected doublepropellerEfficiency Optional: Propeller angular velocity efficiency term.
protected ignition::math::Vector3dthrusterAxis The axis about which the thruster rotates.
protected voidUpdateInput(ConstDoublePtr& _msg) Callback for the input topic subscriber.
Members
publicThrusterPlugin()

Constructor.

public virtual~ThrusterPlugin()

Destructor.

public virtual voidLoad(physics::ModelPtr _model,sdf::ElementPtr _sdf)
public virtual voidInit()
public virtual voidReset()

Custom plugin reset behavior.

public voidUpdate(const common::UpdateInfo & _info)

Update the simulation state.

Parameters
  • _info Information used in the update event.
protected std::shared_ptr<Dynamics>thrusterDynamics

Thruster dynamic model.

protected std::shared_ptr<ConversionFunction>conversionFunction

Thruster conversion function.

protected event::ConnectionPtrupdateConnection

Update event.

Pointer to the thruster link.

protected transport::NodePtrnode

Gazebo node.

protected transport::SubscriberPtrcommandSubscriber

Subscriber to the reference signal topic.

protected transport::PublisherPtrthrustTopicPublisher

Publisher to the output thrust topic.

protected doubleinputCommand

Input command, typically desired angular velocity of the rotor.

protected doublethrustForce

Latest thrust force in [N].

protected common::TimethrustForceStamp

Time stamp of latest thrust force.

protected physics::JointPtrjoint

Optional: The rotor joint, used for visualization.

protected doubleclampMin
Optional: Commands less than this value will be clamped.
protected doubleclampMax
Optional: Commands greater than this value will be clamped.
protected doublethrustMin
Optional: Minimum thrust force output
protected doublethrustMax
Optional: Maximum thrust force output
protected intthrusterID

Thruster ID, used to generated topic names automatically.

protected std::stringtopicPrefix

Thruster topics prefix.

protected doublegain
Optional: Gain factor: Desired angular velocity = command * gain
protected boolisOn

Optional: Flag to indicate if the thruster is turned on or off.

protected doublethrustEfficiency

Optional: Output thrust efficiency factor of the thruster.

protected doublepropellerEfficiency

Optional: Propeller angular velocity efficiency term.

protected ignition::math::Vector3dthrusterAxis

The axis about which the thruster rotates.

protected voidUpdateInput(ConstDoublePtr& _msg)

Callback for the input topic subscriber.