Gazebo Gazebo

API Reference

6.16.0
Thruster Class Reference

This plugin simulates a maritime thruster for boats and underwater vehicles. It uses the equations described in Fossen's "Guidance and Control of Ocean Vehicles" in page 246. This plugin takes in force in Newtons and applies it to the thruster. It also calculates the theoretical angular velocity of the blades and spins them accordingly. More...

#include <Thruster.hh>

Public Member Functions

 Thruster ()
 Constructor. More...
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &) override
 Documentation inherited. More...
 
void PostUpdate (const UpdateInfo &_info, const EntityComponentManager &_ecm) override
 Documentation inherited. More...
 
void PreUpdate (const ignition::gazebo::UpdateInfo &_info, ignition::gazebo::EntityComponentManager &_ecm) override
 Documentation inherited. More...
 
- Public Member Functions inherited from System
 System ()=default
 Constructor. More...
 
virtual ~System ()=default
 Destructor. More...
 

Detailed Description

This plugin simulates a maritime thruster for boats and underwater vehicles. It uses the equations described in Fossen's "Guidance and Control of Ocean Vehicles" in page 246. This plugin takes in force in Newtons and applies it to the thruster. It also calculates the theoretical angular velocity of the blades and spins them accordingly.

System Parameters

  • <namespace> - The namespace in which the robot exists. The plugin will listen on the topic /model/{namespace}/joint/{joint_name}/cmd_thrust or on {namespace}/{topic} if {topic} is set. [Optional]
  • <topic> - The topic for receiving thrust commands. [Optional]
  • <joint_name> - This is the joint in the model which corresponds to the propeller. [Required]
  • <fluid_density> - The fluid density of the liquid in which the thruster is operating in. [Optional, kg/m^3, defaults to 1000 kg/m^3]
  • <propeller_diameter> - The diameter of the propeller in meters. [Optional, m, defaults to 0.02m]
  • <thrust_coefficient> - This is the coefficient which relates the angular velocity to actual thrust. [Optional, no units, defaults to 1.0]

    omega = sqrt(thrust / (fluid_density * thrust_coefficient * propeller_diameter ^ 4))

    Where omega is the propeller's angular velocity in rad/s.

  • <velocity_control> - If true, use joint velocity commands to rotate the propeller. If false, use a PID controller to apply wrenches directly to the propeller link instead. [Optional, defaults to false].
  • <p_gain> - Proportional gain for joint PID controller. [Optional, no units, defaults to 0.1]
  • <i_gain> - Integral gain for joint PID controller. [Optional, no units, defaults to 0.0]
  • <d_gain> - Derivative gain for joint PID controller. [Optional, no units, defaults to 0.0]
  • <max_thrust_cmd> - Maximum thrust command. [Optional, defaults to 1000N]
  • <min_thrust_cmd> - Minimum thrust command. [Optional, defaults to -1000N]
  • <wake_fraction> - Relative speed reduction between the water at the propeller (Va) vs behind the vessel. [Optional, defults to 0.2] See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 95:
               Va = (1 - wake_fraction) * advance_speed
    
  • <alpha_1> - Constant given by the open water propeller diagram. Used in the calculation of the thrust coefficient (Kt). [Optional, defults to 1]
  • <alpha_2> - Constant given by the open water propeller diagram. Used in the calculation of the thrust coefficient (Kt). [Optional, defults to 0] See Thor I Fossen's "Guidance and Control of ocean vehicles" p. 95:

Kt = alpha_1 * alpha_2 * (Va/(propeller_revolution * propeller_diameter))

Example

An example configuration is installed with Gazebo. The example uses the LiftDrag plugin to apply steering controls. It also uses the thruster plugin to propell the craft and the buoyancy plugin for buoyant force. To run the example:

ign gazebo auv_controls.sdf

To control the rudder of the craft run the following:

ign topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos
-m ignition.msgs.Double -p 'data: -0.17'

To apply a thrust you may run the following command:

ign topic -t /model/tethys/joint/propeller_joint/cmd_thrust
-m ignition.msgs.Double -p 'data: -31'

The vehicle should move in a circle.

Constructor & Destructor Documentation

◆ Thruster()

Thruster ( )

Constructor.

Member Function Documentation

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager  
)
overridevirtual

Documentation inherited.

Implements ISystemConfigure.

◆ PostUpdate()

void PostUpdate ( const UpdateInfo _info,
const EntityComponentManager _ecm 
)
overridevirtual

Documentation inherited.

Implements ISystemPostUpdate.

◆ PreUpdate()

void PreUpdate ( const ignition::gazebo::UpdateInfo _info,
ignition::gazebo::EntityComponentManager _ecm 
)
overridevirtual

Documentation inherited.

Implements ISystemPreUpdate.


The documentation for this class was generated from the following file:
This library is part of the Gazebo project.