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 <LiftDragPlugin.hh>

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

Public Member Functions

 LiftDragPlugin ()
 Constructor. More...
 
 ~LiftDragPlugin ()
 Destructor. More...
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 Load function. More...
 
- Public Member Functions inherited from gazebo::ModelPlugin
 ModelPlugin ()
 Constructor. More...
 
virtual ~ModelPlugin ()
 Destructor. More...
 
virtual void Init ()
 Override this method for custom plugin initialization behavior. More...
 
virtual void Reset ()
 Override this method for custom plugin reset behavior. More...
 
- Public Member Functions inherited from gazebo::PluginT< ModelPlugin >
 PluginT ()
 Constructor. More...
 
virtual ~PluginT ()
 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...
 

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...
 
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...
 
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...
 
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...
 
- Protected Attributes inherited from gazebo::PluginT< ModelPlugin >
std::string filename
 Path to the shared library file. More...
 
std::string handleName
 Short name. More...
 
PluginType type
 Type of plugin. More...
 

Additional Inherited Members

- Public Types inherited from gazebo::PluginT< ModelPlugin >
typedef boost::shared_ptr
< ModelPlugin
TPtr
 plugin pointer type definition More...
 
- Static Public Member Functions inherited from gazebo::PluginT< ModelPlugin >
static TPtr Create (const std::string &_filename, const std::string &_name)
 a class method that creates a plugin from a file name. More...
 

Detailed Description

A plugin that simulates lift and drag.

Constructor & Destructor Documentation

gazebo::LiftDragPlugin::LiftDragPlugin ( )

Constructor.

gazebo::LiftDragPlugin::~LiftDragPlugin ( )

Destructor.

Member Function Documentation

virtual void gazebo::LiftDragPlugin::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 gazebo::ModelPlugin.

virtual void gazebo::LiftDragPlugin::OnUpdate ( )
protectedvirtual

Callback for World Update events.

Member Data Documentation

double gazebo::LiftDragPlugin::alpha
protected

angle of attack

double gazebo::LiftDragPlugin::alpha0
protected

initial angle of attack

double gazebo::LiftDragPlugin::alphaStall
protected

angle of attach when airfoil stalls

double gazebo::LiftDragPlugin::area
protected

effective planeform surface area

double gazebo::LiftDragPlugin::cda
protected

Coefficient of Drag / alpha slope.

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

double gazebo::LiftDragPlugin::cdaStall
protected

Cd-alpha rate after stall.

double gazebo::LiftDragPlugin::cla
protected

Coefficient of Lift / alpha slope.

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

double gazebo::LiftDragPlugin::claStall
protected

Cl-alpha rate after stall.

double gazebo::LiftDragPlugin::cma
protected

Coefficient of Moment / alpha slope.

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

double gazebo::LiftDragPlugin::cmaStall
protected

Cm-alpha rate after stall.

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

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

double gazebo::LiftDragPlugin::controlJointRadToCL
protected

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

math::Vector3 gazebo::LiftDragPlugin::cp
protected

center of pressure in link local coordinates

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

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

Pointer to link currently targeted by mud joint.

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

Pointer to model containing plugin.

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

Pointer to physics engine.

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.

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.

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

SDF for this plugin;.

double gazebo::LiftDragPlugin::sweep
protected

angle of sweep

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

Connection to World Update events.

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

double gazebo::LiftDragPlugin::velocityStall
protected

: : make a stall velocity curve

math::Vector3 gazebo::LiftDragPlugin::velSmooth
protected

Smoothed velocity.

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

Pointer to world.


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