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