A plugin that simulates lift and drag. More...
#include <liftdrag_plugin.h>
| Public Member Functions | |
| LiftDragPlugin () | |
| Constructor. | |
| virtual void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) | 
| ~LiftDragPlugin () | |
| Destructor. | |
| Protected Member Functions | |
| virtual void | OnUpdate () | 
| Callback for World Update events. | |
| Protected Attributes | |
| double | alpha | 
| angle of attack | |
| double | alpha0 | 
| initial angle of attack | |
| double | alphaStall | 
| angle of attach when airfoil stalls | |
| double | area | 
| effective planeform surface area | |
| double | cda | 
| Coefficient of Drag / alpha slope. Drag = C_D * q * S where q (dynamic pressure) = 0.5 * rho * v^2. | |
| double | cdaStall | 
| Cd-alpha rate after stall. | |
| double | cla | 
| Coefficient of Lift / alpha slope. Lift = C_L * q * S where q (dynamic pressure) = 0.5 * rho * v^2. | |
| double | claStall | 
| Cl-alpha rate after stall. | |
| double | cma | 
| Coefficient of Moment / alpha slope. Moment = C_M * q * S where q (dynamic pressure) = 0.5 * rho * v^2. | |
| double | cmaStall | 
| Cm-alpha rate after stall. | |
| physics::JointPtr | controlJoint | 
| Pointer to a joint that actuates a control surface for this lifting body. | |
| double | controlJointRadToCL | 
| how much to change CL per radian of control surface joint value. | |
| ignition::math::Vector3d | cp | 
| center of pressure in link local coordinates | |
| 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. | |
| physics::LinkPtr | link | 
| Pointer to link currently targeted by mud joint. | |
| physics::ModelPtr | model | 
| Pointer to model containing plugin. | |
| physics::PhysicsEnginePtr | physics | 
| Pointer to physics engine. | |
| 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. | |
| 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. | |
| sdf::ElementPtr | sdf | 
| SDF for this plugin;. | |
| double | sweep | 
| angle of sweep | |
| event::ConnectionPtr | updateConnection | 
| Connection to World Update events. | |
| 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. | |
| double | velocityStall | 
| : : make a stall velocity curve | |
| ignition::math::Vector3d | velSmooth | 
| Smoothed velocity. | |
| physics::WorldPtr | world | 
| Pointer to world. | |
A plugin that simulates lift and drag.
Definition at line 30 of file liftdrag_plugin.h.
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.
Destructor.
Definition at line 59 of file liftdrag_plugin.cpp.
| void LiftDragPlugin::Load | ( | physics::ModelPtr | _model, | 
| sdf::ElementPtr | _sdf | ||
| ) |  [virtual] | 
Definition at line 64 of file liftdrag_plugin.cpp.
| void LiftDragPlugin::OnUpdate | ( | ) |  [protected, virtual] | 
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.
| double gazebo::LiftDragPlugin::alpha  [protected] | 
angle of attack
Definition at line 107 of file liftdrag_plugin.h.
| double gazebo::LiftDragPlugin::alpha0  [protected] | 
initial angle of attack
Definition at line 104 of file liftdrag_plugin.h.
| double gazebo::LiftDragPlugin::alphaStall  [protected] | 
angle of attach when airfoil stalls
Definition at line 72 of file liftdrag_plugin.h.
| double gazebo::LiftDragPlugin::area  [protected] | 
effective planeform surface area
Definition at line 98 of file liftdrag_plugin.h.
| 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.
| double gazebo::LiftDragPlugin::cdaStall  [protected] | 
Cd-alpha rate after stall.
Definition at line 78 of file liftdrag_plugin.h.
| 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.
| double gazebo::LiftDragPlugin::claStall  [protected] | 
Cl-alpha rate after stall.
Definition at line 75 of file liftdrag_plugin.h.
| 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.
| double gazebo::LiftDragPlugin::cmaStall  [protected] | 
Cm-alpha rate after stall.
Definition at line 81 of file liftdrag_plugin.h.
| 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.
| 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.
| ignition::math::Vector3d gazebo::LiftDragPlugin::cp  [protected] | 
center of pressure in link local coordinates
Definition at line 110 of file liftdrag_plugin.h.
| 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.
| physics::LinkPtr gazebo::LiftDragPlugin::link  [protected] | 
Pointer to link currently targeted by mud joint.
Definition at line 125 of file liftdrag_plugin.h.
| physics::ModelPtr gazebo::LiftDragPlugin::model  [protected] | 
Pointer to model containing plugin.
Definition at line 54 of file liftdrag_plugin.h.
| physics::PhysicsEnginePtr gazebo::LiftDragPlugin::physics  [protected] | 
Pointer to physics engine.
Definition at line 51 of file liftdrag_plugin.h.
| 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.
| 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::ElementPtr gazebo::LiftDragPlugin::sdf  [protected] | 
SDF for this plugin;.
Definition at line 136 of file liftdrag_plugin.h.
| double gazebo::LiftDragPlugin::sweep  [protected] | 
angle of sweep
Definition at line 101 of file liftdrag_plugin.h.
Connection to World Update events.
Definition at line 45 of file liftdrag_plugin.h.
| 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.
| double gazebo::LiftDragPlugin::velocityStall  [protected] | 
: : make a stall velocity curve
Definition at line 84 of file liftdrag_plugin.h.
| ignition::math::Vector3d gazebo::LiftDragPlugin::velSmooth  [protected] | 
Smoothed velocity.
Definition at line 122 of file liftdrag_plugin.h.
| physics::WorldPtr gazebo::LiftDragPlugin::world  [protected] | 
Pointer to world.
Definition at line 48 of file liftdrag_plugin.h.