APM:Libraries
SIM_Plane.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  very simple plane simulator class. Not aerodynamically accurate,
17  just enough to be able to debug control logic for new frame types
18 */
19 
20 #include "SIM_Plane.h"
21 
22 #include <stdio.h>
23 
24 using namespace SITL;
25 
26 Plane::Plane(const char *home_str, const char *frame_str) :
27  Aircraft(home_str, frame_str)
28 {
29  mass = 2.0f;
30 
31  /*
32  scaling from motor power to Newtons. Allows the plane to hold
33  vertically against gravity when the motor is at hover_throttle
34  */
36  frame_height = 0.1f;
37 
39 
40  if (strstr(frame_str, "-heavy")) {
41  mass = 8;
42  }
43  if (strstr(frame_str, "-revthrust")) {
44  reverse_thrust = true;
45  }
46  if (strstr(frame_str, "-elevon")) {
47  elevons = true;
48  } else if (strstr(frame_str, "-vtail")) {
49  vtail = true;
50  } else if (strstr(frame_str, "-dspoilers")) {
51  dspoilers = true;
52  }
53  if (strstr(frame_str, "-elevrev")) {
55  }
56  if (strstr(frame_str, "-catapult")) {
57  have_launcher = true;
58  launch_accel = 15;
59  launch_time = 2;
60  }
61  if (strstr(frame_str, "-bungee")) {
62  have_launcher = true;
63  launch_accel = 7;
64  launch_time = 4;
65  }
66  if (strstr(frame_str, "-throw")) {
67  have_launcher = true;
68  launch_accel = 10;
69  launch_time = 1;
70  }
71  if (strstr(frame_str, "-tailsitter")) {
72  tailsitter = true;
74  thrust_scale *= 1.5;
75  }
76 
77  if (strstr(frame_str, "-ice")) {
78  ice_engine = true;
79  }
80 }
81 
82 /*
83  the following functions are from last_letter
84  https://github.com/Georacer/last_letter/blob/master/last_letter/src/aerodynamicsLib.cpp
85  many thanks to Georacer!
86  */
87 float Plane::liftCoeff(float alpha) const
88 {
89  const float alpha0 = coefficient.alpha_stall;
90  const float M = coefficient.mcoeff;
91  const float c_lift_0 = coefficient.c_lift_0;
92  const float c_lift_a0 = coefficient.c_lift_a;
93 
94  // clamp the value of alpha to avoid exp(90) in calculation of sigmoid
95  const float max_alpha_delta = 0.8f;
96  if (alpha-alpha0 > max_alpha_delta) {
97  alpha = alpha0 + max_alpha_delta;
98  } else if (alpha0-alpha > max_alpha_delta) {
99  alpha = alpha0 - max_alpha_delta;
100  }
101  double sigmoid = ( 1+exp(-M*(alpha-alpha0))+exp(M*(alpha+alpha0)) ) / (1+exp(-M*(alpha-alpha0))) / (1+exp(M*(alpha+alpha0)));
102  double linear = (1.0-sigmoid) * (c_lift_0 + c_lift_a0*alpha); //Lift at small AoA
103  double flatPlate = sigmoid*(2*copysign(1,alpha)*pow(sin(alpha),2)*cos(alpha)); //Lift beyond stall
104 
105  float result = linear+flatPlate;
106  return result;
107 }
108 
109 float Plane::dragCoeff(float alpha) const
110 {
111  const float b = coefficient.b;
112  const float s = coefficient.s;
113  const float c_drag_p = coefficient.c_drag_p;
114  const float c_lift_0 = coefficient.c_lift_0;
115  const float c_lift_a0 = coefficient.c_lift_a;
116  const float oswald = coefficient.oswald;
117 
118  double AR = pow(b,2)/s;
119  double c_drag_a = c_drag_p + pow(c_lift_0+c_lift_a0*alpha,2)/(M_PI*oswald*AR);
120 
121  return c_drag_a;
122 }
123 
124 // Torque calculation function
125 Vector3f Plane::getTorque(float inputAileron, float inputElevator, float inputRudder, float inputThrust, const Vector3f &force) const
126 {
127  float alpha = angle_of_attack;
128 
129  //calculate aerodynamic torque
130  float effective_airspeed = airspeed;
131 
132  if (tailsitter) {
133  /*
134  tailsitters get airspeed from prop-wash
135  */
136  effective_airspeed += inputThrust * 20;
137 
138  // reduce effective angle of attack as thrust increases
139  alpha *= constrain_float(1 - inputThrust, 0, 1);
140  }
141 
142  const float s = coefficient.s;
143  const float c = coefficient.c;
144  const float b = coefficient.b;
145  const float c_l_0 = coefficient.c_l_0;
146  const float c_l_b = coefficient.c_l_b;
147  const float c_l_p = coefficient.c_l_p;
148  const float c_l_r = coefficient.c_l_r;
149  const float c_l_deltaa = coefficient.c_l_deltaa;
150  const float c_l_deltar = coefficient.c_l_deltar;
151  const float c_m_0 = coefficient.c_m_0;
152  const float c_m_a = coefficient.c_m_a;
153  const float c_m_q = coefficient.c_m_q;
154  const float c_m_deltae = coefficient.c_m_deltae;
155  const float c_n_0 = coefficient.c_n_0;
156  const float c_n_b = coefficient.c_n_b;
157  const float c_n_p = coefficient.c_n_p;
158  const float c_n_r = coefficient.c_n_r;
159  const float c_n_deltaa = coefficient.c_n_deltaa;
160  const float c_n_deltar = coefficient.c_n_deltar;
161  const Vector3f &CGOffset = coefficient.CGOffset;
162 
163  float rho = air_density;
164 
165  //read angular rates
166  double p = gyro.x;
167  double q = gyro.y;
168  double r = gyro.z;
169 
170  double qbar = 1.0/2.0*rho*pow(effective_airspeed,2)*s; //Calculate dynamic pressure
171  double la, na, ma;
172  if (is_zero(effective_airspeed))
173  {
174  la = 0;
175  ma = 0;
176  na = 0;
177  }
178  else
179  {
180  la = qbar*b*(c_l_0 + c_l_b*beta + c_l_p*b*p/(2*effective_airspeed) + c_l_r*b*r/(2*effective_airspeed) + c_l_deltaa*inputAileron + c_l_deltar*inputRudder);
181  ma = qbar*c*(c_m_0 + c_m_a*alpha + c_m_q*c*q/(2*effective_airspeed) + c_m_deltae*inputElevator);
182  na = qbar*b*(c_n_0 + c_n_b*beta + c_n_p*b*p/(2*effective_airspeed) + c_n_r*b*r/(2*effective_airspeed) + c_n_deltaa*inputAileron + c_n_deltar*inputRudder);
183  }
184 
185 
186  // Add torque to to force misalignment with CG
187  // r x F, where r is the distance from CoG to CoL
188  la += CGOffset.y * force.z - CGOffset.z * force.y;
189  ma += -CGOffset.x * force.z + CGOffset.z * force.x;
190  na += -CGOffset.y * force.x + CGOffset.x * force.y;
191 
192  return Vector3f(la, ma, na);
193 }
194 
195 // Force calculation function from last_letter
196 Vector3f Plane::getForce(float inputAileron, float inputElevator, float inputRudder) const
197 {
198  const float alpha = angle_of_attack;
199  const float c_drag_q = coefficient.c_drag_q;
200  const float c_lift_q = coefficient.c_lift_q;
201  const float s = coefficient.s;
202  const float c = coefficient.c;
203  const float b = coefficient.b;
204  const float c_drag_deltae = coefficient.c_drag_deltae;
205  const float c_lift_deltae = coefficient.c_lift_deltae;
206  const float c_y_0 = coefficient.c_y_0;
207  const float c_y_b = coefficient.c_y_b;
208  const float c_y_p = coefficient.c_y_p;
209  const float c_y_r = coefficient.c_y_r;
210  const float c_y_deltaa = coefficient.c_y_deltaa;
211  const float c_y_deltar = coefficient.c_y_deltar;
212 
213  float rho = air_density;
214 
215  //request lift and drag alpha-coefficients from the corresponding functions
216  double c_lift_a = liftCoeff(alpha);
217  double c_drag_a = dragCoeff(alpha);
218 
219  //convert coefficients to the body frame
220  double c_x_a = -c_drag_a*cos(alpha)+c_lift_a*sin(alpha);
221  double c_x_q = -c_drag_q*cos(alpha)+c_lift_q*sin(alpha);
222  double c_z_a = -c_drag_a*sin(alpha)-c_lift_a*cos(alpha);
223  double c_z_q = -c_drag_q*sin(alpha)-c_lift_q*cos(alpha);
224 
225  //read angular rates
226  double p = gyro.x;
227  double q = gyro.y;
228  double r = gyro.z;
229 
230  //calculate aerodynamic force
231  double qbar = 1.0/2.0*rho*pow(airspeed,2)*s; //Calculate dynamic pressure
232  double ax, ay, az;
233  if (is_zero(airspeed))
234  {
235  ax = 0;
236  ay = 0;
237  az = 0;
238  }
239  else
240  {
241  ax = qbar*(c_x_a + c_x_q*c*q/(2*airspeed) - c_drag_deltae*cos(alpha)*fabs(inputElevator) + c_lift_deltae*sin(alpha)*inputElevator);
242  // split c_x_deltae to include "abs" term
243  ay = qbar*(c_y_0 + c_y_b*beta + c_y_p*b*p/(2*airspeed) + c_y_r*b*r/(2*airspeed) + c_y_deltaa*inputAileron + c_y_deltar*inputRudder);
244  az = qbar*(c_z_a + c_z_q*c*q/(2*airspeed) - c_drag_deltae*sin(alpha)*fabs(inputElevator) - c_lift_deltae*cos(alpha)*inputElevator);
245  // split c_z_deltae to include "abs" term
246  }
247  return Vector3f(ax, ay, az);
248 }
249 
250 void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
251 {
252  float aileron = filtered_servo_angle(input, 0);
253  float elevator = filtered_servo_angle(input, 1);
254  float rudder = filtered_servo_angle(input, 3);
255  bool launch_triggered = input.servos[6] > 1700;
256  float throttle;
258  elevator = -elevator;
259  rudder = -rudder;
260  }
261  if (elevons) {
262  // fake an elevon plane
263  float ch1 = aileron;
264  float ch2 = elevator;
265  aileron = (ch2-ch1)/2.0f;
266  // the minus does away with the need for RC2_REV=-1
267  elevator = -(ch2+ch1)/2.0f;
268 
269  // assume no rudder
270  rudder = 0;
271  } else if (vtail) {
272  // fake a vtail plane
273  float ch1 = elevator;
274  float ch2 = rudder;
275  // this matches VTAIL_OUTPUT==2
276  elevator = (ch2-ch1)/2.0f;
277  rudder = (ch2+ch1)/2.0f;
278  } else if (dspoilers) {
279  // fake a differential spoiler plane. Use outputs 1, 2, 4 and 5
280  float dspoiler1_left = filtered_servo_angle(input, 0);
281  float dspoiler1_right = filtered_servo_angle(input, 1);
282  float dspoiler2_left = filtered_servo_angle(input, 3);
283  float dspoiler2_right = filtered_servo_angle(input, 4);
284  float elevon_left = (dspoiler1_left + dspoiler2_left)/2;
285  float elevon_right = (dspoiler1_right + dspoiler2_right)/2;
286  aileron = (elevon_right-elevon_left)/2;
287  elevator = (elevon_left+elevon_right)/2;
288  rudder = fabsf(dspoiler1_right - dspoiler2_right)/2 - fabsf(dspoiler1_left - dspoiler2_left)/2;
289  }
290  //printf("Aileron: %.1f elevator: %.1f rudder: %.1f\n", aileron, elevator, rudder);
291 
292  if (reverse_thrust) {
293  throttle = filtered_servo_angle(input, 2);
294  } else {
295  throttle = filtered_servo_range(input, 2);
296  }
297 
298  float thrust = throttle;
299 
300  if (ice_engine) {
301  thrust = icengine.update(input);
302  }
303 
304  // calculate angle of attack
307 
308  if (tailsitter) {
309  /*
310  tailsitters get 4x the control surfaces
311  */
312  aileron *= 4;
313  elevator *= 4;
314  rudder *= 4;
315  }
316 
317  Vector3f force = getForce(aileron, elevator, rudder);
318  rot_accel = getTorque(aileron, elevator, rudder, thrust, force);
319 
320  if (have_launcher) {
321  /*
322  simple simulation of a launcher
323  */
324  if (launch_triggered) {
325  uint64_t now = AP_HAL::millis64();
326  if (launch_start_ms == 0) {
327  launch_start_ms = now;
328  }
329  if (now - launch_start_ms < launch_time*1000) {
330  force.x += launch_accel;
331  force.z += launch_accel/3;
332  }
333  } else {
334  // allow reset of catapult
335  launch_start_ms = 0;
336  }
337  }
338 
339  // simulate engine RPM
340  rpm1 = thrust * 7000;
341 
342  // scale thrust to newtons
343  thrust *= thrust_scale;
344 
345  accel_body = Vector3f(thrust, 0, 0) + force;
346  accel_body /= mass;
347 
348  // add some noise
349  if (thrust_scale > 0) {
350  add_noise(fabsf(thrust) / thrust_scale);
351  }
352 
353  if (on_ground() && !tailsitter) {
354  // add some ground friction
355  Vector3f vel_body = dcm.transposed() * velocity_ef;
356  accel_body.x -= vel_body.x * 0.3f;
357  }
358 }
359 
360 /*
361  update the plane simulation by one time step
362  */
363 void Plane::update(const struct sitl_input &input)
364 {
365  Vector3f rot_accel;
366 
367  update_wind(input);
368 
369  calculate_forces(input, rot_accel, accel_body);
370 
371  update_dynamics(rot_accel);
372 
373  // update lat/lon/altitude
374  update_position();
375  time_advance();
376 
377  // update magnetic field
379 }
Vector3f accel_body
Definition: SIM_Aircraft.h:142
ICEngine icengine
Definition: SIM_Plane.h:107
float c_l_p
Definition: SIM_Plane.h:71
void update_wind(const struct sitl_input &input)
Vector3< float > Vector3f
Definition: vector3.h:246
float c_n_r
Definition: SIM_Plane.h:83
float launch_accel
Definition: SIM_Plane.h:103
bool reverse_thrust
Definition: SIM_Plane.h:95
Plane(const char *home_str, const char *frame_str)
Definition: SIM_Plane.cpp:26
float c_n_b
Definition: SIM_Plane.h:81
float c_y_b
Definition: SIM_Plane.h:65
float c_n_p
Definition: SIM_Plane.h:82
float c_drag_q
Definition: SIM_Plane.h:61
float c_m_deltae
Definition: SIM_Plane.h:79
float c_drag_deltae
Definition: SIM_Plane.h:62
void add_noise(float throttle)
float c_y_deltaa
Definition: SIM_Plane.h:68
float c_l_0
Definition: SIM_Plane.h:70
float c_n_deltar
Definition: SIM_Plane.h:85
float filtered_servo_range(const struct sitl_input &input, uint8_t idx)
float c_y_deltar
Definition: SIM_Plane.h:69
const float air_density
Definition: SIM_Plane.h:44
bool have_launcher
Definition: SIM_Plane.h:102
void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
Definition: SIM_Plane.cpp:250
float update(const struct Aircraft::sitl_input &input)
float c_l_deltar
Definition: SIM_Plane.h:75
bool dspoilers
Definition: SIM_Plane.h:98
float c_lift_deltae
Definition: SIM_Plane.h:55
float c_m_0
Definition: SIM_Plane.h:76
const char * result
Definition: Printf.cpp:16
bool tailsitter
Definition: SIM_Plane.h:101
float c_lift_q
Definition: SIM_Plane.h:57
float b
Definition: SIM_Plane.h:52
bool ice_engine
Definition: SIM_Plane.h:100
float c_lift_a
Definition: SIM_Plane.h:56
uint64_t millis64()
Definition: system.cpp:167
float c
Definition: SIM_Plane.h:53
float oswald
Definition: SIM_Plane.h:59
float c_y_p
Definition: SIM_Plane.h:66
virtual bool on_ground() const
float dragCoeff(float alpha) const
Definition: SIM_Plane.cpp:109
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
float launch_time
Definition: SIM_Plane.h:104
const float hover_throttle
Definition: SIM_Plane.h:43
Vector3f CGOffset
Definition: SIM_Plane.h:91
Vector3f getTorque(float inputAileron, float inputElevator, float inputRudder, float inputThrust, const Vector3f &force) const
Definition: SIM_Plane.cpp:125
float thrust_scale
Definition: SIM_Plane.h:94
#define GRAVITY_MSS
Definition: definitions.h:47
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
uint64_t launch_start_ms
Definition: SIM_Plane.h:105
Vector3f velocity_ef
Definition: SIM_Aircraft.h:136
float s
Definition: SIM_Plane.h:51
T y
Definition: vector3.h:67
float angle_of_attack
Definition: SIM_Plane.h:45
float c_y_0
Definition: SIM_Plane.h:64
T z
Definition: vector3.h:67
float c_y_r
Definition: SIM_Plane.h:67
Vector3f velocity_air_bf
Definition: SIM_Aircraft.h:139
float c_n_deltaa
Definition: SIM_Plane.h:84
float c_drag_p
Definition: SIM_Plane.h:63
void update_mag_field_bf(void)
float c_m_a
Definition: SIM_Plane.h:77
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
float beta
Definition: SIM_Plane.h:46
void update_position(void)
float c_lift_0
Definition: SIM_Plane.h:54
void update_dynamics(const Vector3f &rot_accel)
struct SITL::Plane::@209 coefficient
bool vtail
Definition: SIM_Plane.h:97
bool elevons
Definition: SIM_Plane.h:96
#define M_PI
Definition: definitions.h:10
float c_n_0
Definition: SIM_Plane.h:80
float c_l_b
Definition: SIM_Plane.h:72
float c_m_q
Definition: SIM_Plane.h:78
float c_l_r
Definition: SIM_Plane.h:73
Vector3f getForce(float inputAileron, float inputElevator, float inputRudder) const
Definition: SIM_Plane.cpp:196
enum SITL::Aircraft::@199 ground_behavior
virtual void update(const struct sitl_input &input)
Definition: SIM_Plane.cpp:363
float liftCoeff(float alpha) const
Definition: SIM_Plane.cpp:87
float filtered_servo_angle(const struct sitl_input &input, uint8_t idx)
float c_l_deltaa
Definition: SIM_Plane.h:74
bool reverse_elevator_rudder
Definition: SIM_Plane.h:99
T x
Definition: vector3.h:67