SIM_Plane.cpp 12 KB

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