AP_NavEKF3_Measurements.cpp 44 KB

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