A plugin that simulates lift and drag. More...
#include <LiftDragPlugin.hh>
Inherits ModelPlugin.
Public Types | |
typedef boost::shared_ptr < ModelPlugin > | TPtr |
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... | |
ignition::math::Vector3d | cp |
center of pressure in link local coordinates More... | |
std::string | filename |
Path to the shared library file. 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... | |
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... | |
ignition::math::Vector3d | upward |
A vector in the lift/drag plane, perpendicular to the forward vector. More... | |
double | velocityStall |
: : make a stall velocity curve More... | |
ignition::math::Vector3d | velSmooth |
Smoothed velocity. More... | |
physics::WorldPtr | world |
Pointer to world. More... | |
A plugin that simulates lift and drag.
|
inherited |
plugin pointer type definition
LiftDragPlugin | ( | ) |
Constructor.
~LiftDragPlugin | ( | ) |
Destructor.
|
inlinestaticinherited |
a class method that creates a plugin from a file name.
It locates the shared library and loads it dynamically.
[in] | _filename | the path to the shared library. |
[in] | _name | short name of the plugin |
References PluginT< T >::filename, gzerr, and SingletonT< SystemPaths >::Instance().
|
inlineinherited |
Get the name of the handler.
References PluginT< T >::filename.
|
inlineinherited |
Get the short name of the handler.
References PluginT< T >::handleName.
|
inlineinherited |
|
inlinevirtualinherited |
Override this method for custom plugin initialization behavior.
Reimplemented in BuoyancyPlugin, HarnessPlugin, FollowerPlugin, PlaneDemoPlugin, MudPlugin, CartDemoPlugin, VehiclePlugin, GimbalSmall2dPlugin, LinearBatteryPlugin, DiffDrivePlugin, and SphereAtlasDemoPlugin.
|
virtual |
Load function.
Called when a Plugin is first created, and after the World has been loaded. This function should not be blocking.
[in] | _model | Pointer to the Model |
[in] | _sdf | Pointer to the SDF element of the plugin. |
Implements ModelPlugin.
|
protectedvirtual |
Callback for World Update events.
|
inlinevirtualinherited |
Override this method for custom plugin reset behavior.
Reimplemented in RandomVelocityPlugin, ElevatorPlugin, FollowerPlugin, LinearBatteryPlugin, ActorPlugin, InitialVelocityPlugin, and SphereAtlasDemoPlugin.
|
protected |
angle of attack
|
protected |
initial angle of attack
|
protected |
angle of attach when airfoil stalls
|
protected |
effective planeform surface area
|
protected |
Coefficient of Drag / alpha slope.
Drag = C_D * q * S where q (dynamic pressure) = 0.5 * rho * v^2
|
protected |
Cd-alpha rate after stall.
|
protected |
Coefficient of Lift / alpha slope.
Lift = C_L * q * S where q (dynamic pressure) = 0.5 * rho * v^2
|
protected |
Cl-alpha rate after stall.
|
protected |
Coefficient of Moment / alpha slope.
Moment = C_M * q * S where q (dynamic pressure) = 0.5 * rho * v^2
|
protected |
Cm-alpha rate after stall.
|
protected |
Pointer to a joint that actuates a control surface for this lifting body.
|
protected |
how much to change CL per radian of control surface joint value.
|
protected |
center of pressure in link local coordinates
|
protectedinherited |
Path to the shared library file.
|
protected |
Normally, this is taken as a direction parallel to the chord of the airfoil in zero angle of attack forward flight.
|
protectedinherited |
Short name.
|
protected |
Pointer to link currently targeted by mud joint.
|
protected |
Pointer to model containing plugin.
|
protected |
Pointer to physics engine.
|
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.
|
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.
|
protected |
SDF for this plugin;.
|
protected |
angle of sweep
|
protectedinherited |
Type of plugin.
Referenced by ModelPlugin::ModelPlugin().
|
protected |
Connection to World Update events.
|
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.
|
protected |
: : make a stall velocity curve
|
protected |
Smoothed velocity.
|
protected |
Pointer to world.