SIM_Aircraft.cpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806
  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. parent class for aircraft simulators
  15. */
  16. #include "SIM_Aircraft.h"
  17. #include <stdio.h>
  18. #include <sys/time.h>
  19. #include <unistd.h>
  20. #if defined(__CYGWIN__) || defined(__CYGWIN64__)
  21. #include <windows.h>
  22. #include <time.h>
  23. #include <mmsystem.h>
  24. #endif
  25. #include <AP_Logger/AP_Logger.h>
  26. #include <AP_Param/AP_Param.h>
  27. #include <AP_Declination/AP_Declination.h>
  28. using namespace SITL;
  29. /*
  30. parent class for all simulator types
  31. */
  32. Aircraft::Aircraft(const char *frame_str) :
  33. ground_level(0.0f),
  34. frame_height(0.0f),
  35. dcm(),
  36. gyro(),
  37. gyro_prev(),
  38. ang_accel(),
  39. velocity_ef(),
  40. mass(0.0f),
  41. accel_body(0.0f, 0.0f, -GRAVITY_MSS),
  42. time_now_us(0),
  43. gyro_noise(radians(0.1f)),
  44. accel_noise(0.3f),
  45. rate_hz(1200.0f),
  46. autotest_dir(nullptr),
  47. frame(frame_str),
  48. #if defined(__CYGWIN__) || defined(__CYGWIN64__)
  49. min_sleep_time(20000)
  50. #else
  51. min_sleep_time(5000)
  52. #endif
  53. {
  54. // make the SIM_* variables available to simulator backends
  55. sitl = AP::sitl();
  56. set_speedup(1.0f);
  57. last_wall_time_us = get_wall_time_us();
  58. frame_counter = 0;
  59. // allow for orientation settings, such as with tailsitters
  60. enum ap_var_type ptype;
  61. ahrs_orientation = (AP_Int8 *)AP_Param::find("AHRS_ORIENTATION", &ptype);
  62. terrain = reinterpret_cast<AP_Terrain *>(AP_Param::find_object("TERRAIN_"));
  63. }
  64. void Aircraft::set_start_location(const Location &start_loc, const float start_yaw)
  65. {
  66. home = start_loc;
  67. home_yaw = start_yaw;
  68. home_is_set = true;
  69. ::printf("Home: %f %f alt=%fm hdg=%f\n",
  70. home.lat*1e-7,
  71. home.lng*1e-7,
  72. home.alt*0.01,
  73. home_yaw);
  74. location = home;
  75. ground_level = home.alt * 0.01f;
  76. dcm.from_euler(0.0f, 0.0f, radians(home_yaw));
  77. }
  78. /*
  79. return difference in altitude between home position and current loc
  80. */
  81. float Aircraft::ground_height_difference() const
  82. {
  83. float h1, h2;
  84. if (sitl &&
  85. sitl->terrain_enable && terrain &&
  86. terrain->height_amsl(home, h1, false) &&
  87. terrain->height_amsl(location, h2, false)) {
  88. return h2 - h1;
  89. }
  90. return 0.0f;
  91. }
  92. void Aircraft::set_precland(SIM_Precland *_precland) {
  93. precland = _precland;
  94. precland->set_default_location(home.lat * 1.0e-7f, home.lng * 1.0e-7f, static_cast<int16_t>(get_home_yaw()));
  95. }
  96. /*
  97. return current height above ground level (metres)
  98. */
  99. float Aircraft::hagl() const
  100. {
  101. return (-position.z) + home.alt * 0.01f - ground_level - frame_height - ground_height_difference();
  102. }
  103. /*
  104. return true if we are on the ground
  105. */
  106. bool Aircraft::on_ground() const
  107. {
  108. return hagl() <= 0.001f; // prevent bouncing around ground
  109. }
  110. /*
  111. update location from position
  112. */
  113. void Aircraft::update_position(void)
  114. {
  115. location = home;
  116. location.offset(position.x, position.y);
  117. location.alt = static_cast<int32_t>(home.alt - position.z * 100.0f);
  118. #if 0
  119. // logging of raw sitl data
  120. Vector3f accel_ef = dcm * accel_body;
  121. AP::logger().Write("SITL", "TimeUS,VN,VE,VD,AN,AE,AD,PN,PE,PD", "Qfffffffff",
  122. AP_HAL::micros64(),
  123. velocity_ef.x, velocity_ef.y, velocity_ef.z,
  124. accel_ef.x, accel_ef.y, accel_ef.z,
  125. position.x, position.y, position.z);
  126. #endif
  127. }
  128. /*
  129. update body magnetic field from position and rotation
  130. */
  131. void Aircraft::update_mag_field_bf()
  132. {
  133. // get the magnetic field intensity and orientation
  134. float intensity;
  135. float declination;
  136. float inclination;
  137. AP_Declination::get_mag_field_ef(location.lat * 1e-7f, location.lng * 1e-7f, intensity, declination, inclination);
  138. // create a field vector and rotate to the required orientation
  139. Vector3f mag_ef(1e3f * intensity, 0.0f, 0.0f);
  140. Matrix3f R;
  141. R.from_euler(0.0f, -ToRad(inclination), ToRad(declination));
  142. mag_ef = R * mag_ef;
  143. // calculate frame height above ground
  144. const float frame_height_agl = fmaxf((-position.z) + home.alt * 0.01f - ground_level, 0.0f);
  145. if (!sitl) {
  146. // running example program
  147. return;
  148. }
  149. // calculate scaling factor that varies from 1 at ground level to 1/8 at sitl->mag_anomaly_hgt
  150. // Assume magnetic anomaly strength scales with 1/R**3
  151. float anomaly_scaler = (sitl->mag_anomaly_hgt / (frame_height_agl + sitl->mag_anomaly_hgt));
  152. anomaly_scaler = anomaly_scaler * anomaly_scaler * anomaly_scaler;
  153. // add scaled anomaly to earth field
  154. mag_ef += sitl->mag_anomaly_ned.get() * anomaly_scaler;
  155. // Rotate into body frame
  156. mag_bf = dcm.transposed() * mag_ef;
  157. // add motor interference
  158. mag_bf += sitl->mag_mot.get() * battery_current;
  159. }
  160. /* advance time by deltat in seconds */
  161. void Aircraft::time_advance()
  162. {
  163. // we only advance time if it hasn't been advanced already by the
  164. // backend
  165. if (last_time_us == time_now_us) {
  166. time_now_us += frame_time_us;
  167. }
  168. last_time_us = time_now_us;
  169. if (use_time_sync) {
  170. sync_frame_time();
  171. }
  172. }
  173. /* setup the frame step time */
  174. void Aircraft::setup_frame_time(float new_rate, float new_speedup)
  175. {
  176. rate_hz = new_rate;
  177. target_speedup = new_speedup;
  178. frame_time_us = static_cast<uint64_t>(1.0e6f/rate_hz);
  179. scaled_frame_time_us = frame_time_us/target_speedup;
  180. last_wall_time_us = get_wall_time_us();
  181. achieved_rate_hz = rate_hz;
  182. }
  183. /* adjust frame_time calculation */
  184. void Aircraft::adjust_frame_time(float new_rate)
  185. {
  186. if (!is_equal(rate_hz, new_rate)) {
  187. rate_hz = new_rate;
  188. frame_time_us = static_cast<uint64_t>(1.0e6f/rate_hz);
  189. scaled_frame_time_us = frame_time_us/target_speedup;
  190. }
  191. }
  192. /*
  193. try to synchronise simulation time with wall clock time, taking
  194. into account desired speedup
  195. This tries to take account of possible granularity of
  196. get_wall_time_us() so it works reasonably well on windows
  197. */
  198. void Aircraft::sync_frame_time(void)
  199. {
  200. frame_counter++;
  201. uint64_t now = get_wall_time_us();
  202. if (frame_counter >= 40 &&
  203. now > last_wall_time_us) {
  204. const float rate = frame_counter * 1.0e6f/(now - last_wall_time_us);
  205. achieved_rate_hz = (0.99f*achieved_rate_hz) + (0.01f * rate);
  206. if (achieved_rate_hz < rate_hz * target_speedup) {
  207. scaled_frame_time_us *= 0.999f;
  208. } else {
  209. scaled_frame_time_us /= 0.999f;
  210. }
  211. #if 0
  212. ::printf("achieved_rate_hz=%.3f rate=%.2f rate_hz=%.3f sft=%.1f\n",
  213. static_cast<double>(achieved_rate_hz),
  214. static_cast<double>(rate),
  215. static_cast<double>(rate_hz),
  216. static_cast<double>(scaled_frame_time_us));
  217. #endif
  218. const uint32_t sleep_time = static_cast<uint32_t>(scaled_frame_time_us * frame_counter);
  219. if (sleep_time > min_sleep_time) {
  220. usleep(sleep_time);
  221. }
  222. last_wall_time_us = now;
  223. frame_counter = 0;
  224. }
  225. }
  226. /* add noise based on throttle level (from 0..1) */
  227. void Aircraft::add_noise(float throttle)
  228. {
  229. gyro += Vector3f(rand_normal(0, 1),
  230. rand_normal(0, 1),
  231. rand_normal(0, 1)) * gyro_noise * fabsf(throttle);
  232. accel_body += Vector3f(rand_normal(0, 1),
  233. rand_normal(0, 1),
  234. rand_normal(0, 1)) * accel_noise * fabsf(throttle);
  235. }
  236. /*
  237. normal distribution random numbers
  238. See
  239. http://en.literateprograms.org/index.php?title=Special:DownloadCode/Box-Muller_transform_%28C%29&oldid=7011
  240. */
  241. double Aircraft::rand_normal(double mean, double stddev)
  242. {
  243. static double n2 = 0.0;
  244. static int n2_cached = 0;
  245. if (!n2_cached) {
  246. double x, y, r;
  247. do
  248. {
  249. x = 2.0 * rand()/RAND_MAX - 1;
  250. y = 2.0 * rand()/RAND_MAX - 1;
  251. r = x*x + y*y;
  252. } while (is_zero(r) || r > 1.0);
  253. const double d = sqrt(-2.0 * log(r)/r);
  254. const double n1 = x * d;
  255. n2 = y * d;
  256. const double result = n1 * stddev + mean;
  257. n2_cached = 1;
  258. return result;
  259. } else {
  260. n2_cached = 0;
  261. return n2 * stddev + mean;
  262. }
  263. }
  264. /*
  265. fill a sitl_fdm structure from the simulator state
  266. */
  267. void Aircraft::fill_fdm(struct sitl_fdm &fdm)
  268. {
  269. if (use_smoothing) {
  270. smooth_sensors();
  271. }
  272. fdm.timestamp_us = time_now_us;
  273. if (fdm.home.lat == 0 && fdm.home.lng == 0) {
  274. // initialise home
  275. fdm.home = home;
  276. }
  277. fdm.latitude = location.lat * 1.0e-7;
  278. fdm.longitude = location.lng * 1.0e-7;
  279. fdm.altitude = location.alt * 1.0e-2;
  280. fdm.heading = degrees(atan2f(velocity_ef.y, velocity_ef.x));
  281. fdm.speedN = velocity_ef.x;
  282. fdm.speedE = velocity_ef.y;
  283. fdm.speedD = velocity_ef.z;
  284. fdm.xAccel = accel_body.x;
  285. fdm.yAccel = accel_body.y;
  286. fdm.zAccel = accel_body.z;
  287. fdm.rollRate = degrees(gyro.x);
  288. fdm.pitchRate = degrees(gyro.y);
  289. fdm.yawRate = degrees(gyro.z);
  290. fdm.angAccel.x = degrees(ang_accel.x);
  291. fdm.angAccel.y = degrees(ang_accel.y);
  292. fdm.angAccel.z = degrees(ang_accel.z);
  293. float r, p, y;
  294. dcm.to_euler(&r, &p, &y);
  295. fdm.rollDeg = degrees(r);
  296. fdm.pitchDeg = degrees(p);
  297. fdm.yawDeg = degrees(y);
  298. fdm.quaternion.from_rotation_matrix(dcm);
  299. fdm.airspeed = airspeed_pitot;
  300. fdm.battery_voltage = battery_voltage;
  301. fdm.battery_current = battery_current;
  302. fdm.rpm1 = rpm1;
  303. fdm.rpm2 = rpm2;
  304. fdm.rcin_chan_count = rcin_chan_count;
  305. fdm.range = range;
  306. memcpy(fdm.rcin, rcin, rcin_chan_count * sizeof(float));
  307. fdm.bodyMagField = mag_bf;
  308. // copy laser scanner results
  309. fdm.scanner.points = scanner.points;
  310. fdm.scanner.ranges = scanner.ranges;
  311. if (smoothing.enabled) {
  312. fdm.xAccel = smoothing.accel_body.x;
  313. fdm.yAccel = smoothing.accel_body.y;
  314. fdm.zAccel = smoothing.accel_body.z;
  315. fdm.rollRate = degrees(smoothing.gyro.x);
  316. fdm.pitchRate = degrees(smoothing.gyro.y);
  317. fdm.yawRate = degrees(smoothing.gyro.z);
  318. fdm.speedN = smoothing.velocity_ef.x;
  319. fdm.speedE = smoothing.velocity_ef.y;
  320. fdm.speedD = smoothing.velocity_ef.z;
  321. fdm.latitude = smoothing.location.lat * 1.0e-7;
  322. fdm.longitude = smoothing.location.lng * 1.0e-7;
  323. fdm.altitude = smoothing.location.alt * 1.0e-2;
  324. }
  325. if (ahrs_orientation != nullptr) {
  326. enum Rotation imu_rotation = (enum Rotation)ahrs_orientation->get();
  327. if (imu_rotation != ROTATION_NONE) {
  328. Matrix3f m = dcm;
  329. Matrix3f rot;
  330. rot.from_rotation(imu_rotation);
  331. m = m * rot.transposed();
  332. m.to_euler(&r, &p, &y);
  333. fdm.rollDeg = degrees(r);
  334. fdm.pitchDeg = degrees(p);
  335. fdm.yawDeg = degrees(y);
  336. fdm.quaternion.from_rotation_matrix(m);
  337. }
  338. }
  339. if (!is_equal(last_speedup, float(sitl->speedup)) && sitl->speedup > 0) {
  340. set_speedup(sitl->speedup);
  341. last_speedup = sitl->speedup;
  342. }
  343. }
  344. uint64_t Aircraft::get_wall_time_us() const
  345. {
  346. #if defined(__CYGWIN__) || defined(__CYGWIN64__)
  347. static DWORD tPrev;
  348. static uint64_t last_ret_us;
  349. if (tPrev == 0) {
  350. tPrev = timeGetTime();
  351. return 0;
  352. }
  353. DWORD now = timeGetTime();
  354. last_ret_us += (uint64_t)((now - tPrev)*1000UL);
  355. tPrev = now;
  356. return last_ret_us;
  357. #else
  358. struct timeval tp;
  359. gettimeofday(&tp, nullptr);
  360. return static_cast<uint64_t>(tp.tv_sec * 1.0e6 + tp.tv_usec);
  361. #endif
  362. }
  363. /*
  364. set simulation speedup
  365. */
  366. void Aircraft::set_speedup(float speedup)
  367. {
  368. setup_frame_time(rate_hz, speedup);
  369. }
  370. void Aircraft::update_model(const struct sitl_input &input)
  371. {
  372. if (!home_is_set) {
  373. if (sitl == nullptr) {
  374. return;
  375. }
  376. Location loc;
  377. loc.lat = sitl->opos.lat.get() * 1.0e7;
  378. loc.lng = sitl->opos.lng.get() * 1.0e7;
  379. loc.alt = sitl->opos.alt.get() * 1.0e2;
  380. set_start_location(loc, sitl->opos.hdg.get());
  381. }
  382. update(input);
  383. }
  384. /*
  385. update the simulation attitude and relative position
  386. */
  387. void Aircraft::update_dynamics(const Vector3f &rot_accel)
  388. {
  389. const float delta_time = frame_time_us * 1.0e-6f;
  390. // update rotational rates in body frame
  391. gyro += rot_accel * delta_time;
  392. gyro.x = constrain_float(gyro.x, -radians(2000.0f), radians(2000.0f));
  393. gyro.y = constrain_float(gyro.y, -radians(2000.0f), radians(2000.0f));
  394. gyro.z = constrain_float(gyro.z, -radians(2000.0f), radians(2000.0f));
  395. // estimate angular acceleration using a first order difference calculation
  396. // TODO the simulator interface should provide the angular acceleration
  397. ang_accel = (gyro - gyro_prev) / delta_time;
  398. gyro_prev = gyro;
  399. // update attitude
  400. dcm.rotate(gyro * delta_time);
  401. dcm.normalize();
  402. Vector3f accel_earth = dcm * accel_body;
  403. accel_earth += Vector3f(0.0f, 0.0f, GRAVITY_MSS);
  404. // if we're on the ground, then our vertical acceleration is limited
  405. // to zero. This effectively adds the force of the ground on the aircraft
  406. if (on_ground() && accel_earth.z > 0) {
  407. accel_earth.z = 0;
  408. }
  409. // work out acceleration as seen by the accelerometers. It sees the kinematic
  410. // acceleration (ie. real movement), plus gravity
  411. accel_body = dcm.transposed() * (accel_earth + Vector3f(0.0f, 0.0f, -GRAVITY_MSS));
  412. // new velocity vector
  413. velocity_ef += accel_earth * delta_time;
  414. const bool was_on_ground = on_ground();
  415. // new position vector
  416. position += velocity_ef * delta_time;
  417. // velocity relative to air mass, in earth frame
  418. velocity_air_ef = velocity_ef + wind_ef;
  419. // velocity relative to airmass in body frame
  420. velocity_air_bf = dcm.transposed() * velocity_air_ef;
  421. // airspeed
  422. airspeed = velocity_air_ef.length();
  423. // airspeed as seen by a fwd pitot tube (limited to 120m/s)
  424. airspeed_pitot = constrain_float(velocity_air_bf * Vector3f(1.0f, 0.0f, 0.0f), 0.0f, 120.0f);
  425. // constrain height to the ground
  426. if (on_ground()) {
  427. if (!was_on_ground && AP_HAL::millis() - last_ground_contact_ms > 1000) {
  428. printf("Hit ground at %f m/s\n", velocity_ef.z);
  429. last_ground_contact_ms = AP_HAL::millis();
  430. }
  431. position.z = -(ground_level + frame_height - home.alt * 0.01f + ground_height_difference());
  432. switch (ground_behavior) {
  433. case GROUND_BEHAVIOR_NONE:
  434. break;
  435. case GROUND_BEHAVIOR_NO_MOVEMENT: {
  436. // zero roll/pitch, but keep yaw
  437. float r, p, y;
  438. dcm.to_euler(&r, &p, &y);
  439. dcm.from_euler(0.0f, 0.0f, y);
  440. // no X or Y movement
  441. velocity_ef.x = 0.0f;
  442. velocity_ef.y = 0.0f;
  443. if (velocity_ef.z > 0.0f) {
  444. velocity_ef.z = 0.0f;
  445. }
  446. gyro.zero();
  447. use_smoothing = true;
  448. break;
  449. }
  450. case GROUND_BEHAVIOR_FWD_ONLY: {
  451. // zero roll/pitch, but keep yaw
  452. float r, p, y;
  453. dcm.to_euler(&r, &p, &y);
  454. if (velocity_ef.length() < 5) {
  455. // at high speeds don't constrain pitch, otherwise we
  456. // can get stuck in takeoff
  457. p = 0;
  458. } else {
  459. p = MAX(p, 0);
  460. }
  461. dcm.from_euler(0.0f, p, y);
  462. // only fwd movement
  463. Vector3f v_bf = dcm.transposed() * velocity_ef;
  464. v_bf.y = 0.0f;
  465. if (v_bf.x < 0.0f) {
  466. v_bf.x = 0.0f;
  467. }
  468. velocity_ef = dcm * v_bf;
  469. if (velocity_ef.z > 0.0f) {
  470. velocity_ef.z = 0.0f;
  471. }
  472. gyro.zero();
  473. use_smoothing = true;
  474. break;
  475. }
  476. case GROUND_BEHAVIOR_TAILSITTER: {
  477. // point straight up
  478. float r, p, y;
  479. dcm.to_euler(&r, &p, &y);
  480. dcm.from_euler(0.0f, radians(90), y);
  481. // no movement
  482. if (accel_earth.z > -1.1*GRAVITY_MSS) {
  483. velocity_ef.zero();
  484. }
  485. gyro.zero();
  486. use_smoothing = true;
  487. break;
  488. }
  489. }
  490. }
  491. }
  492. /*
  493. update wind vector
  494. */
  495. void Aircraft::update_wind(const struct sitl_input &input)
  496. {
  497. // wind vector in earth frame
  498. wind_ef = Vector3f(cosf(radians(input.wind.direction))*cosf(radians(input.wind.dir_z)),
  499. sinf(radians(input.wind.direction))*cosf(radians(input.wind.dir_z)),
  500. sinf(radians(input.wind.dir_z))) * input.wind.speed;
  501. const float wind_turb = input.wind.turbulence * 10.0f; // scale input.wind.turbulence to match standard deviation when using iir_coef=0.98
  502. const float iir_coef = 0.98f; // filtering high frequencies from turbulence
  503. if (wind_turb > 0 && !on_ground()) {
  504. turbulence_azimuth = turbulence_azimuth + (2 * rand());
  505. turbulence_horizontal_speed =
  506. static_cast<float>(turbulence_horizontal_speed * iir_coef+wind_turb * rand_normal(0, 1) * (1 - iir_coef));
  507. turbulence_vertical_speed = static_cast<float>((turbulence_vertical_speed * iir_coef) + (wind_turb * rand_normal(0, 1) * (1 - iir_coef)));
  508. wind_ef += Vector3f(
  509. cosf(radians(turbulence_azimuth)) * turbulence_horizontal_speed,
  510. sinf(radians(turbulence_azimuth)) * turbulence_horizontal_speed,
  511. turbulence_vertical_speed);
  512. }
  513. }
  514. /*
  515. smooth sensors for kinematic consistancy when we interact with the ground
  516. */
  517. void Aircraft::smooth_sensors(void)
  518. {
  519. uint64_t now = time_now_us;
  520. Vector3f delta_pos = position - smoothing.position;
  521. if (smoothing.last_update_us == 0 || delta_pos.length() > 10) {
  522. smoothing.position = position;
  523. smoothing.rotation_b2e = dcm;
  524. smoothing.accel_body = accel_body;
  525. smoothing.velocity_ef = velocity_ef;
  526. smoothing.gyro = gyro;
  527. smoothing.last_update_us = now;
  528. smoothing.location = location;
  529. printf("Smoothing reset at %.3f\n", now * 1.0e-6f);
  530. return;
  531. }
  532. const float delta_time = (now - smoothing.last_update_us) * 1.0e-6f;
  533. if (delta_time < 0 || delta_time > 0.1) {
  534. return;
  535. }
  536. // calculate required accel to get us to desired position and velocity in the time_constant
  537. const float time_constant = 0.1f;
  538. Vector3f dvel = (velocity_ef - smoothing.velocity_ef) + (delta_pos / time_constant);
  539. Vector3f accel_e = dvel / time_constant + (dcm * accel_body + Vector3f(0.0f, 0.0f, GRAVITY_MSS));
  540. const float accel_limit = 14 * GRAVITY_MSS;
  541. accel_e.x = constrain_float(accel_e.x, -accel_limit, accel_limit);
  542. accel_e.y = constrain_float(accel_e.y, -accel_limit, accel_limit);
  543. accel_e.z = constrain_float(accel_e.z, -accel_limit, accel_limit);
  544. smoothing.accel_body = smoothing.rotation_b2e.transposed() * (accel_e + Vector3f(0.0f, 0.0f, -GRAVITY_MSS));
  545. // calculate rotational rate to get us to desired attitude in time constant
  546. Quaternion desired_q, current_q, error_q;
  547. desired_q.from_rotation_matrix(dcm);
  548. desired_q.normalize();
  549. current_q.from_rotation_matrix(smoothing.rotation_b2e);
  550. current_q.normalize();
  551. error_q = desired_q / current_q;
  552. error_q.normalize();
  553. Vector3f angle_differential;
  554. error_q.to_axis_angle(angle_differential);
  555. smoothing.gyro = gyro + angle_differential / time_constant;
  556. float R, P, Y;
  557. smoothing.rotation_b2e.to_euler(&R, &P, &Y);
  558. float R2, P2, Y2;
  559. dcm.to_euler(&R2, &P2, &Y2);
  560. #if 0
  561. AP::logger().Write("SMOO", "TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2",
  562. "Qffffffffffff",
  563. AP_HAL::micros64(),
  564. degrees(angle_differential.x),
  565. degrees(angle_differential.y),
  566. degrees(angle_differential.z),
  567. delta_pos.x, delta_pos.y, delta_pos.z,
  568. degrees(R), degrees(P), degrees(Y),
  569. degrees(R2), degrees(P2), degrees(Y2));
  570. #endif
  571. // integrate to get new attitude
  572. smoothing.rotation_b2e.rotate(smoothing.gyro * delta_time);
  573. smoothing.rotation_b2e.normalize();
  574. // integrate to get new position
  575. smoothing.velocity_ef += accel_e * delta_time;
  576. smoothing.position += smoothing.velocity_ef * delta_time;
  577. smoothing.location = home;
  578. smoothing.location.offset(smoothing.position.x, smoothing.position.y);
  579. smoothing.location.alt = static_cast<int32_t>(home.alt - smoothing.position.z * 100.0f);
  580. smoothing.last_update_us = now;
  581. smoothing.enabled = true;
  582. }
  583. /*
  584. return a filtered servo input as a value from -1 to 1
  585. servo is assumed to be 1000 to 2000, trim at 1500
  586. */
  587. float Aircraft::filtered_idx(float v, uint8_t idx)
  588. {
  589. if (sitl->servo_speed <= 0) {
  590. return v;
  591. }
  592. const float cutoff = 1.0f / (2 * M_PI * sitl->servo_speed);
  593. servo_filter[idx].set_cutoff_frequency(cutoff);
  594. return servo_filter[idx].apply(v, frame_time_us * 1.0e-6f);
  595. }
  596. /*
  597. return a filtered servo input as a value from -1 to 1
  598. servo is assumed to be 1000 to 2000, trim at 1500
  599. */
  600. float Aircraft::filtered_servo_angle(const struct sitl_input &input, uint8_t idx)
  601. {
  602. const float v = (input.servos[idx] - 1500)/500.0f;
  603. return filtered_idx(v, idx);
  604. }
  605. /*
  606. return a filtered servo input as a value from 0 to 1
  607. servo is assumed to be 1000 to 2000
  608. */
  609. float Aircraft::filtered_servo_range(const struct sitl_input &input, uint8_t idx)
  610. {
  611. const float v = (input.servos[idx] - 1000)/1000.0f;
  612. return filtered_idx(v, idx);
  613. }
  614. // extrapolate sensors by a given delta time in seconds
  615. void Aircraft::extrapolate_sensors(float delta_time)
  616. {
  617. Vector3f accel_earth = dcm * accel_body;
  618. accel_earth.z += GRAVITY_MSS;
  619. dcm.rotate(gyro * delta_time);
  620. dcm.normalize();
  621. // work out acceleration as seen by the accelerometers. It sees the kinematic
  622. // acceleration (ie. real movement), plus gravity
  623. accel_body = dcm.transposed() * (accel_earth + Vector3f(0,0,-GRAVITY_MSS));
  624. // new velocity and position vectors
  625. velocity_ef += accel_earth * delta_time;
  626. position += velocity_ef * delta_time;
  627. velocity_air_ef = velocity_ef + wind_ef;
  628. velocity_air_bf = dcm.transposed() * velocity_air_ef;
  629. }
  630. void Aircraft::update_external_payload(const struct sitl_input &input)
  631. {
  632. external_payload_mass = 0;
  633. // update sprayer
  634. if (sprayer && sprayer->is_enabled()) {
  635. sprayer->update(input);
  636. external_payload_mass += sprayer->payload_mass();
  637. }
  638. // update grippers
  639. if (gripper && gripper->is_enabled()) {
  640. gripper->set_alt(hagl());
  641. gripper->update(input);
  642. external_payload_mass += gripper->payload_mass();
  643. }
  644. if (gripper_epm && gripper_epm->is_enabled()) {
  645. gripper_epm->update(input);
  646. external_payload_mass += gripper_epm->payload_mass();
  647. }
  648. // update parachute
  649. if (parachute && parachute->is_enabled()) {
  650. parachute->update(input);
  651. // TODO: add drag to vehicle, presumably proportional to velocity
  652. }
  653. if (precland && precland->is_enabled()) {
  654. precland->update(get_location(), get_position());
  655. }
  656. }
  657. void Aircraft::add_shove_forces(Vector3f &rot_accel, Vector3f &body_accel)
  658. {
  659. const uint32_t now = AP_HAL::millis();
  660. if (sitl == nullptr) {
  661. return;
  662. }
  663. if (sitl->shove.t == 0) {
  664. return;
  665. }
  666. if (sitl->shove.start_ms == 0) {
  667. sitl->shove.start_ms = now;
  668. }
  669. if (now - sitl->shove.start_ms < uint32_t(sitl->shove.t)) {
  670. // FIXME: can we get a vector operation here instead?
  671. body_accel.x += sitl->shove.x;
  672. body_accel.y += sitl->shove.y;
  673. body_accel.z += sitl->shove.z;
  674. } else {
  675. sitl->shove.start_ms = 0;
  676. sitl->shove.t = 0;
  677. }
  678. }
  679. void Aircraft::add_twist_forces(Vector3f &rot_accel)
  680. {
  681. if (sitl == nullptr) {
  682. return;
  683. }
  684. if (sitl->gnd_behav != -1) {
  685. ground_behavior = (GroundBehaviour)sitl->gnd_behav.get();
  686. }
  687. const uint32_t now = AP_HAL::millis();
  688. if (sitl == nullptr) {
  689. return;
  690. }
  691. if (sitl->twist.t == 0) {
  692. return;
  693. }
  694. if (sitl->twist.start_ms == 0) {
  695. sitl->twist.start_ms = now;
  696. }
  697. if (now - sitl->twist.start_ms < uint32_t(sitl->twist.t)) {
  698. // FIXME: can we get a vector operation here instead?
  699. rot_accel.x += sitl->twist.x;
  700. rot_accel.y += sitl->twist.y;
  701. rot_accel.z += sitl->twist.z;
  702. } else {
  703. sitl->twist.start_ms = 0;
  704. sitl->twist.t = 0;
  705. }
  706. }