AP_AHRS.cpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531
  1. /*
  2. APM_AHRS.cpp
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  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. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. #include "AP_AHRS.h"
  15. #include "AP_AHRS_View.h"
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_Logger/AP_Logger.h>
  18. #include <AP_GPS/AP_GPS.h>
  19. #include <AP_Baro/AP_Baro.h>
  20. #include <AP_NMEA_Output/AP_NMEA_Output.h>
  21. extern const AP_HAL::HAL& hal;
  22. // table of user settable parameters
  23. const AP_Param::GroupInfo AP_AHRS::var_info[] = {
  24. // index 0 and 1 are for old parameters that are no longer not used
  25. // @Param: GPS_GAIN
  26. // @DisplayName: AHRS GPS gain
  27. // @Description: This controls how much to use the GPS to correct the attitude. This should never be set to zero for a plane as it would result in the plane losing control in turns. For a plane please use the default value of 1.0.
  28. // @Range: 0.0 1.0
  29. // @Increment: .01
  30. // @User: Advanced
  31. AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0f),
  32. // @Param: GPS_USE
  33. // @DisplayName: AHRS use GPS for navigation
  34. // @Description: This controls whether to use dead-reckoning or GPS based navigation. If set to 0 then the GPS won't be used for navigation, and only dead reckoning will be used. A value of zero should never be used for normal flight. Currently this affects only the DCM-based AHRS: the EKF uses GPS whenever it is available.
  35. // @Values: 0:Disabled,1:Enabled
  36. // @User: Advanced
  37. AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, 1),
  38. // @Param: YAW_P
  39. // @DisplayName: Yaw P
  40. // @Description: This controls the weight the compass or GPS has on the heading. A higher value means the heading will track the yaw source (GPS or compass) more rapidly.
  41. // @Range: 0.1 0.4
  42. // @Increment: .01
  43. // @User: Advanced
  44. AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.2f),
  45. // @Param: RP_P
  46. // @DisplayName: AHRS RP_P
  47. // @Description: This controls how fast the accelerometers correct the attitude
  48. // @Range: 0.1 0.4
  49. // @Increment: .01
  50. // @User: Advanced
  51. AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.2f),
  52. // @Param: WIND_MAX
  53. // @DisplayName: Maximum wind
  54. // @Description: This sets the maximum allowable difference between ground speed and airspeed. This allows the plane to cope with a failing airspeed sensor. A value of zero means to use the airspeed as is.
  55. // @Range: 0 127
  56. // @Units: m/s
  57. // @Increment: 1
  58. // @User: Advanced
  59. AP_GROUPINFO("WIND_MAX", 6, AP_AHRS, _wind_max, 0.0f),
  60. // NOTE: 7 was BARO_USE
  61. // @Param: TRIM_X
  62. // @DisplayName: AHRS Trim Roll
  63. // @Description: Compensates for the roll angle difference between the control board and the frame. Positive values make the vehicle roll right.
  64. // @Units: rad
  65. // @Range: -0.1745 +0.1745
  66. // @Increment: 0.01
  67. // @User: Standard
  68. // @Param: TRIM_Y
  69. // @DisplayName: AHRS Trim Pitch
  70. // @Description: Compensates for the pitch angle difference between the control board and the frame. Positive values make the vehicle pitch up/back.
  71. // @Units: rad
  72. // @Range: -0.1745 +0.1745
  73. // @Increment: 0.01
  74. // @User: Standard
  75. // @Param: TRIM_Z
  76. // @DisplayName: AHRS Trim Yaw
  77. // @Description: Not Used
  78. // @Units: rad
  79. // @Range: -0.1745 +0.1745
  80. // @Increment: 0.01
  81. // @User: Advanced
  82. AP_GROUPINFO("TRIM", 8, AP_AHRS, _trim, 0),
  83. // @Param: ORIENTATION
  84. // @DisplayName: Board Orientation
  85. // @Description: Overall board orientation relative to the standard orientation for the board type. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. This option takes affect on next boot. After changing you will need to re-level your vehicle.
  86. // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315,100:Custom
  87. // @User: Advanced
  88. AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0),
  89. // @Param: COMP_BETA
  90. // @DisplayName: AHRS Velocity Complementary Filter Beta Coefficient
  91. // @Description: This controls the time constant for the cross-over frequency used to fuse AHRS (airspeed and heading) and GPS data to estimate ground velocity. Time constant is 0.1/beta. A larger time constant will use GPS data less and a small time constant will use air data less.
  92. // @Range: 0.001 0.5
  93. // @Increment: .01
  94. // @User: Advanced
  95. AP_GROUPINFO("COMP_BETA", 10, AP_AHRS, beta, 0.1f),
  96. // @Param: GPS_MINSATS
  97. // @DisplayName: AHRS GPS Minimum satellites
  98. // @Description: Minimum number of satellites visible to use GPS for velocity based corrections attitude correction. This defaults to 6, which is about the point at which the velocity numbers from a GPS become too unreliable for accurate correction of the accelerometers.
  99. // @Range: 0 10
  100. // @Increment: 1
  101. // @User: Advanced
  102. AP_GROUPINFO("GPS_MINSATS", 11, AP_AHRS, _gps_minsats, 6),
  103. // NOTE: index 12 was for GPS_DELAY, but now removed, fixed delay
  104. // of 1 was found to be the best choice
  105. // 13 was the old EKF_USE
  106. #if AP_AHRS_NAVEKF_AVAILABLE
  107. // @Param: EKF_TYPE
  108. // @DisplayName: Use NavEKF Kalman filter for attitude and position estimation
  109. // @Description: This controls which NavEKF Kalman filter version is used for attitude and position estimation
  110. // @Values: 0:Disabled,2:Enable EKF2,3:Enable EKF3
  111. // @User: Advanced
  112. AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, 2),
  113. #endif
  114. // @Param: CUSTOM_ROLL
  115. // @DisplayName: Board orientation roll offset
  116. // @Description: Autopilot mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
  117. // @Range: -180 180
  118. // @Units: deg
  119. // @Increment: 1
  120. // @User: Advanced
  121. AP_GROUPINFO("CUSTOM_ROLL", 15, AP_AHRS, _custom_roll, 0),
  122. // @Param: CUSTOM_PIT
  123. // @DisplayName: Board orientation pitch offset
  124. // @Description: Autopilot mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
  125. // @Range: -180 180
  126. // @Units: deg
  127. // @Increment: 1
  128. // @User: Advanced
  129. AP_GROUPINFO("CUSTOM_PIT", 16, AP_AHRS, _custom_pitch, 0),
  130. // @Param: CUSTOM_YAW
  131. // @DisplayName: Board orientation yaw offset
  132. // @Description: Autopilot mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
  133. // @Range: -180 180
  134. // @Units: deg
  135. // @Increment: 1
  136. // @User: Advanced
  137. AP_GROUPINFO("CUSTOM_YAW", 17, AP_AHRS, _custom_yaw, 0),
  138. AP_GROUPEND
  139. };
  140. // init sets up INS board orientation
  141. void AP_AHRS::init()
  142. {
  143. update_orientation();
  144. #if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
  145. _nmea_out = AP_NMEA_Output::probe();
  146. #endif
  147. }
  148. // return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
  149. Vector3f AP_AHRS::get_gyro_latest(void) const
  150. {
  151. const uint8_t primary_gyro = get_primary_gyro_index();
  152. return AP::ins().get_gyro(primary_gyro) + get_gyro_drift();
  153. }
  154. // return airspeed estimate if available
  155. bool AP_AHRS::airspeed_estimate(float *airspeed_ret) const
  156. {
  157. if (airspeed_sensor_enabled()) {
  158. *airspeed_ret = _airspeed->get_airspeed();
  159. if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
  160. // constrain the airspeed by the ground speed
  161. // and AHRS_WIND_MAX
  162. const float gnd_speed = AP::gps().ground_speed();
  163. float true_airspeed = *airspeed_ret * get_EAS2TAS();
  164. true_airspeed = constrain_float(true_airspeed,
  165. gnd_speed - _wind_max,
  166. gnd_speed + _wind_max);
  167. *airspeed_ret = true_airspeed / get_EAS2TAS();
  168. }
  169. return true;
  170. }
  171. return false;
  172. }
  173. // set_trim
  174. void AP_AHRS::set_trim(const Vector3f &new_trim)
  175. {
  176. Vector3f trim;
  177. trim.x = constrain_float(new_trim.x, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
  178. trim.y = constrain_float(new_trim.y, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
  179. _trim.set_and_save(trim);
  180. }
  181. // add_trim - adjust the roll and pitch trim up to a total of 10 degrees
  182. void AP_AHRS::add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom)
  183. {
  184. Vector3f trim = _trim.get();
  185. // add new trim
  186. trim.x = constrain_float(trim.x + roll_in_radians, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
  187. trim.y = constrain_float(trim.y + pitch_in_radians, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
  188. // set new trim values
  189. _trim.set(trim);
  190. // save to eeprom
  191. if( save_to_eeprom ) {
  192. _trim.save();
  193. }
  194. }
  195. // Set the board mounting orientation, may be called while disarmed
  196. void AP_AHRS::update_orientation()
  197. {
  198. const enum Rotation orientation = (enum Rotation)_board_orientation.get();
  199. if (orientation != ROTATION_CUSTOM) {
  200. AP::ins().set_board_orientation(orientation);
  201. if (_compass != nullptr) {
  202. _compass->set_board_orientation(orientation);
  203. }
  204. } else {
  205. _custom_rotation.from_euler(radians(_custom_roll), radians(_custom_pitch), radians(_custom_yaw));
  206. AP::ins().set_board_orientation(orientation, &_custom_rotation);
  207. if (_compass != nullptr) {
  208. _compass->set_board_orientation(orientation, &_custom_rotation);
  209. }
  210. }
  211. }
  212. // return a ground speed estimate in m/s
  213. Vector2f AP_AHRS::groundspeed_vector(void)
  214. {
  215. // Generate estimate of ground speed vector using air data system
  216. Vector2f gndVelADS;
  217. Vector2f gndVelGPS;
  218. float airspeed = 0;
  219. const bool gotAirspeed = airspeed_estimate_true(&airspeed);
  220. const bool gotGPS = (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D);
  221. if (gotAirspeed) {
  222. const Vector3f wind = wind_estimate();
  223. const Vector2f wind2d(wind.x, wind.y);
  224. const Vector2f airspeed_vector(_cos_yaw * airspeed, _sin_yaw * airspeed);
  225. gndVelADS = airspeed_vector + wind2d;
  226. }
  227. // Generate estimate of ground speed vector using GPS
  228. if (gotGPS) {
  229. const float cog = radians(AP::gps().ground_course_cd()*0.01f);
  230. gndVelGPS = Vector2f(cosf(cog), sinf(cog)) * AP::gps().ground_speed();
  231. }
  232. // If both ADS and GPS data is available, apply a complementary filter
  233. if (gotAirspeed && gotGPS) {
  234. // The LPF is applied to the GPS and the HPF is applied to the air data estimate
  235. // before the two are summed
  236. //Define filter coefficients
  237. // alpha and beta must sum to one
  238. // beta = dt/Tau, where
  239. // dt = filter time step (0.1 sec if called by nav loop)
  240. // Tau = cross-over time constant (nominal 2 seconds)
  241. // More lag on GPS requires Tau to be bigger, less lag allows it to be smaller
  242. // To-Do - set Tau as a function of GPS lag.
  243. const float alpha = 1.0f - beta;
  244. // Run LP filters
  245. _lp = gndVelGPS * beta + _lp * alpha;
  246. // Run HP filters
  247. _hp = (gndVelADS - _lastGndVelADS) + _hp * alpha;
  248. // Save the current ADS ground vector for the next time step
  249. _lastGndVelADS = gndVelADS;
  250. // Sum the HP and LP filter outputs
  251. return _hp + _lp;
  252. }
  253. // Only ADS data is available return ADS estimate
  254. if (gotAirspeed && !gotGPS) {
  255. return gndVelADS;
  256. }
  257. // Only GPS data is available so return GPS estimate
  258. if (!gotAirspeed && gotGPS) {
  259. return gndVelGPS;
  260. }
  261. if (airspeed > 0) {
  262. // we have a rough airspeed, and we have a yaw. For
  263. // dead-reckoning purposes we can create a estimated
  264. // groundspeed vector
  265. Vector2f ret(cosf(yaw), sinf(yaw));
  266. ret *= airspeed;
  267. // adjust for estimated wind
  268. const Vector3f wind = wind_estimate();
  269. ret.x += wind.x;
  270. ret.y += wind.y;
  271. return ret;
  272. }
  273. return Vector2f(0.0f, 0.0f);
  274. }
  275. /*
  276. calculate sin and cos of roll/pitch/yaw from a body_to_ned rotation matrix
  277. */
  278. void AP_AHRS::calc_trig(const Matrix3f &rot,
  279. float &cr, float &cp, float &cy,
  280. float &sr, float &sp, float &sy) const
  281. {
  282. Vector2f yaw_vector(rot.a.x, rot.b.x);
  283. if (fabsf(yaw_vector.x) > 0 ||
  284. fabsf(yaw_vector.y) > 0) {
  285. yaw_vector.normalize();
  286. }
  287. sy = constrain_float(yaw_vector.y, -1.0f, 1.0f);
  288. cy = constrain_float(yaw_vector.x, -1.0f, 1.0f);
  289. // sanity checks
  290. if (yaw_vector.is_inf() || yaw_vector.is_nan()) {
  291. sy = 0.0f;
  292. cy = 1.0f;
  293. }
  294. const float cx2 = rot.c.x * rot.c.x;
  295. if (cx2 >= 1.0f) {
  296. cp = 0;
  297. cr = 1.0f;
  298. } else {
  299. cp = safe_sqrt(1 - cx2);
  300. cr = rot.c.z / cp;
  301. }
  302. cp = constrain_float(cp, 0.0f, 1.0f);
  303. cr = constrain_float(cr, -1.0f, 1.0f); // this relies on constrain_float() of infinity doing the right thing
  304. sp = -rot.c.x;
  305. if (!is_zero(cp)) {
  306. sr = rot.c.y / cp;
  307. }
  308. if (is_zero(cp) || isinf(cr) || isnan(cr) || isinf(sr) || isnan(sr)) {
  309. float r, p, y;
  310. rot.to_euler(&r, &p, &y);
  311. cr = cosf(r);
  312. sr = sinf(r);
  313. }
  314. }
  315. // update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
  316. // should be called after _dcm_matrix is updated
  317. void AP_AHRS::update_trig(void)
  318. {
  319. if (_last_trim != _trim.get()) {
  320. _last_trim = _trim.get();
  321. _rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, 0.0f);
  322. _rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();
  323. }
  324. calc_trig(get_rotation_body_to_ned(),
  325. _cos_roll, _cos_pitch, _cos_yaw,
  326. _sin_roll, _sin_pitch, _sin_yaw);
  327. }
  328. /*
  329. update the centi-degree values
  330. */
  331. void AP_AHRS::update_cd_values(void)
  332. {
  333. roll_sensor = degrees(roll) * 100;
  334. pitch_sensor = degrees(pitch) * 100;
  335. yaw_sensor = degrees(yaw) * 100;
  336. if (yaw_sensor < 0)
  337. yaw_sensor += 36000;
  338. }
  339. /*
  340. create a rotated view of AP_AHRS with optional pitch trim
  341. */
  342. AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg)
  343. {
  344. if (_view != nullptr) {
  345. // can only have one
  346. return nullptr;
  347. }
  348. _view = new AP_AHRS_View(*this, rotation, pitch_trim_deg);
  349. return _view;
  350. }
  351. /*
  352. * Update AOA and SSA estimation based on airspeed, velocity vector and wind vector
  353. *
  354. * Based on:
  355. * "On estimation of wind velocity, angle-of-attack and sideslip angle of small UAVs using standard sensors" by
  356. * Tor A. Johansen, Andrea Cristofaro, Kim Sorensen, Jakob M. Hansen, Thor I. Fossen
  357. *
  358. * "Multi-Stage Fusion Algorithm for Estimation of Aerodynamic Angles in Mini Aerial Vehicle" by
  359. * C.Ramprasadh and Hemendra Arya
  360. *
  361. * "ANGLE OF ATTACK AND SIDESLIP ESTIMATION USING AN INERTIAL REFERENCE PLATFORM" by
  362. * JOSEPH E. ZEIS, JR., CAPTAIN, USAF
  363. */
  364. void AP_AHRS::update_AOA_SSA(void)
  365. {
  366. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  367. const uint32_t now = AP_HAL::millis();
  368. if (now - _last_AOA_update_ms < 50) {
  369. // don't update at more than 20Hz
  370. return;
  371. }
  372. _last_AOA_update_ms = now;
  373. Vector3f aoa_velocity, aoa_wind;
  374. // get velocity and wind
  375. if (get_velocity_NED(aoa_velocity) == false) {
  376. return;
  377. }
  378. aoa_wind = wind_estimate();
  379. // Rotate vectors to the body frame and calculate velocity and wind
  380. const Matrix3f &rot = get_rotation_body_to_ned();
  381. aoa_velocity = rot.mul_transpose(aoa_velocity);
  382. aoa_wind = rot.mul_transpose(aoa_wind);
  383. // calculate relative velocity in body coordinates
  384. aoa_velocity = aoa_velocity - aoa_wind;
  385. const float vel_len = aoa_velocity.length();
  386. // do not calculate if speed is too low
  387. if (vel_len < 2.0) {
  388. _AOA = 0;
  389. _SSA = 0;
  390. return;
  391. }
  392. // Calculate AOA and SSA
  393. if (aoa_velocity.x > 0) {
  394. _AOA = degrees(atanf(aoa_velocity.z / aoa_velocity.x));
  395. } else {
  396. _AOA = 0;
  397. }
  398. _SSA = degrees(safe_asin(aoa_velocity.y / vel_len));
  399. #endif
  400. }
  401. // return current AOA
  402. float AP_AHRS::getAOA(void)
  403. {
  404. update_AOA_SSA();
  405. return _AOA;
  406. }
  407. // return calculated SSA
  408. float AP_AHRS::getSSA(void)
  409. {
  410. update_AOA_SSA();
  411. return _SSA;
  412. }
  413. // rotate a 2D vector from earth frame to body frame
  414. Vector2f AP_AHRS::rotate_earth_to_body2D(const Vector2f &ef) const
  415. {
  416. return Vector2f(ef.x * _cos_yaw + ef.y * _sin_yaw,
  417. -ef.x * _sin_yaw + ef.y * _cos_yaw);
  418. }
  419. // rotate a 2D vector from earth frame to body frame
  420. Vector2f AP_AHRS::rotate_body_to_earth2D(const Vector2f &bf) const
  421. {
  422. return Vector2f(bf.x * _cos_yaw - bf.y * _sin_yaw,
  423. bf.x * _sin_yaw + bf.y * _cos_yaw);
  424. }
  425. // log ahrs home and EKF origin
  426. void AP_AHRS::Log_Write_Home_And_Origin()
  427. {
  428. AP_Logger *logger = AP_Logger::get_singleton();
  429. if (logger == nullptr) {
  430. return;
  431. }
  432. #if AP_AHRS_NAVEKF_AVAILABLE
  433. Location ekf_orig;
  434. if (get_origin(ekf_orig)) {
  435. logger->Write_Origin(LogOriginType::ekf_origin, ekf_orig);
  436. }
  437. #endif
  438. if (home_is_set()) {
  439. logger->Write_Origin(LogOriginType::ahrs_home, _home);
  440. }
  441. }
  442. // get apparent to true airspeed ratio
  443. float AP_AHRS::get_EAS2TAS(void) const {
  444. return AP::baro().get_EAS2TAS();
  445. }
  446. void AP_AHRS::update_nmea_out()
  447. {
  448. #if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
  449. if (_nmea_out != nullptr) {
  450. _nmea_out->update();
  451. }
  452. #endif
  453. }
  454. // singleton instance
  455. AP_AHRS *AP_AHRS::_singleton;
  456. namespace AP {
  457. AP_AHRS &ahrs()
  458. {
  459. return *AP_AHRS::get_singleton();
  460. }
  461. }