AP_NavEKF2_Measurements.cpp 44 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_NavEKF2.h"
  3. #include "AP_NavEKF2_core.h"
  4. #include <AP_AHRS/AP_AHRS.h>
  5. #include <AP_Vehicle/AP_Vehicle.h>
  6. #include <GCS_MAVLink/GCS.h>
  7. #include <AP_RangeFinder/RangeFinder_Backend.h>
  8. #include <AP_GPS/AP_GPS.h>
  9. #include <AP_Baro/AP_Baro.h>
  10. #include <stdio.h>
  11. extern const AP_HAL::HAL& hal;
  12. /********************************************************
  13. * OPT FLOW AND RANGE FINDER *
  14. ********************************************************/
  15. // Read the range finder and take new measurements if available
  16. // Apply a median filter
  17. void NavEKF2_core::readRangeFinder(void)
  18. {
  19. uint8_t midIndex;
  20. uint8_t maxIndex;
  21. uint8_t minIndex;
  22. // get theoretical correct range when the vehicle is on the ground
  23. // don't allow range to go below 5cm because this can cause problems with optical flow processing
  24. rngOnGnd = MAX(frontend->_rng.ground_clearance_cm_orient(ROTATION_PITCH_270) * 0.01f, 0.05f);
  25. // read range finder at 20Hz
  26. // TODO better way of knowing if it has new data
  27. if ((imuSampleTime_ms - lastRngMeasTime_ms) > 50) {
  28. // reset the timer used to control the measurement rate
  29. lastRngMeasTime_ms = imuSampleTime_ms;
  30. // store samples and sample time into a ring buffer if valid
  31. // use data from two range finders if available
  32. for (uint8_t sensorIndex = 0; sensorIndex <= 1; sensorIndex++) {
  33. AP_RangeFinder_Backend *sensor = frontend->_rng.get_backend(sensorIndex);
  34. if (sensor == nullptr) {
  35. continue;
  36. }
  37. if ((sensor->orientation() == ROTATION_PITCH_270) && (sensor->status() == RangeFinder::RangeFinder_Good)) {
  38. rngMeasIndex[sensorIndex] ++;
  39. if (rngMeasIndex[sensorIndex] > 2) {
  40. rngMeasIndex[sensorIndex] = 0;
  41. }
  42. storedRngMeasTime_ms[sensorIndex][rngMeasIndex[sensorIndex]] = imuSampleTime_ms - 25;
  43. storedRngMeas[sensorIndex][rngMeasIndex[sensorIndex]] = sensor->distance_cm() * 0.01f;
  44. }
  45. // check for three fresh samples
  46. bool sampleFresh[2][3] = {};
  47. for (uint8_t index = 0; index <= 2; index++) {
  48. sampleFresh[sensorIndex][index] = (imuSampleTime_ms - storedRngMeasTime_ms[sensorIndex][index]) < 500;
  49. }
  50. // find the median value if we have three fresh samples
  51. if (sampleFresh[sensorIndex][0] && sampleFresh[sensorIndex][1] && sampleFresh[sensorIndex][2]) {
  52. if (storedRngMeas[sensorIndex][0] > storedRngMeas[sensorIndex][1]) {
  53. minIndex = 1;
  54. maxIndex = 0;
  55. } else {
  56. minIndex = 0;
  57. maxIndex = 1;
  58. }
  59. if (storedRngMeas[sensorIndex][2] > storedRngMeas[sensorIndex][maxIndex]) {
  60. midIndex = maxIndex;
  61. } else if (storedRngMeas[sensorIndex][2] < storedRngMeas[sensorIndex][minIndex]) {
  62. midIndex = minIndex;
  63. } else {
  64. midIndex = 2;
  65. }
  66. // don't allow time to go backwards
  67. if (storedRngMeasTime_ms[sensorIndex][midIndex] > rangeDataNew.time_ms) {
  68. rangeDataNew.time_ms = storedRngMeasTime_ms[sensorIndex][midIndex];
  69. }
  70. // limit the measured range to be no less than the on-ground range
  71. rangeDataNew.rng = MAX(storedRngMeas[sensorIndex][midIndex],rngOnGnd);
  72. // get position in body frame for the current sensor
  73. rangeDataNew.sensor_idx = sensorIndex;
  74. // write data to buffer with time stamp to be fused when the fusion time horizon catches up with it
  75. storedRange.push(rangeDataNew);
  76. // indicate we have updated the measurement
  77. rngValidMeaTime_ms = imuSampleTime_ms;
  78. } else if (!takeOffDetected && ((imuSampleTime_ms - rngValidMeaTime_ms) > 200)) {
  79. // before takeoff we assume on-ground range value if there is no data
  80. rangeDataNew.time_ms = imuSampleTime_ms;
  81. rangeDataNew.rng = rngOnGnd;
  82. rangeDataNew.time_ms = imuSampleTime_ms;
  83. // don't allow time to go backwards
  84. if (imuSampleTime_ms > rangeDataNew.time_ms) {
  85. rangeDataNew.time_ms = imuSampleTime_ms;
  86. }
  87. // write data to buffer with time stamp to be fused when the fusion time horizon catches up with it
  88. storedRange.push(rangeDataNew);
  89. // indicate we have updated the measurement
  90. rngValidMeaTime_ms = imuSampleTime_ms;
  91. }
  92. }
  93. }
  94. }
  95. // write the raw optical flow measurements
  96. // this needs to be called externally.
  97. void NavEKF2_core::writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset)
  98. {
  99. // The raw measurements need to be optical flow rates in radians/second averaged across the time since the last update
  100. // The PX4Flow sensor outputs flow rates with the following axis and sign conventions:
  101. // A positive X rate is produced by a positive sensor rotation about the X axis
  102. // A positive Y rate is produced by a positive sensor rotation about the Y axis
  103. // This filter uses a different definition of optical flow rates to the sensor with a positive optical flow rate produced by a
  104. // negative rotation about that axis. For example a positive rotation of the flight vehicle about its X (roll) axis would produce a negative X flow rate
  105. flowMeaTime_ms = imuSampleTime_ms;
  106. // calculate bias errors on flow sensor gyro rates, but protect against spikes in data
  107. // reset the accumulated body delta angle and time
  108. // don't do the calculation if not enough time lapsed for a reliable body rate measurement
  109. if (delTimeOF > 0.01f) {
  110. flowGyroBias.x = 0.99f * flowGyroBias.x + 0.01f * constrain_float((rawGyroRates.x - delAngBodyOF.x/delTimeOF),-0.1f,0.1f);
  111. flowGyroBias.y = 0.99f * flowGyroBias.y + 0.01f * constrain_float((rawGyroRates.y - delAngBodyOF.y/delTimeOF),-0.1f,0.1f);
  112. delAngBodyOF.zero();
  113. delTimeOF = 0.0f;
  114. }
  115. // by definition if this function is called, then flow measurements have been provided so we
  116. // need to run the optical flow takeoff detection
  117. detectOptFlowTakeoff();
  118. // calculate rotation matrices at mid sample time for flow observations
  119. stateStruct.quat.rotation_matrix(Tbn_flow);
  120. // don't use data with a low quality indicator or extreme rates (helps catch corrupt sensor data)
  121. if ((rawFlowQuality > 0) && rawFlowRates.length() < 4.2f && rawGyroRates.length() < 4.2f) {
  122. // correct flow sensor body rates for bias and write
  123. ofDataNew.bodyRadXYZ.x = rawGyroRates.x - flowGyroBias.x;
  124. ofDataNew.bodyRadXYZ.y = rawGyroRates.y - flowGyroBias.y;
  125. // the sensor interface doesn't provide a z axis rate so use the rate from the nav sensor instead
  126. if (delTimeOF > 0.001f) {
  127. // first preference is to use the rate averaged over the same sampling period as the flow sensor
  128. ofDataNew.bodyRadXYZ.z = delAngBodyOF.z / delTimeOF;
  129. } else if (imuDataNew.delAngDT > 0.001f){
  130. // second preference is to use most recent IMU data
  131. ofDataNew.bodyRadXYZ.z = imuDataNew.delAng.z / imuDataNew.delAngDT;
  132. } else {
  133. // third preference is use zero
  134. ofDataNew.bodyRadXYZ.z = 0.0f;
  135. }
  136. // write uncorrected flow rate measurements
  137. // note correction for different axis and sign conventions used by the px4flow sensor
  138. ofDataNew.flowRadXY = - rawFlowRates; // raw (non motion compensated) optical flow angular rate about the X axis (rad/sec)
  139. // write the flow sensor position in body frame
  140. ofDataNew.body_offset = &posOffset;
  141. // write flow rate measurements corrected for body rates
  142. ofDataNew.flowRadXYcomp.x = ofDataNew.flowRadXY.x + ofDataNew.bodyRadXYZ.x;
  143. ofDataNew.flowRadXYcomp.y = ofDataNew.flowRadXY.y + ofDataNew.bodyRadXYZ.y;
  144. // record time last observation was received so we can detect loss of data elsewhere
  145. flowValidMeaTime_ms = imuSampleTime_ms;
  146. // estimate sample time of the measurement
  147. ofDataNew.time_ms = imuSampleTime_ms - frontend->_flowDelay_ms - frontend->flowTimeDeltaAvg_ms/2;
  148. // Correct for the average intersampling delay due to the filter updaterate
  149. ofDataNew.time_ms -= localFilterTimeStep_ms/2;
  150. // Prevent time delay exceeding age of oldest IMU data in the buffer
  151. ofDataNew.time_ms = MAX(ofDataNew.time_ms,imuDataDelayed.time_ms);
  152. // Save data to buffer
  153. storedOF.push(ofDataNew);
  154. // Check for data at the fusion time horizon
  155. flowDataToFuse = storedOF.recall(ofDataDelayed, imuDataDelayed.time_ms);
  156. }
  157. }
  158. /********************************************************
  159. * MAGNETOMETER *
  160. ********************************************************/
  161. // check for new magnetometer data and update store measurements if available
  162. void NavEKF2_core::readMagData()
  163. {
  164. if (!_ahrs->get_compass()) {
  165. allMagSensorsFailed = true;
  166. return;
  167. }
  168. // If we are a vehicle with a sideslip constraint to aid yaw estimation and we have timed out on our last avialable
  169. // magnetometer, then declare the magnetometers as failed for this flight
  170. uint8_t maxCount = _ahrs->get_compass()->get_count();
  171. if (allMagSensorsFailed || (magTimeout && assume_zero_sideslip() && magSelectIndex >= maxCount-1 && inFlight)) {
  172. allMagSensorsFailed = true;
  173. return;
  174. }
  175. if (_ahrs->get_compass()->learn_offsets_enabled()) {
  176. // while learning offsets keep all mag states reset
  177. InitialiseVariablesMag();
  178. wasLearningCompass_ms = imuSampleTime_ms;
  179. } else if (wasLearningCompass_ms != 0 && imuSampleTime_ms - wasLearningCompass_ms > 1000) {
  180. wasLearningCompass_ms = 0;
  181. // force a new yaw alignment 1s after learning completes. The
  182. // delay is to ensure any buffered mag samples are discarded
  183. yawAlignComplete = false;
  184. InitialiseVariablesMag();
  185. }
  186. // do not accept new compass data faster than 14Hz (nominal rate is 10Hz) to prevent high processor loading
  187. // because magnetometer fusion is an expensive step and we could overflow the FIFO buffer
  188. if (use_compass() && _ahrs->get_compass()->last_update_usec() - lastMagUpdate_us > 70000) {
  189. frontend->logging.log_compass = true;
  190. // If the magnetometer has timed out (been rejected too long) we find another magnetometer to use if available
  191. // Don't do this if we are on the ground because there can be magnetic interference and we need to know if there is a problem
  192. // before taking off. Don't do this within the first 30 seconds from startup because the yaw error could be due to large yaw gyro bias affsets
  193. if (magTimeout && (maxCount > 1) && !onGround && imuSampleTime_ms - ekfStartTime_ms > 30000) {
  194. // search through the list of magnetometers
  195. for (uint8_t i=1; i<maxCount; i++) {
  196. uint8_t tempIndex = magSelectIndex + i;
  197. // loop back to the start index if we have exceeded the bounds
  198. if (tempIndex >= maxCount) {
  199. tempIndex -= maxCount;
  200. }
  201. // if the magnetometer is allowed to be used for yaw and has a different index, we start using it
  202. if (_ahrs->get_compass()->use_for_yaw(tempIndex) && tempIndex != magSelectIndex) {
  203. magSelectIndex = tempIndex;
  204. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u switching to compass %u",(unsigned)imu_index,magSelectIndex);
  205. // reset the timeout flag and timer
  206. magTimeout = false;
  207. lastHealthyMagTime_ms = imuSampleTime_ms;
  208. // zero the learned magnetometer bias states
  209. stateStruct.body_magfield.zero();
  210. // clear the measurement buffer
  211. storedMag.reset();
  212. // clear the data waiting flag so that we do not use any data pending from the previous sensor
  213. magDataToFuse = false;
  214. // request a reset of the magnetic field states
  215. magStateResetRequest = true;
  216. // declare the field unlearned so that the reset request will be obeyed
  217. magFieldLearned = false;
  218. break;
  219. }
  220. }
  221. }
  222. // detect changes to magnetometer offset parameters and reset states
  223. Vector3f nowMagOffsets = _ahrs->get_compass()->get_offsets(magSelectIndex);
  224. bool changeDetected = lastMagOffsetsValid && (nowMagOffsets != lastMagOffsets);
  225. if (changeDetected) {
  226. // zero the learned magnetometer bias states
  227. stateStruct.body_magfield.zero();
  228. // clear the measurement buffer
  229. storedMag.reset();
  230. }
  231. lastMagOffsets = nowMagOffsets;
  232. lastMagOffsetsValid = true;
  233. // store time of last measurement update
  234. lastMagUpdate_us = _ahrs->get_compass()->last_update_usec(magSelectIndex);
  235. // estimate of time magnetometer measurement was taken, allowing for delays
  236. magDataNew.time_ms = imuSampleTime_ms - frontend->magDelay_ms;
  237. // Correct for the average intersampling delay due to the filter updaterate
  238. magDataNew.time_ms -= localFilterTimeStep_ms/2;
  239. // read compass data and scale to improve numerical conditioning
  240. magDataNew.mag = _ahrs->get_compass()->get_field(magSelectIndex) * 0.001f;
  241. // check for consistent data between magnetometers
  242. consistentMagData = _ahrs->get_compass()->consistent();
  243. // save magnetometer measurement to buffer to be fused later
  244. storedMag.push(magDataNew);
  245. }
  246. }
  247. /********************************************************
  248. * Inertial Measurements *
  249. ********************************************************/
  250. /*
  251. * Read IMU delta angle and delta velocity measurements and downsample to 100Hz
  252. * for storage in the data buffers used by the EKF. If the IMU data arrives at
  253. * lower rate than 100Hz, then no downsampling or upsampling will be performed.
  254. * Downsampling is done using a method that does not introduce coning or sculling
  255. * errors.
  256. */
  257. void NavEKF2_core::readIMUData()
  258. {
  259. const AP_InertialSensor &ins = AP::ins();
  260. // average IMU sampling rate
  261. dtIMUavg = ins.get_loop_delta_t();
  262. // the imu sample time is used as a common time reference throughout the filter
  263. imuSampleTime_ms = AP_HAL::millis();
  264. // use the nominated imu or primary if not available
  265. uint8_t accel_active, gyro_active;
  266. if (ins.use_accel(imu_index)) {
  267. accel_active = imu_index;
  268. } else {
  269. accel_active = ins.get_primary_accel();
  270. }
  271. if (ins.use_gyro(imu_index)) {
  272. gyro_active = imu_index;
  273. } else {
  274. gyro_active = ins.get_primary_gyro();
  275. }
  276. if (gyro_active != gyro_index_active) {
  277. // we are switching active gyro at runtime. Copy over the
  278. // biases we have learned from the previously inactive
  279. // gyro. We don't re-init the bias uncertainty as it should
  280. // have the same uncertainty as the previously active gyro
  281. stateStruct.gyro_bias = inactiveBias[gyro_active].gyro_bias;
  282. gyro_index_active = gyro_active;
  283. // use the gyro scale factor we have previously used on this
  284. // IMU (if any). We don't reset the variances as we don't want
  285. // errors after switching to be mis-assigned to the gyro scale
  286. // factor
  287. stateStruct.gyro_scale = inactiveBias[gyro_active].gyro_scale;
  288. }
  289. if (accel_active != accel_index_active) {
  290. // switch to the learned accel bias for this IMU
  291. stateStruct.accel_zbias = inactiveBias[accel_active].accel_zbias;
  292. accel_index_active = accel_active;
  293. }
  294. // update the inactive bias states
  295. learnInactiveBiases();
  296. readDeltaVelocity(accel_index_active, imuDataNew.delVel, imuDataNew.delVelDT);
  297. accelPosOffset = ins.get_imu_pos_offset(accel_index_active);
  298. imuDataNew.accel_index = accel_index_active;
  299. // Get delta angle data from primary gyro or primary if not available
  300. readDeltaAngle(gyro_index_active, imuDataNew.delAng, imuDataNew.delAngDT);
  301. imuDataNew.gyro_index = gyro_index_active;
  302. // Get current time stamp
  303. imuDataNew.time_ms = imuSampleTime_ms;
  304. // use the most recent IMU index for the downsampled IMU
  305. // data. This isn't strictly correct if we switch IMUs between
  306. // samples
  307. imuDataDownSampledNew.gyro_index = imuDataNew.gyro_index;
  308. imuDataDownSampledNew.accel_index = imuDataNew.accel_index;
  309. // Accumulate the measurement time interval for the delta velocity and angle data
  310. imuDataDownSampledNew.delAngDT += imuDataNew.delAngDT;
  311. imuDataDownSampledNew.delVelDT += imuDataNew.delVelDT;
  312. // Rotate quaternon atitude from previous to new and normalise.
  313. // Accumulation using quaternions prevents introduction of coning errors due to downsampling
  314. imuQuatDownSampleNew.rotate(imuDataNew.delAng);
  315. imuQuatDownSampleNew.normalize();
  316. // Rotate the latest delta velocity into body frame at the start of accumulation
  317. Matrix3f deltaRotMat;
  318. imuQuatDownSampleNew.rotation_matrix(deltaRotMat);
  319. // Apply the delta velocity to the delta velocity accumulator
  320. imuDataDownSampledNew.delVel += deltaRotMat*imuDataNew.delVel;
  321. // Keep track of the number of IMU frames since the last state prediction
  322. framesSincePredict++;
  323. /*
  324. * If the target EKF time step has been accumulated, and the frontend has allowed start of a new predict cycle,
  325. * then store the accumulated IMU data to be used by the state prediction, ignoring the frontend permission if more
  326. * than twice the target time has lapsed. Adjust the target EKF step time threshold to allow for timing jitter in the
  327. * IMU data.
  328. */
  329. if ((dtIMUavg*(float)framesSincePredict >= (EKF_TARGET_DT-(dtIMUavg*0.5)) &&
  330. startPredictEnabled) || (dtIMUavg*(float)framesSincePredict >= 2.0f*EKF_TARGET_DT)) {
  331. // convert the accumulated quaternion to an equivalent delta angle
  332. imuQuatDownSampleNew.to_axis_angle(imuDataDownSampledNew.delAng);
  333. // Time stamp the data
  334. imuDataDownSampledNew.time_ms = imuSampleTime_ms;
  335. // Write data to the FIFO IMU buffer
  336. storedIMU.push_youngest_element(imuDataDownSampledNew);
  337. // calculate the achieved average time step rate for the EKF
  338. float dtNow = constrain_float(0.5f*(imuDataDownSampledNew.delAngDT+imuDataDownSampledNew.delVelDT),0.0f,10.0f*EKF_TARGET_DT);
  339. dtEkfAvg = 0.98f * dtEkfAvg + 0.02f * dtNow;
  340. // zero the accumulated IMU data and quaternion
  341. imuDataDownSampledNew.delAng.zero();
  342. imuDataDownSampledNew.delVel.zero();
  343. imuDataDownSampledNew.delAngDT = 0.0f;
  344. imuDataDownSampledNew.delVelDT = 0.0f;
  345. imuDataDownSampledNew.gyro_index = gyro_index_active;
  346. imuDataDownSampledNew.accel_index = accel_index_active;
  347. imuQuatDownSampleNew[0] = 1.0f;
  348. imuQuatDownSampleNew[3] = imuQuatDownSampleNew[2] = imuQuatDownSampleNew[1] = 0.0f;
  349. // reset the counter used to let the frontend know how many frames have elapsed since we started a new update cycle
  350. framesSincePredict = 0;
  351. // set the flag to let the filter know it has new IMU data and needs to run
  352. runUpdates = true;
  353. // extract the oldest available data from the FIFO buffer
  354. imuDataDelayed = storedIMU.pop_oldest_element();
  355. // protect against delta time going to zero
  356. // TODO - check if calculations can tolerate 0
  357. float minDT = 0.1f*dtEkfAvg;
  358. imuDataDelayed.delAngDT = MAX(imuDataDelayed.delAngDT,minDT);
  359. imuDataDelayed.delVelDT = MAX(imuDataDelayed.delVelDT,minDT);
  360. updateTimingStatistics();
  361. // correct the extracted IMU data for sensor errors
  362. delAngCorrected = imuDataDelayed.delAng;
  363. delVelCorrected = imuDataDelayed.delVel;
  364. correctDeltaAngle(delAngCorrected, imuDataDelayed.delAngDT, imuDataDelayed.gyro_index);
  365. correctDeltaVelocity(delVelCorrected, imuDataDelayed.delVelDT, imuDataDelayed.accel_index);
  366. } else {
  367. // we don't have new IMU data in the buffer so don't run filter updates on this time step
  368. runUpdates = false;
  369. }
  370. }
  371. // read the delta velocity and corresponding time interval from the IMU
  372. // return false if data is not available
  373. bool NavEKF2_core::readDeltaVelocity(uint8_t ins_index, Vector3f &dVel, float &dVel_dt) {
  374. const AP_InertialSensor &ins = AP::ins();
  375. if (ins_index < ins.get_accel_count()) {
  376. ins.get_delta_velocity(ins_index,dVel);
  377. dVel_dt = MAX(ins.get_delta_velocity_dt(ins_index),1.0e-4f);
  378. dVel_dt = MIN(dVel_dt,1.0e-1f);
  379. return true;
  380. }
  381. return false;
  382. }
  383. /********************************************************
  384. * Global Position Measurement *
  385. ********************************************************/
  386. // check for new valid GPS data and update stored measurement if available
  387. void NavEKF2_core::readGpsData()
  388. {
  389. if (frontend->_fusionModeGPS == 3) {
  390. // don't read GPS data if GPS usage disabled
  391. return;
  392. }
  393. // check for new GPS data
  394. // do not accept data at a faster rate than 14Hz to avoid overflowing the FIFO buffer
  395. const AP_GPS &gps = AP::gps();
  396. if (gps.last_message_time_ms() - lastTimeGpsReceived_ms > 70) {
  397. if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
  398. // report GPS fix status
  399. gpsCheckStatus.bad_fix = false;
  400. // store fix time from previous read
  401. secondLastGpsTime_ms = lastTimeGpsReceived_ms;
  402. // get current fix time
  403. lastTimeGpsReceived_ms = gps.last_message_time_ms();
  404. // estimate when the GPS fix was valid, allowing for GPS processing and other delays
  405. // ideally we should be using a timing signal from the GPS receiver to set this time
  406. float gps_delay = 0.0;
  407. gps.get_lag(gps_delay); // ignore the return value
  408. gpsDataNew.time_ms = lastTimeGpsReceived_ms - (uint32_t)(1e3f * gps_delay);
  409. // Correct for the average intersampling delay due to the filter updaterate
  410. gpsDataNew.time_ms -= localFilterTimeStep_ms/2;
  411. // Prevent time delay exceeding age of oldest IMU data in the buffer
  412. gpsDataNew.time_ms = MAX(gpsDataNew.time_ms,imuDataDelayed.time_ms);
  413. // Get which GPS we are using for position information
  414. gpsDataNew.sensor_idx = gps.primary_sensor();
  415. // read the NED velocity from the GPS
  416. gpsDataNew.vel = gps.velocity();
  417. // Use the speed and position accuracy from the GPS if available, otherwise set it to zero.
  418. // Apply a decaying envelope filter with a 5 second time constant to the raw accuracy data
  419. float alpha = constrain_float(0.0002f * (lastTimeGpsReceived_ms - secondLastGpsTime_ms),0.0f,1.0f);
  420. gpsSpdAccuracy *= (1.0f - alpha);
  421. float gpsSpdAccRaw;
  422. if (!gps.speed_accuracy(gpsSpdAccRaw)) {
  423. gpsSpdAccuracy = 0.0f;
  424. } else {
  425. gpsSpdAccuracy = MAX(gpsSpdAccuracy,gpsSpdAccRaw);
  426. gpsSpdAccuracy = MIN(gpsSpdAccuracy,50.0f);
  427. }
  428. gpsPosAccuracy *= (1.0f - alpha);
  429. float gpsPosAccRaw;
  430. if (!gps.horizontal_accuracy(gpsPosAccRaw)) {
  431. gpsPosAccuracy = 0.0f;
  432. } else {
  433. gpsPosAccuracy = MAX(gpsPosAccuracy,gpsPosAccRaw);
  434. gpsPosAccuracy = MIN(gpsPosAccuracy,100.0f);
  435. }
  436. gpsHgtAccuracy *= (1.0f - alpha);
  437. float gpsHgtAccRaw;
  438. if (!gps.vertical_accuracy(gpsHgtAccRaw)) {
  439. gpsHgtAccuracy = 0.0f;
  440. } else {
  441. gpsHgtAccuracy = MAX(gpsHgtAccuracy,gpsHgtAccRaw);
  442. gpsHgtAccuracy = MIN(gpsHgtAccuracy,100.0f);
  443. }
  444. // check if we have enough GPS satellites and increase the gps noise scaler if we don't
  445. if (gps.num_sats() >= 6 && (PV_AidingMode == AID_ABSOLUTE)) {
  446. gpsNoiseScaler = 1.0f;
  447. } else if (gps.num_sats() == 5 && (PV_AidingMode == AID_ABSOLUTE)) {
  448. gpsNoiseScaler = 1.4f;
  449. } else { // <= 4 satellites or in constant position mode
  450. gpsNoiseScaler = 2.0f;
  451. }
  452. // Check if GPS can output vertical velocity, if it is allowed to be used, and set GPS fusion mode accordingly
  453. if (gps.have_vertical_velocity() && frontend->_fusionModeGPS == 0 && !frontend->inhibitGpsVertVelUse) {
  454. useGpsVertVel = true;
  455. } else {
  456. useGpsVertVel = false;
  457. }
  458. // Monitor quality of the GPS velocity data both before and after alignment. This updates
  459. // GpsGoodToAlign class variable
  460. calcGpsGoodToAlign();
  461. // Post-alignment checks
  462. calcGpsGoodForFlight();
  463. // see if we can get origin from frontend
  464. if (!validOrigin && frontend->common_origin_valid) {
  465. setOrigin(frontend->common_EKF_origin);
  466. }
  467. // Read the GPS location in WGS-84 lat,long,height coordinates
  468. const struct Location &gpsloc = gps.location();
  469. // Set the EKF origin and magnetic field declination if not previously set and GPS checks have passed
  470. if (gpsGoodToAlign && !validOrigin) {
  471. setOrigin(gpsloc);
  472. // set the NE earth magnetic field states using the published declination
  473. // and set the corresponding variances and covariances
  474. alignMagStateDeclination();
  475. // Set the height of the NED origin
  476. ekfGpsRefHgt = (double)0.01 * (double)gpsloc.alt + (double)outputDataNew.position.z;
  477. // Set the uncertainty of the GPS origin height
  478. ekfOriginHgtVar = sq(gpsHgtAccuracy);
  479. }
  480. if (gpsGoodToAlign && !have_table_earth_field) {
  481. table_earth_field_ga = AP_Declination::get_earth_field_ga(gpsloc);
  482. table_declination = radians(AP_Declination::get_declination(gpsloc.lat*1.0e-7,
  483. gpsloc.lng*1.0e-7));
  484. have_table_earth_field = true;
  485. if (frontend->_mag_ef_limit > 0) {
  486. // initialise earth field from tables
  487. stateStruct.earth_magfield = table_earth_field_ga;
  488. }
  489. }
  490. // convert GPS measurements to local NED and save to buffer to be fused later if we have a valid origin
  491. if (validOrigin) {
  492. gpsDataNew.pos = EKF_origin.get_distance_NE(gpsloc);
  493. if ((frontend->_originHgtMode & (1<<2)) == 0) {
  494. gpsDataNew.hgt = (float)((double)0.01 * (double)gpsloc.alt - ekfGpsRefHgt);
  495. } else {
  496. gpsDataNew.hgt = 0.01 * (gpsloc.alt - EKF_origin.alt);
  497. }
  498. storedGPS.push(gpsDataNew);
  499. // declare GPS available for use
  500. gpsNotAvailable = false;
  501. }
  502. } else {
  503. // report GPS fix status
  504. gpsCheckStatus.bad_fix = true;
  505. hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "Waiting for 3D fix");
  506. }
  507. }
  508. }
  509. // read the delta angle and corresponding time interval from the IMU
  510. // return false if data is not available
  511. bool NavEKF2_core::readDeltaAngle(uint8_t ins_index, Vector3f &dAng, float &dAng_dt) {
  512. const AP_InertialSensor &ins = AP::ins();
  513. if (ins_index < ins.get_gyro_count()) {
  514. ins.get_delta_angle(ins_index,dAng);
  515. frontend->logging.log_imu = true;
  516. dAng_dt = MAX(ins.get_delta_angle_dt(ins_index),1.0e-4f);
  517. dAng_dt = MIN(dAng_dt,1.0e-1f);
  518. return true;
  519. }
  520. return false;
  521. }
  522. /********************************************************
  523. * Height Measurements *
  524. ********************************************************/
  525. // check for new pressure altitude measurement data and update stored measurement if available
  526. void NavEKF2_core::readBaroData()
  527. {
  528. // check to see if baro measurement has changed so we know if a new measurement has arrived
  529. // do not accept data at a faster rate than 14Hz to avoid overflowing the FIFO buffer
  530. const AP_Baro &baro = AP::baro();
  531. if (baro.get_last_update() - lastBaroReceived_ms > 70) {
  532. frontend->logging.log_baro = true;
  533. baroDataNew.hgt = baro.get_altitude();
  534. // If we are in takeoff mode, the height measurement is limited to be no less than the measurement at start of takeoff
  535. // This prevents negative baro disturbances due to copter downwash corrupting the EKF altitude during initial ascent
  536. if (getTakeoffExpected()) {
  537. baroDataNew.hgt = MAX(baroDataNew.hgt, meaHgtAtTakeOff);
  538. }
  539. // time stamp used to check for new measurement
  540. lastBaroReceived_ms = baro.get_last_update();
  541. // estimate of time height measurement was taken, allowing for delays
  542. baroDataNew.time_ms = lastBaroReceived_ms - frontend->_hgtDelay_ms;
  543. // Correct for the average intersampling delay due to the filter updaterate
  544. baroDataNew.time_ms -= localFilterTimeStep_ms/2;
  545. // Prevent time delay exceeding age of oldest IMU data in the buffer
  546. baroDataNew.time_ms = MAX(baroDataNew.time_ms,imuDataDelayed.time_ms);
  547. // save baro measurement to buffer to be fused later
  548. storedBaro.push(baroDataNew);
  549. }
  550. }
  551. // calculate filtered offset between baro height measurement and EKF height estimate
  552. // offset should be subtracted from baro measurement to match filter estimate
  553. // offset is used to enable reversion to baro from alternate height data source
  554. void NavEKF2_core::calcFiltBaroOffset()
  555. {
  556. // Apply a first order LPF with spike protection
  557. baroHgtOffset += 0.1f * constrain_float(baroDataDelayed.hgt + stateStruct.position.z - baroHgtOffset, -5.0f, 5.0f);
  558. }
  559. // correct the height of the EKF origin to be consistent with GPS Data using a Bayes filter.
  560. void NavEKF2_core::correctEkfOriginHeight()
  561. {
  562. // Estimate the WGS-84 height of the EKF's origin using a Bayes filter
  563. // calculate the variance of our a-priori estimate of the ekf origin height
  564. float deltaTime = constrain_float(0.001f * (imuDataDelayed.time_ms - lastOriginHgtTime_ms), 0.0f, 1.0f);
  565. if (activeHgtSource == HGT_SOURCE_BARO) {
  566. // Use the baro drift rate
  567. const float baroDriftRate = 0.05f;
  568. ekfOriginHgtVar += sq(baroDriftRate * deltaTime);
  569. } else if (activeHgtSource == HGT_SOURCE_RNG) {
  570. // use the worse case expected terrain gradient and vehicle horizontal speed
  571. const float maxTerrGrad = 0.25f;
  572. ekfOriginHgtVar += sq(maxTerrGrad * norm(stateStruct.velocity.x , stateStruct.velocity.y) * deltaTime);
  573. } else {
  574. // by definition our height source is absolute so cannot run this filter
  575. return;
  576. }
  577. lastOriginHgtTime_ms = imuDataDelayed.time_ms;
  578. // calculate the observation variance assuming EKF error relative to datum is independent of GPS observation error
  579. // when not using GPS as height source
  580. float originHgtObsVar = sq(gpsHgtAccuracy) + P[8][8];
  581. // calculate the correction gain
  582. float gain = ekfOriginHgtVar / (ekfOriginHgtVar + originHgtObsVar);
  583. // calculate the innovation
  584. float innovation = - stateStruct.position.z - gpsDataDelayed.hgt;
  585. // check the innovation variance ratio
  586. float ratio = sq(innovation) / (ekfOriginHgtVar + originHgtObsVar);
  587. // correct the EKF origin and variance estimate if the innovation is less than 5-sigma
  588. if (ratio < 25.0f && gpsAccuracyGood) {
  589. ekfGpsRefHgt -= (double)(gain * innovation);
  590. ekfOriginHgtVar -= MAX(gain * ekfOriginHgtVar , 0.0f);
  591. }
  592. }
  593. /********************************************************
  594. * Air Speed Measurements *
  595. ********************************************************/
  596. // check for new airspeed data and update stored measurements if available
  597. void NavEKF2_core::readAirSpdData()
  598. {
  599. // if airspeed reading is valid and is set by the user to be used and has been updated then
  600. // we take a new reading, convert from EAS to TAS and set the flag letting other functions
  601. // know a new measurement is available
  602. const AP_Airspeed *aspeed = _ahrs->get_airspeed();
  603. if (aspeed &&
  604. aspeed->use() &&
  605. aspeed->last_update_ms() != timeTasReceived_ms) {
  606. tasDataNew.tas = aspeed->get_airspeed() * AP::ahrs().get_EAS2TAS();
  607. timeTasReceived_ms = aspeed->last_update_ms();
  608. tasDataNew.time_ms = timeTasReceived_ms - frontend->tasDelay_ms;
  609. // Correct for the average intersampling delay due to the filter update rate
  610. tasDataNew.time_ms -= localFilterTimeStep_ms/2;
  611. // Save data into the buffer to be fused when the fusion time horizon catches up with it
  612. storedTAS.push(tasDataNew);
  613. }
  614. // Check the buffer for measurements that have been overtaken by the fusion time horizon and need to be fused
  615. tasDataToFuse = storedTAS.recall(tasDataDelayed,imuDataDelayed.time_ms);
  616. }
  617. /********************************************************
  618. * Range Beacon Measurements *
  619. ********************************************************/
  620. // check for new range beacon data and push to data buffer if available
  621. void NavEKF2_core::readRngBcnData()
  622. {
  623. // get the location of the beacon data
  624. const AP_Beacon *beacon = AP::beacon();
  625. // exit immediately if no beacon object
  626. if (beacon == nullptr) {
  627. return;
  628. }
  629. // get the number of beacons in use
  630. N_beacons = beacon->count();
  631. // search through all the beacons for new data and if we find it stop searching and push the data into the observation buffer
  632. bool newDataToPush = false;
  633. uint8_t numRngBcnsChecked = 0;
  634. // start the search one index up from where we left it last time
  635. uint8_t index = lastRngBcnChecked;
  636. while (!newDataToPush && numRngBcnsChecked < N_beacons) {
  637. // track the number of beacons checked
  638. numRngBcnsChecked++;
  639. // move to next beacon, wrap index if necessary
  640. index++;
  641. if (index >= N_beacons) {
  642. index = 0;
  643. }
  644. // check that the beacon is healthy and has new data
  645. if (beacon->beacon_healthy(index) &&
  646. beacon->beacon_last_update_ms(index) != lastTimeRngBcn_ms[index])
  647. {
  648. // set the timestamp, correcting for measurement delay and average intersampling delay due to the filter update rate
  649. lastTimeRngBcn_ms[index] = beacon->beacon_last_update_ms(index);
  650. rngBcnDataNew.time_ms = lastTimeRngBcn_ms[index] - frontend->_rngBcnDelay_ms - localFilterTimeStep_ms/2;
  651. // set the range noise
  652. // TODO the range library should provide the noise/accuracy estimate for each beacon
  653. rngBcnDataNew.rngErr = frontend->_rngBcnNoise;
  654. // set the range measurement
  655. rngBcnDataNew.rng = beacon->beacon_distance(index);
  656. // set the beacon position
  657. rngBcnDataNew.beacon_posNED = beacon->beacon_position(index);
  658. // identify the beacon identifier
  659. rngBcnDataNew.beacon_ID = index;
  660. // indicate we have new data to push to the buffer
  661. newDataToPush = true;
  662. // update the last checked index
  663. lastRngBcnChecked = index;
  664. }
  665. }
  666. // Check if the beacon system has returned a 3D fix
  667. if (beacon->get_vehicle_position_ned(beaconVehiclePosNED, beaconVehiclePosErr)) {
  668. rngBcnLast3DmeasTime_ms = imuSampleTime_ms;
  669. }
  670. // Check if the range beacon data can be used to align the vehicle position
  671. if (imuSampleTime_ms - rngBcnLast3DmeasTime_ms < 250 && beaconVehiclePosErr < 1.0f && rngBcnAlignmentCompleted) {
  672. // check for consistency between the position reported by the beacon and the position from the 3-State alignment filter
  673. float posDiffSq = sq(receiverPos.x - beaconVehiclePosNED.x) + sq(receiverPos.y - beaconVehiclePosNED.y);
  674. float posDiffVar = sq(beaconVehiclePosErr) + receiverPosCov[0][0] + receiverPosCov[1][1];
  675. if (posDiffSq < 9.0f*posDiffVar) {
  676. rngBcnGoodToAlign = true;
  677. // Set the EKF origin and magnetic field declination if not previously set
  678. if (!validOrigin && PV_AidingMode != AID_ABSOLUTE) {
  679. // get origin from beacon system
  680. Location origin_loc;
  681. if (beacon->get_origin(origin_loc)) {
  682. setOriginLLH(origin_loc);
  683. // set the NE earth magnetic field states using the published declination
  684. // and set the corresponding variances and covariances
  685. alignMagStateDeclination();
  686. // Set the uncertainty of the origin height
  687. ekfOriginHgtVar = sq(beaconVehiclePosErr);
  688. }
  689. }
  690. } else {
  691. rngBcnGoodToAlign = false;
  692. }
  693. } else {
  694. rngBcnGoodToAlign = false;
  695. }
  696. // Save data into the buffer to be fused when the fusion time horizon catches up with it
  697. if (newDataToPush) {
  698. storedRangeBeacon.push(rngBcnDataNew);
  699. }
  700. // Check the buffer for measurements that have been overtaken by the fusion time horizon and need to be fused
  701. rngBcnDataToFuse = storedRangeBeacon.recall(rngBcnDataDelayed,imuDataDelayed.time_ms);
  702. }
  703. /*
  704. update timing statistics structure
  705. */
  706. void NavEKF2_core::updateTimingStatistics(void)
  707. {
  708. if (timing.count == 0) {
  709. timing.dtIMUavg_max = dtIMUavg;
  710. timing.dtIMUavg_min = dtIMUavg;
  711. timing.dtEKFavg_max = dtEkfAvg;
  712. timing.dtEKFavg_min = dtEkfAvg;
  713. timing.delAngDT_max = imuDataDelayed.delAngDT;
  714. timing.delAngDT_min = imuDataDelayed.delAngDT;
  715. timing.delVelDT_max = imuDataDelayed.delVelDT;
  716. timing.delVelDT_min = imuDataDelayed.delVelDT;
  717. } else {
  718. timing.dtIMUavg_max = MAX(timing.dtIMUavg_max, dtIMUavg);
  719. timing.dtIMUavg_min = MIN(timing.dtIMUavg_min, dtIMUavg);
  720. timing.dtEKFavg_max = MAX(timing.dtEKFavg_max, dtEkfAvg);
  721. timing.dtEKFavg_min = MIN(timing.dtEKFavg_min, dtEkfAvg);
  722. timing.delAngDT_max = MAX(timing.delAngDT_max, imuDataDelayed.delAngDT);
  723. timing.delAngDT_min = MIN(timing.delAngDT_min, imuDataDelayed.delAngDT);
  724. timing.delVelDT_max = MAX(timing.delVelDT_max, imuDataDelayed.delVelDT);
  725. timing.delVelDT_min = MIN(timing.delVelDT_min, imuDataDelayed.delVelDT);
  726. }
  727. timing.count++;
  728. }
  729. // get timing statistics structure
  730. void NavEKF2_core::getTimingStatistics(struct ekf_timing &_timing)
  731. {
  732. _timing = timing;
  733. memset(&timing, 0, sizeof(timing));
  734. }
  735. void NavEKF2_core::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
  736. {
  737. // limit update rate to maximum allowed by sensor buffers and fusion process
  738. // don't try to write to buffer until the filter has been initialised
  739. if ((timeStamp_ms - extNavMeasTime_ms) < 70) {
  740. return;
  741. } else {
  742. extNavMeasTime_ms = timeStamp_ms;
  743. }
  744. if (resetTime_ms > extNavLastPosResetTime_ms) {
  745. extNavDataNew.posReset = true;
  746. extNavLastPosResetTime_ms = resetTime_ms;
  747. } else {
  748. extNavDataNew.posReset = false;
  749. }
  750. extNavDataNew.pos = pos;
  751. extNavDataNew.quat = quat;
  752. if (posErr > 0) {
  753. extNavDataNew.posErr = posErr;
  754. } else {
  755. extNavDataNew.posErr = frontend->_gpsHorizPosNoise;
  756. }
  757. extNavDataNew.angErr = angErr;
  758. extNavDataNew.body_offset = &sensOffset;
  759. timeStamp_ms = timeStamp_ms - frontend->_extnavDelay_ms;
  760. // Correct for the average intersampling delay due to the filter updaterate
  761. timeStamp_ms -= localFilterTimeStep_ms/2;
  762. // Prevent time delay exceeding age of oldest IMU data in the buffer
  763. timeStamp_ms = MAX(timeStamp_ms,imuDataDelayed.time_ms);
  764. extNavDataNew.time_ms = timeStamp_ms;
  765. storedExtNav.push(extNavDataNew);
  766. }
  767. /*
  768. return declination in radians
  769. */
  770. float NavEKF2_core::MagDeclination(void) const
  771. {
  772. // if we are using the WMM tables then use the table declination
  773. // to ensure consistency with the table mag field. Otherwise use
  774. // the declination from the compass library
  775. if (have_table_earth_field && frontend->_mag_ef_limit > 0) {
  776. return table_declination;
  777. }
  778. if (!use_compass()) {
  779. return 0;
  780. }
  781. return _ahrs->get_compass()->get_declination();
  782. }
  783. /*
  784. update estimates of inactive bias states. This keeps inactive IMUs
  785. as hot-spares so we can switch to them without causing a jump in the
  786. error
  787. */
  788. void NavEKF2_core::learnInactiveBiases(void)
  789. {
  790. const AP_InertialSensor &ins = AP::ins();
  791. // learn gyro biases
  792. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  793. if (!ins.use_gyro(i)) {
  794. // can't use this gyro
  795. continue;
  796. }
  797. if (gyro_index_active == i) {
  798. // use current estimates from main filter of gyro bias and scale
  799. inactiveBias[i].gyro_bias = stateStruct.gyro_bias;
  800. inactiveBias[i].gyro_scale = stateStruct.gyro_scale;
  801. } else {
  802. // get filtered gyro and use the difference between the
  803. // corrected gyro on the active IMU and the inactive IMU
  804. // to move the inactive bias towards the right value
  805. Vector3f filtered_gyro_active = ins.get_gyro(gyro_index_active) - (stateStruct.gyro_bias/dtEkfAvg);
  806. Vector3f filtered_gyro_inactive = ins.get_gyro(i) - (inactiveBias[i].gyro_bias/dtEkfAvg);
  807. Vector3f error = filtered_gyro_active - filtered_gyro_inactive;
  808. // prevent a single large error from contaminating bias estimate
  809. const float bias_limit = radians(5);
  810. error.x = constrain_float(error.x, -bias_limit, bias_limit);
  811. error.y = constrain_float(error.y, -bias_limit, bias_limit);
  812. error.z = constrain_float(error.z, -bias_limit, bias_limit);
  813. // slowly bring the inactive gyro in line with the active gyro. This corrects a 5 deg/sec
  814. // gyro bias error in around 1 minute
  815. inactiveBias[i].gyro_bias -= error * (1.0e-4f * dtEkfAvg);
  816. }
  817. }
  818. // learn accel biases
  819. for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
  820. if (!ins.use_accel(i)) {
  821. // can't use this accel
  822. continue;
  823. }
  824. if (accel_index_active == i) {
  825. // use current estimate from main filter
  826. inactiveBias[i].accel_zbias = stateStruct.accel_zbias;
  827. } else {
  828. // get filtered accel and use the difference between the
  829. // corrected accel on the active IMU and the inactive IMU
  830. // to move the inactive bias towards the right value
  831. float filtered_accel_active = ins.get_accel(accel_index_active).z - (stateStruct.accel_zbias/dtEkfAvg);
  832. float filtered_accel_inactive = ins.get_accel(i).z - (inactiveBias[i].accel_zbias/dtEkfAvg);
  833. float error = filtered_accel_active - filtered_accel_inactive;
  834. // prevent a single large error from contaminating bias estimate
  835. const float bias_limit = 1; // m/s/s
  836. error = constrain_float(error, -bias_limit, bias_limit);
  837. // slowly bring the inactive accel in line with the active accel
  838. // this learns 0.5m/s/s bias in about 1 minute
  839. inactiveBias[i].accel_zbias -= error * (1.0e-4f * dtEkfAvg);
  840. }
  841. }
  842. }