* Unfortunately, due to the SWIG dependency, we need sudo to install on
Travis (conflicts when adding with debian-sid source prevent using addons)
which means we cannot use the container-based infrastructure anymore.
* Building the Python bindings requires g++5 (at least with -Werr set).
* When building the Python bindings on Travis, the numpy includes are not found
by cmake, so they have to be added separately by running a Python process with
`numpy.get_include()`
* The build script now (somewhat clumsily) depends on the RUN_PYTEST environment
variable. If it is set to anything other than "", it will make the tests and
run tests and benchmarks
* Add requirements.txt file with required Python packages
* Read requirements.txt from CMakeLists.txt to check dependencies and alert the
user if necessary.
* Add SWIG interface definition (and external numpy interface) to ecl classes
* Add section in CMakeLists.txt to build Python bindings and execute
Python-based tests
* Write (property-based) tests that show the basic functionality of the Python
bindings and the EKF (using pytest and hypothesis libraries)
* Write minimal benchmark for the EKF update (using benchmark plugin for pytest)
* Add plotting utilities to analyze tests
* Add lint script to keep the Python scripts clean
* This is a sane choice (and should arguably always be done for classes with
virtual methods to avoid undefined behavior)
* It is required for wrapping the EstimatorInterface with SWIG (without virtual
destructor, deriving from the EstimatorInterface leads to
-Werror=delete-non-virtual-dtor).
When starting aiding using EV only and commencing GPS aiding later, this change means that the GPS origin is set to the local position 0,0 point rather than the current vehicle position. This avoids large changes in local position when GPs aiding starts.
Fuse external vision data using a relative position odometry method when GPS data is also being used and enable both GPOS and EV data to be fused on the same time step.
Moves calculation only required for mag heading fusion into the if (_control_status.flags.mag_hdg) branch
When using EV yaw, the observed yaw angle is calculated directly from the EV quaternions using derived expressions from references in code comments.
This enables the initial uncertainty to be set based on application and also ensures that the max allowed growth in wind state variance is consistent with the initial uncertainty specified.
- when switching to range finder use the current terrain estimate as
height sensor offset, otherwise spikes in the range measurements could lead
to a wrong offset
Signed-off-by: Roman <bapstroman@gmail.com>
- do not subtract the height sensor offset variable when computing the
baro offset from the local origin. The baro height offset is calculated
when baro is not fused and so the height sensor offset used in that case
is associated to another sensor and has nothing to do with the baro.
Signed-off-by: Roman <bapstroman@gmail.com>
the primary height source
- moved height control into single function in order to decide which sensor
should be used for estimating height
- under certain conditions allow to use the range finder to estimate height
even if it's not the primary height source
- fixed a bug where the delta time for the baro offset calculation was always
zero
- use methods to set height control flags to reduce code duplication and
to prevent bugs
Signed-off-by: Roman <bapstroman@gmail.com>
Add calculation of a vertical position derivative to the output predictor. This will have degraded tracking relative to the EKF states, but the velocity will be closer to the first derivative of the position and reduce the effect inertial prediction errors on control loops that are operating in a pure velocity feedback mode.
Move calculation of IMU offset angular rate correction out of velocity accessor and into output predictor.
Provide separate accessor for vertical position derivative.
Use horizontal acceleration to check if yaw is observable independent of the magnetometer.
Use rotation about the vertical to check if mag raises are observable.
If neither yaw of mag biases are observable, save the magnetic field variances and switch to magnetic yaw fusion.
Use the last learned declination when using magnetic yaw fusion so that the yaw reference remains consistent.
When yaw or biases become observable, reinstate the saved variances and switch back to 3D mag fusion.
Add a bitmask parameter to control bias learning for individual axes. This is achieved by setting the disabled states to zero together with their corresponding covariances.
Minor cleanup of the covariance prediction comments.
Removal of unnecessary variable copy operations.
Replace index operations to initialise covariance to zero with the more efficient memset.
Use vertical velocity and position innovation failure to detect bad accelerometer data caused by clipping or aliasing which can cause large vertical acceleration errors and loss of height estimation. When bad accel data is detected:
1) Inhibit accelerometer bias learning
2) Force fusion of vertical velocity and height data
3) Increase accelerometer process noise
The previous practice of relying on the off-diagonals being zero caused problems with conditioning of the magnetometer fusion on one flight. By storing the variances when the learning inhibit becomes active and ensuring that the rows and columns in the covariance matrix for the inhibited states are always zero, the observed numerical conditioning error has been eliminated for replay of the problem flight log .
Doing so can casue large jumps in GPS position and innovation check errors after landing and also reduces the effectiveness of pre-flight innovation consistency checks.
Previously GPS quality checks were only run until the EKF origin was set. This meant that they could not be used by other pre-flight checks.
This change ensures that checks will always be run when the vehicle on-ground or not using GPS to enable use by external preflight checks.
When using a union of flags and integer value it is safer to initialise the value to 0 rather than memset the flags because the flags may not define all bits in the integer.
This bug caused X and Y delta velocity bias state variance to be reset to the same value as the Z axis when learning was inhibited.
Documentation has also been updated.
This change removes the following compiler error when building using the ARM cross compiler.
/Users/paul/src/Firmware/src/lib/ecl/EKF/ekf_helper.cpp:45:12: error: 'std::abs' has not been declared
using std::abs;
Make the target EKF rate an integer multiple of the IMU rate. This slightly increases the average prediction time step for the EKF from just over 10msec to 12msec, but the variation reduces significantly which makes filter tuning more deterministic.
Improve the algorithm used to adjust the collection time criteria to reduce jitter in the correction.
This was incorrectly using the IMU (1/250 sec) timestamp instead of the EKF (1/100 sec) value.
The corresponding accelerometer limit has been made a parameter and adjusted to match previous behaviour.
This is a functionally equivalent. It moves all of the code for the terrain estimator into a single function call from the main filter update, making it clear that it is independent of the main filter.
The tilt compensation being applied previously was based on a flat earth geometric model assuming perfect tilt knowledge which reduces the effect of range errors on height error as the vehicle tilts. however in the real world, variations in terrain gradient and uncertainty in vehicle tilt and sensor alignment tend to increase height error with tilt, so the adjustment of observation variance with tilt has been removed given we do not have a valid mathematical model on which to base it.
Taking off before passing GPS checks would cause airspeed or sideslip to be fused when the filter was still using a constant position assumption. This would cause large airspeed innovations, invalid wind estimates and degrade filter performance after GPS was gained and position and velocity was reset.
The bug meant the Y velocity (state index 5) covariance was not being updated correctly when sideslip was being used to constrain velocity drift (extended GPS loss).
The rework of the covariance update to reduce RAM follows the same pattern as adopted for other fusion processes
Enables wind estimation without an airspeed sensor and enables synthetic sideslip to be used with an airspeed sensor for improved wind state estimation.
Wind states and covariances are reset differently depending on whether airspeed is available.
Everywhere where KHP is used, it is first completely reset, thus making
it unnecessary to keep it as a class member.
This saves 2.3KB RAM.
Stack sizes don't need changing, since there is already a function
Ekf::predictCovariance(), which needs around 3KB of stack and is called
close to where the fuse* functions are called.
- if both gps position and velocity measurements are rejected for 7 seconds
do a reset
- if only gps position measurements are rejected then wait for 14 seconds
as we still have velocity measurements to constrain the drift in position
- introduced ecl internal parameter for the timeout
Signed-off-by: Roman <bapstroman@gmail.com>