Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::LiftDragPlugin Class Reference

A plugin that simulates lift and drag. More...

#include <liftdrag_plugin.h>

Inheritance diagram for gazebo::LiftDragPlugin:
Inheritance graph
[legend]

Public Member Functions

 LiftDragPlugin ()
 Constructor. More...
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
 ~LiftDragPlugin ()
 Destructor. More...
 

Protected Member Functions

virtual void OnUpdate ()
 Callback for World Update events. More...
 

Protected Attributes

double alpha
 angle of attack More...
 
double alpha0
 initial angle of attack More...
 
double alphaStall
 angle of attach when airfoil stalls More...
 
double area
 effective planeform surface area More...
 
double cda
 Coefficient of Drag / alpha slope. Drag = C_D * q * S where q (dynamic pressure) = 0.5 * rho * v^2. More...
 
double cdaStall
 Cd-alpha rate after stall. More...
 
double cla
 Coefficient of Lift / alpha slope. Lift = C_L * q * S where q (dynamic pressure) = 0.5 * rho * v^2. More...
 
double claStall
 Cl-alpha rate after stall. More...
 
double cma
 Coefficient of Moment / alpha slope. Moment = C_M * q * S where q (dynamic pressure) = 0.5 * rho * v^2. More...
 
double cmaStall
 Cm-alpha rate after stall. More...
 
physics::JointPtr controlJoint
 Pointer to a joint that actuates a control surface for this lifting body. More...
 
double controlJointRadToCL
 how much to change CL per radian of control surface joint value. More...
 
ignition::math::Vector3d cp
 center of pressure in link local coordinates More...
 
ignition::math::Vector3d forward
 Normally, this is taken as a direction parallel to the chord of the airfoil in zero angle of attack forward flight. More...
 
physics::LinkPtr link
 Pointer to link currently targeted by mud joint. More...
 
physics::ModelPtr model
 Pointer to model containing plugin. More...
 
physics::PhysicsEnginePtr physics
 Pointer to physics engine. More...
 
bool radialSymmetry
 if the shape is aerodynamically radially symmetric about the forward direction. Defaults to false for wing shapes. If set to true, the upward direction is determined by the angle of attack. More...
 
double rho
 air density at 25 deg C it's about 1.1839 kg/m^3 At 20 °C and 101.325 kPa, dry air has a density of 1.2041 kg/m3. More...
 
sdf::ElementPtr sdf
 SDF for this plugin;. More...
 
double sweep
 angle of sweep More...
 
event::ConnectionPtr updateConnection
 Connection to World Update events. More...
 
ignition::math::Vector3d upward
 A vector in the lift/drag plane, perpendicular to the forward vector. Inflow velocity orthogonal to forward and upward vectors is considered flow in the wing sweep direction. More...
 
double velocityStall
 : : make a stall velocity curve More...
 
ignition::math::Vector3d velSmooth
 Smoothed velocity. More...
 
physics::WorldPtr world
 Pointer to world. More...
 

Detailed Description

A plugin that simulates lift and drag.

Definition at line 30 of file liftdrag_plugin.h.

Constructor & Destructor Documentation

◆ LiftDragPlugin()

LiftDragPlugin::LiftDragPlugin ( )

Constructor.

: what's flat plate drag?

how much to change CL per every radian of the control joint value

Definition at line 33 of file liftdrag_plugin.cpp.

◆ ~LiftDragPlugin()

LiftDragPlugin::~LiftDragPlugin ( )

Destructor.

Definition at line 59 of file liftdrag_plugin.cpp.

Member Function Documentation

◆ Load()

void LiftDragPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
virtual

Definition at line 64 of file liftdrag_plugin.cpp.

◆ OnUpdate()

void LiftDragPlugin::OnUpdate ( )
protectedvirtual

Callback for World Update events.

: also change cm and cd

: implement cm for now, reset cm to zero, as cm needs testing

Definition at line 161 of file liftdrag_plugin.cpp.

Member Data Documentation

◆ alpha

double gazebo::LiftDragPlugin::alpha
protected

angle of attack

Definition at line 107 of file liftdrag_plugin.h.

◆ alpha0

double gazebo::LiftDragPlugin::alpha0
protected

initial angle of attack

Definition at line 104 of file liftdrag_plugin.h.

◆ alphaStall

double gazebo::LiftDragPlugin::alphaStall
protected

angle of attach when airfoil stalls

Definition at line 72 of file liftdrag_plugin.h.

◆ area

double gazebo::LiftDragPlugin::area
protected

effective planeform surface area

Definition at line 98 of file liftdrag_plugin.h.

◆ cda

double gazebo::LiftDragPlugin::cda
protected

