The problem with using min() and max() is that they conflict with some
C++ headers. Name the macros in uppercase instead. We may go case by
case later converting them to be typesafe.
Changes generated with:
git ls-files '*.cpp' '*.h' -z | xargs -0 sed -i 's/\([^_[:alnum:]]\)max(/\1MAX(/g'
git ls-files '*.cpp' '*.h' -z | xargs -0 sed -i 's/\([^_[:alnum:]]\)min(/\1MIN(/g'
Ensures that the latest GPS data is used to reset the states.
Separates the logic used to set the origin from the logic used to determine when to reset states and commence GPS aiding
This removes errors in the in-flight reset of the earth field states by:
1) Using a state vector and magnetometer measurement from the same time coordinate
2) Not using the AHRS trim offsets in the calculation
dtIMUactual has been spit into a separate dtDelAng and dtDelVel and dtDelVel1 and dtDelVel2 delta time in recognition of the amount of timing jitter and different update rates for the IMU's
Vibration in the 400Hz delta angles could cause the angular rate condition check for in-flight magnetic field alignment to fail.
The symptons were failure to start magnetic field learning as expected when EK2_MAG_CAL=3 was set.
The calculation of a delta rotation between consecutive magnetometer samples has been introduced instead of the most recent IMU delta angle as this is less affected by noise and give an upper bound on the angular error.
the check has been moved into the magnetometer fusion control function so that any reset will be performed using fresh magnetometer data
Explicitly set Plane parameters rather than rely on use of the default
If no type defined, default to Copter parameters (most common platform type
Enable different platform types to use different initial accel bias uncertainty
Reduce initial accel bias uncertainty for copter to prevent initial oscillation in bias and height estimate
Large baro data errors when flying without GPS could cause total failure of the EKF.
This patch provides protection against this happening in-flight but allows for large innovations during preflight alignment.
Now variables don't have to be declared with PROGMEM anymore, so remove
them. This was automated with:
git grep -l -z PROGMEM | xargs -0 sed -i 's/ PROGMEM / /g'
git grep -l -z PROGMEM | xargs -0 sed -i 's/PROGMEM//g'
The 2 commands were done so we don't leave behind spurious spaces.
AVR-specific places were not changed.
Now that we are using a consistent 50Hz minimum update rate for the covariance prediction we do not need a different initial gyro bias uncertainty for plane and copter to maintain filter stability margins.
The default value of 0.1 rad/s was too high and gave excessive settling time of the filter attitude after startup.
The initial attitude uncertainty has been increased to allow for some movement during startup.
If the baro data and magnetometer data are interleaved (arriving every 100 msec and offset by 50 msec), then the filter will go unstable during startup and fail to complete checks.
Fixes a potential error where changes to timing and arrival rate of magnetometer and baro data could block the fusion of synthetic position and velocity measurements, allowing unrestrained tilt errors during operation without GPS or optical flow.
Fusion of synthetic position or velocity measurements is now timed to coincide with fusion of barometer observations.
If a new barometer observation has not arrived after 200 msec then the synthetic position or velocity is fused anyway so that fusion of synthetic position or velocity observations cannot occur any slower than 5 Hz
Previous check default only checked the number of satellites and horizontal position accuracy.
Updated default value also checks HDoP and speed accuracy.
Now that we have a pre-arm check in place to detect bad lidar, the motion check is unnecessary and can false trigger for copters with flexible undercarriages or on uneven ground.
This method checks for consistency between accelerometer readings and switches to the unit with the lowest vibration of the difference exceeds 0.3g
The threshold of 1.7 m/s/s corresponds to a maximum tilt error of 10 deg assuming one IMU is good, one is bad and the EKF is using the bad IMU.
This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
If a badly conditioned covariance matrix causes negative innovation variances, then the filter will diverge. The previous approach of increasing process noise was not effective in some cases, so a hard reset of the covariance matrix has been adopted to guarantee recovery.
This fixes a numerical error observed using the replay on flight log which had significant periods of compass rejection.
This patch increases initial gyro bias uncertainty and plane and rover specific process noise to improve the rate of gyro bias learning.
This reduces the likelihood of a navigation failure due to rapid temperature changes in the inertial sensors causing rapid changes in zero rate offset.
The increase in process noise cannot be applied to Copter due to different numerical stability limits arising from the faster update rate.
This ensures that when we start using GPS, that the EKF will be using the correct declination for that location
If declination is not known it defaults to zero
This prevents bad inertial or GPS data combined with the post takeoff heading alignment check used by plane from resulting in earth field states that have an incorrect declination
This patch reworks the in-air transition criteria to reduce the likelihood of false positives and to ensure that there will be enough ground speed to make the heading check work reliably.
This check will declare the EKF as unhealthy if the horizontal position innovations exceed a threshold before motors are armed.
This will help to prevent a takeoff with bad inertial data caused by bad accel or gyro offsets.
Prolonged yaw rotations with gyro scale factor errors can cause yaw errors and gyro bias estimation errors to build up to a point where EKF health checks fail.
This patch introduces the following protections:
1) The assumed yaw gyro error is scaled using a filtered yaw rate and an assumed 3% scale factor error (MPU6000 data sheet)
2) When the filtered yaw rate magnitude is greater than 1 rad/sec, the Z gyro bias process noise is zeroed and the state variance set to zero to inhibit modification of the bias state
3) When the filtered yaw rate magnitude is greater than 1 rad/sec, the magnetometer quaternion corrections are scaled by a factor of four to maintain tighter alignment with the compass
Increases magnetometer weighting on yaw corrections when there there is no other aiding to constrain yaw drift.
Prevents switch to GPS if magnetometer data is failing innovation checks which indicates a bad yaw angle
The interface definition has been modified so that it returns true for a position obtained usin geither the normal inertial navigation calculation, or a raw GPS measurement.
This enables this function to be used to set a home position before flight.
If a calculated position is not available, the function will return a value based on raw GPS or last calculation if available, but the status will be set to false to indicate that it cannot be used for control.
The inconsistent baro data during ground effect takeoff combined with the larger variances in the Z accel bias state early in flight can cause unwanted changes in bias estimate and therefore changes in height estimation error.
This patch turns of the process noise and state updates for the Z accel bias state when takeoff in ground effect is expected.
Thsi fixes a potential bug where the vehicle could land at a lower location without disarming and re-enter ground effect takeoff mode wiht a baro height floor above the current altitude, causing unpredictable height gain
Ground effect baro errors can cause a spike in height innovation on disarming if ground effect compensation was used during the landing. This causes a transient AHRS fault message if this innovation is outside the pre-arm check limits.
Resetting the vertical position state to the measured height after disarming prevents this.
This estimate is used to offset baro data if we need to switch across from range finder data due to sensor failure. The previous filter coefficients gave a 0.5 seconds time constant on the offset which was too susceptible to baro noise.