liftdrag_plugin.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014-2016 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef _GAZEBO_LIFT_DRAG_PLUGIN_HH_
18 #define _GAZEBO_LIFT_DRAG_PLUGIN_HH_
19 
20 #include <string>
21 #include <vector>
22 
23 #include "gazebo/common/Plugin.hh"
24 #include "gazebo/physics/physics.hh"
25 #include "gazebo/transport/TransportTypes.hh"
26 
27 namespace gazebo
28 {
30  class GAZEBO_VISIBLE LiftDragPlugin : public ModelPlugin
31  {
33  public: LiftDragPlugin();
34 
36  public: ~LiftDragPlugin();
37 
38  // Documentation Inherited.
39  public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
40 
42  protected: virtual void OnUpdate();
43 
45  protected: event::ConnectionPtr updateConnection;
46 
48  protected: physics::WorldPtr world;
49 
51  protected: physics::PhysicsEnginePtr physics;
52 
54  protected: physics::ModelPtr model;
55 
59  protected: double cla;
60 
64  protected: double cda;
65 
69  protected: double cma;
70 
72  protected: double alphaStall;
73 
75  protected: double claStall;
76 
78  protected: double cdaStall;
79 
81  protected: double cmaStall;
82 
84  protected: double velocityStall;
85 
89  protected: double rho;
90 
95  protected: bool radialSymmetry;
96 
98  protected: double area;
99 
101  protected: double sweep;
102 
104  protected: double alpha0;
105 
107  protected: double alpha;
108 
110  protected: ignition::math::Vector3d cp;
111 
114  protected: ignition::math::Vector3d forward;
115 
119  protected: ignition::math::Vector3d upward;
120 
122  protected: ignition::math::Vector3d velSmooth;
123 
125  protected: physics::LinkPtr link;
126 
129  protected: physics::JointPtr controlJoint;
130 
133  protected: double controlJointRadToCL;
134 
136  protected: sdf::ElementPtr sdf;
137  };
138 }
139 #endif
physics::LinkPtr link
Pointer to link currently targeted by mud joint.
double area
effective planeform surface area
double alpha
angle of attack
ignition::math::Vector3d upward
A vector in the lift/drag plane, perpendicular to the forward vector. Inflow velocity orthogonal to f...
double sweep
angle of sweep
physics::ModelPtr model
Pointer to model containing plugin.
double cla
Coefficient of Lift / alpha slope. Lift = C_L * q * S where q (dynamic pressure) = 0...
sdf::ElementPtr sdf
SDF for this plugin;.
double alphaStall
angle of attach when airfoil stalls
ignition::math::Vector3d forward
Normally, this is taken as a direction parallel to the chord of the airfoil in zero angle of attack f...
double controlJointRadToCL
how much to change CL per radian of control surface joint value.
double rho
air density at 25 deg C it&#39;s about 1.1839 kg/m^3 At 20 °C and 101.325 kPa, dry air has a density of 1...
double cdaStall
Cd-alpha rate after stall.
physics::WorldPtr world
Pointer to world.
event::ConnectionPtr updateConnection
Connection to World Update events.
physics::JointPtr controlJoint
Pointer to a joint that actuates a control surface for this lifting body.
double cma
Coefficient of Moment / alpha slope. Moment = C_M * q * S where q (dynamic pressure) = 0...
double cmaStall
Cm-alpha rate after stall.
ignition::math::Vector3d cp
center of pressure in link local coordinates
A plugin that simulates lift and drag.
bool radialSymmetry
if the shape is aerodynamically radially symmetric about the forward direction. Defaults to false for...
double cda
Coefficient of Drag / alpha slope. Drag = C_D * q * S where q (dynamic pressure) = 0...
double claStall
Cl-alpha rate after stall.
ignition::math::Vector3d velSmooth
Smoothed velocity.
physics::PhysicsEnginePtr physics
Pointer to physics engine.
double alpha0
initial angle of attack
double velocityStall
: : make a stall velocity curve


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