LiftDragPlugin Class Reference

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

#include <LiftDragPlugin.hh>

Inherits ModelPlugin.

Public Types

typedef boost::shared_ptr< ModelPluginTPtr
 plugin pointer type definition More...
 

Public Member Functions

 LiftDragPlugin ()
 Constructor. More...
 
 ~LiftDragPlugin ()
 Destructor. More...
 
std::string GetFilename () const
 Get the name of the handler. More...
 
std::string GetHandle () const
 Get the short name of the handler. More...
 
PluginType GetType () const
 Returns the type of the plugin. More...
 
virtual void Init ()
 Override this method for custom plugin initialization behavior. More...
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 Load function. More...
 
virtual void Reset ()
 Override this method for custom plugin reset behavior. More...
 

Static Public Member Functions

static TPtr Create (const std::string &_filename, const std::string &_name)
 a class method that creates a plugin from a file name. 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. More...
 
double cdaStall
 Cd-alpha rate after stall. More...
 
double cla
 Coefficient of Lift / alpha slope. More...
 
double claStall
 Cl-alpha rate after stall. More...
 
double cma
 Coefficient of Moment / alpha slope. 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...
 
math::Vector3 cp
 center of pressure in link local coordinates More...
 
std::string filename
 Path to the shared library file. More...
 
math::Vector3 forward
 Normally, this is taken as a direction parallel to the chord of the airfoil in zero angle of attack forward flight. More...
 
std::string handleName
 Short name. 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. 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...
 
PluginType type
 Type of plugin. More...
 
event::ConnectionPtr updateConnection
 Connection to World Update events. More...
 
math::Vector3 upward
 A vector in the lift/drag plane, perpendicular to the forward vector. More...
 
double velocityStall
 : : make a stall velocity curve More...
 
math::Vector3 velSmooth
 Smoothed velocity. More...
 
physics::WorldPtr world
 Pointer to world. More...
 

Detailed Description

A plugin that simulates lift and drag.

Member Typedef Documentation

§ TPtr

typedef boost::shared_ptr<ModelPlugin > TPtr
inherited

plugin pointer type definition

Constructor & Destructor Documentation

§ LiftDragPlugin()

Constructor.

§ ~LiftDragPlugin()

Destructor.

Member Function Documentation

§ Create()

static TPtr Create ( const std::string &  _filename,
const std::string &  _name 
)
inlinestaticinherited

a class method that creates a plugin from a file name.

It locates the shared library and loads it dynamically.

Parameters
[in]_filenamethe path to the shared library.
[in]_nameshort name of the plugin
Returns
Shared Pointer to this class type

References PluginT< T >::filename, gzerr, and SingletonT< SystemPaths >::Instance().

§ GetFilename()

std::string GetFilename ( ) const
inlineinherited

Get the name of the handler.

References PluginT< T >::filename.

§ GetHandle()

std::string GetHandle ( ) const
inlineinherited

Get the short name of the handler.

References PluginT< T >::handleName.

§ GetType()

PluginType GetType ( ) const
inlineinherited

Returns the type of the plugin.

Returns
type of the plugin

References PluginT< T >::type.

§ Init()

virtual void Init ( )
inlinevirtualinherited

Override this method for custom plugin initialization behavior.

Reimplemented in BuoyancyPlugin, HarnessPlugin, FollowerPlugin, VehiclePlugin, LinearBatteryPlugin, MudPlugin, CartDemoPlugin, SphereAtlasDemoPlugin, and DiffDrivePlugin.

§ Load()

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

Load function.

Called when a Plugin is first created, and after the World has been loaded. This function should not be blocking.

Parameters
[in]_modelPointer to the Model
[in]_sdfPointer to the SDF element of the plugin.

Implements ModelPlugin.

§ OnUpdate()

virtual void OnUpdate ( )
protectedvirtual

Callback for World Update events.

§ Reset()

virtual void Reset ( )
inlinevirtualinherited

Override this method for custom plugin reset behavior.

Reimplemented in RandomVelocityPlugin, ElevatorPlugin, FollowerPlugin, LinearBatteryPlugin, InitialVelocityPlugin, and SphereAtlasDemoPlugin.

Member Data Documentation

§ alpha

double alpha
protected

angle of attack

§ alpha0

double alpha0
protected

initial angle of attack

§ alphaStall

double alphaStall
protected

angle of attach when airfoil stalls

§ area

double area
protected

effective planeform surface area

§ cda

double cda
protected

Coefficient of Drag / alpha slope.

Drag = C_D * q * S where q (dynamic pressure) = 0.5 * rho * v^2

§ cdaStall

double cdaStall
protected

Cd-alpha rate after stall.

§ cla

double cla
protected

Coefficient of Lift / alpha slope.

Lift = C_L * q * S where q (dynamic pressure) = 0.5 * rho * v^2

§ claStall

double claStall
protected

Cl-alpha rate after stall.

§ cma

double cma
protected

Coefficient of Moment / alpha slope.

Moment = C_M * q * S where q (dynamic pressure) = 0.5 * rho * v^2

§ cmaStall

double cmaStall
protected

Cm-alpha rate after stall.

§ controlJoint

physics::JointPtr controlJoint
protected

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

§ controlJointRadToCL

double controlJointRadToCL
protected

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

§ cp

math::Vector3 cp
protected

center of pressure in link local coordinates

§ filename

std::string filename
protectedinherited

Path to the shared library file.

§ forward

math::Vector3 forward
protected

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

§ handleName

std::string handleName
protectedinherited

Short name.

§ link

physics::LinkPtr link
protected

Pointer to link currently targeted by mud joint.

§ model

physics::ModelPtr model
protected

Pointer to model containing plugin.

§ physics

physics::PhysicsEnginePtr physics
protected

Pointer to physics engine.

§ radialSymmetry

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

§ rho

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

§ sdf

sdf::ElementPtr sdf
protected

SDF for this plugin;.

§ sweep

double sweep
protected

angle of sweep

§ type

PluginType type
protectedinherited

Type of plugin.

§ updateConnection

event::ConnectionPtr updateConnection
protected

Connection to World Update events.

§ upward

math::Vector3 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.

§ velocityStall

double velocityStall
protected

: : make a stall velocity curve

§ velSmooth

math::Vector3 velSmooth
protected

Smoothed velocity.

§ world

physics::WorldPtr world
protected

Pointer to world.


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