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