Coefficient of Drag / alpha slope. Drag = C_D * q * S where q (dynamic pressure) = 0.5 * rho * v^2.

Definition at line 64 of file liftdrag_plugin.h.

◆ cdaStall

double gazebo::LiftDragPlugin::cdaStall
protected

Cd-alpha rate after stall.

Definition at line 78 of file liftdrag_plugin.h.

◆ cla

double gazebo::LiftDragPlugin::cla
protected

Coefficient of Lift / alpha slope. Lift = C_L * q * S where q (dynamic pressure) = 0.5 * rho * v^2.

Definition at line 59 of file liftdrag_plugin.h.

◆ claStall

double gazebo::LiftDragPlugin::claStall
protected

Cl-alpha rate after stall.

Definition at line 75 of file liftdrag_plugin.h.

◆ cma

double gazebo::LiftDragPlugin::cma
protected

Coefficient of Moment / alpha slope. Moment = C_M * q * S where q (dynamic pressure) = 0.5 * rho * v^2.

Definition at line 69 of file liftdrag_plugin.h.

◆ cmaStall

double gazebo::LiftDragPlugin::cmaStall
protected

Cm-alpha rate after stall.

Definition at line 81 of file liftdrag_plugin.h.

◆ controlJoint

physics::JointPtr gazebo::LiftDragPlugin::controlJoint
protected

Pointer to a joint that actuates a control surface for this lifting body.

Definition at line 129 of file liftdrag_plugin.h.

◆ controlJointRadToCL

double gazebo::LiftDragPlugin::controlJointRadToCL
protected

how much to change CL per radian of control surface joint value.

Definition at line 133 of file liftdrag_plugin.h.

◆ cp

ignition::math::Vector3d gazebo::LiftDragPlugin::cp
protected

center of pressure in link local coordinates

Definition at line 110 of file liftdrag_plugin.h.

◆ forward

ignition::math::Vector3d gazebo::LiftDragPlugin::forward
protected

Normally, this is taken as a direction parallel to the chord of the airfoil in zero angle of attack forward flight.

Definition at line 114 of file liftdrag_plugin.h.

◆ link

physics::LinkPtr gazebo::LiftDragPlugin::link
protected

Pointer to link currently targeted by mud joint.

Definition at line 125 of file liftdrag_plugin.h.

◆ model

physics::ModelPtr gazebo::LiftDragPlugin::model
protected

Pointer to model containing plugin.

Definition at line 54 of file liftdrag_plugin.h.

◆ physics

physics::PhysicsEnginePtr gazebo::LiftDragPlugin::physics
protected

Pointer to physics engine.

Definition at line 51 of file liftdrag_plugin.h.

◆ radialSymmetry

bool gazebo::LiftDragPlugin::radialSymmetry
protected

if the shape is aerodynamically radially symmetric about the forward direction. Defaults to false for wing shapes. If set to true, the upward direction is determined by the angle of attack.

Definition at line 95 of file liftdrag_plugin.h.

◆ rho

double gazebo::LiftDragPlugin::rho
protected

air density at 25 deg C it's about 1.1839 kg/m^3 At 20 °C and 101.325 kPa, dry air has a density of 1.2041 kg/m3.

Definition at line 89 of file liftdrag_plugin.h.

◆ sdf

sdf::ElementPtr gazebo::LiftDragPlugin::sdf
protected

SDF for this plugin;.

Definition at line 136 of file liftdrag_plugin.h.

◆ sweep

double gazebo::LiftDragPlugin::sweep
protected

angle of sweep

Definition at line 101 of file liftdrag_plugin.h.

◆ updateConnection

event::ConnectionPtr gazebo::LiftDragPlugin::updateConnection
protected

Connection to World Update events.

Definition at line 45 of file liftdrag_plugin.h.

◆ upward

ignition::math::Vector3d gazebo::LiftDragPlugin::upward
protected

A vector in the lift/drag plane, perpendicular to the forward vector. Inflow velocity orthogonal to forward and upward vectors is considered flow in the wing sweep direction.

Definition at line 119 of file liftdrag_plugin.h.

◆ velocityStall

double gazebo::LiftDragPlugin::velocityStall
protected

: : make a stall velocity curve

Definition at line 84 of file liftdrag_plugin.h.

◆ velSmooth

ignition::math::Vector3d gazebo::LiftDragPlugin::velSmooth
protected

Smoothed velocity.

Definition at line 122 of file liftdrag_plugin.h.

◆ world

physics::WorldPtr gazebo::LiftDragPlugin::world
protected

Pointer to world.

Definition at line 48 of file liftdrag_plugin.h.


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


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:04