Commit Graph

840 Commits

Author SHA1 Message Date
Paul Riseborough 78e983073a
EKF: Fix bug in use of gps velocity noise parameter (#401)
This fixes a bug introduced by an earlier feature request PR. The parameter is supposed to define the lower limit on the observation noise.
2018-02-28 11:48:53 +11:00
ChristophTobler cdc6efc5d6 EKF: fix rot vec calc from quat by using matrix lib 2018-02-08 10:22:55 +01:00
ChristophTobler 9238e2f1a2 EKF: fix spike handling in ev rotation calculation 2018-02-08 10:20:59 +01:00
Paul Riseborough db5264e45c EKF: Add missing reset for output observer vertical position derivative
Required to prevent large transients in value returned by get_pos_d_deriv accessor following a vertical state reset event.
2018-01-31 08:43:39 +01:00
ChristophTobler 337cdcc59a init height using baro when set to ev height (#388)
this also makes sure the _baro_hgt_offset is being initialized correctly
2018-01-30 07:33:28 +11:00
Paul Riseborough a2d6a4dded
EKF: fix indexing bug (#387)
Should use index 9 for vertical position.
2018-01-29 08:09:55 +11:00
Paul Riseborough f016e66ff8
Revert "EKF: Release flow speed limit with altitude gained" (#382)
* Revert "EKF: Release flow speed limit with altitude gained"

This reverts commit e70206f74b.

* Revert "fix code style"

This reverts commit 76bf70121c.

* Revert "Reverse the linked list of data_validator_group and maintain a first node"

This reverts commit 32482e7644.
2018-01-24 20:46:48 +11:00
ChristophTobler cdbca91e79 EV height reset (#379)
* fix typo

* EKF: use baro if it was reset to baro from ev

* EKF: set vert_pos_reset if resetting to ev hgt

otherwise the position controller will not reset the setpoint -> leading to unwanted altitude changes
2018-01-15 20:15:56 +11:00
Daniel Agar 7df4e0f8eb reenable pytest with px4-dev-ecl 2018-01-05 02:39:02 -05:00
Daniel Agar f407954207 initial jenkins configuration 2018-01-05 02:39:02 -05:00
Paul Riseborough 0f047504d4 EKF: Prevent possible div 0 due to incorrect initial values
Gate size class variables should not be initialised to zero, because it will cause a /0 error if fuseVelPosHeight() is called before they are set to their respective parameter values.
2018-01-04 07:47:03 +11:00
Daniel Agar f0862210c7 EKF initialize _hvelInnovGate
- fixes CID 139550
2018-01-03 08:07:28 +01:00
CarlOlsson 5c8b22b43f ekf: return beta test ratio in get_innovation_test_status
Signed-off-by: CarlOlsson <carlolsson.co@gmail.com>
2017-12-18 15:48:36 +01:00
Paul Riseborough e70206f74b EKF: Release flow speed limit with altitude gained
When GPS use is gained whilst flying using optical flow data, the sudden release of the speed limit is unannounced to  the operator and can cause unexpected acceleration.
This patch releases the speed limit as height is gained, but does not reduce it when the vehicle descends, unless GPS use is lost.
2017-12-12 01:26:44 +00:00
Paul Riseborough 83b765f707 EKF: Don't print navigation lost message on startup 2017-12-03 23:02:02 +00:00
Daniel Agar e3da71c89d Ekf initialize all fields 2017-11-26 16:50:16 -05:00
Paul Riseborough 89be63d6c2 EKF: Fix vel pos innovation logging bug 2017-11-24 14:25:44 +11:00
Paul Riseborough b0ad8269a5 EKF: enable separate monitoring of aux velocity innovations 2017-11-21 11:18:09 +11:00
Paul Riseborough 2a57fd858d EKF: clean up reset of fusion flags 2017-11-21 11:18:09 +11:00
Paul Riseborough 8e30c2666d EKF: Add support auxiliary velocity observation
This enables the EKF to use an additional NE velocity measurement. This can be used to improve position hold stability when landing using a beacon system for positioning by fusing the beacon velocity estimates.
2017-11-21 11:18:09 +11:00
Paul Riseborough a2b24fa960 EKF: Protect against ground effect induced static pressure rise during landing and takeoff.
Apply a dead-zone to the vertical position innovation if using baro for height and if in the ground effect region during and just after takeoff.
Method needs to be activated externally.
Turns off automatically after 10 seconds or if specified height gained.
2017-11-17 21:41:31 +11:00
Daniel Agar d9c8af54bd
EKF add print_status() with memory usage 2017-11-16 14:11:34 -05:00
Daniel Agar 75d1ed894c
EKF simplify RingBuffer allocation check 2017-11-16 13:09:17 -05:00
Paul Riseborough af7004ef01 EKF: report observation buffer allocation errors 2017-11-16 20:04:46 +11:00
Paul Riseborough d785a19c0a EKF: delay final allocation of observation buffers until required 2017-11-16 19:47:04 +11:00
Paul Riseborough 7c8fcf7628 EKF: Clarify use of *= operator for quaternions 2017-11-16 11:52:19 +11:00
Daniel Agar ed9a394029
EKF RingBuffer avoid copying 2017-11-15 18:08:51 -05:00
Paul Riseborough 2b20c52c4d EKF: Remove redundant code 2017-11-15 22:03:17 +11:00
Paul Riseborough cfdab732d1 EKF: Update parameter description 2017-11-15 21:28:11 +11:00
Paul Riseborough 72a7ab2c25 EKF: Improve resistance to bad initial mag offset
When magnetic field states have been reset in-flight using a single sample, the magnetic field states are not used to constrain heading drift for a period after the reset. This period has been shortened from 10 to 5 seconds which is enough time to average out the effects of measurement noise (the original concern). The shorter time has enabled the previous practice for RW vehicles of using magnetic heading in that time period to constrain yaw drift to be discontinued. This is necessary becasue while magnetic heading is being used, it fights the yaw corrections obtained from GPs observations and lengthens the time required to recover from a bad mag calibration.
2017-11-13 07:05:56 +11:00
Paul Riseborough df9f48d2d3 EKF: Fix build error 2017-11-13 07:05:56 +11:00
Paul Riseborough 44c50ab2df EKF: Correct magnetic yaw measurement using learned mag biases
Don't apply bias corrections when biases are being learned to avoid possible circular data dependency.
2017-11-13 07:05:56 +11:00
Paul Riseborough c70363c501 EKF: Don't fuse heading if FW and waiting for mag states to stabilise
Doing so is a bad idea because bad mag data can drag the yaw angle away from the reset value and lead to rejection of GPS.
2017-11-13 07:05:56 +11:00
Paul Riseborough 279fc836f7 EKF: Always reset covariance matrix terms when doing vel pos state reset
If state errors were large before the reset, then failure to reset the covariance matrix terms can result in incorrect fusion of position and velocity measurements after the reset due to inconsistencies in the covariance matrix.
2017-11-13 07:05:56 +11:00
Paul Riseborough 141264fe63 EKF: Add method to set diagonals in covariance matrix 2017-11-13 07:05:56 +11:00
Paul Riseborough 32de90b9ef EKF: Add method to zero covariance terms 2017-11-13 07:05:56 +11:00
Paul Riseborough f3e34eddc9 EKF: do not attempt to align FW yaw using GPS method if on ground 2017-11-13 07:05:56 +11:00
Paul Riseborough 8f27d3fc54 EKF: don't reset quaternion states unnecessarily
When performing the initial in-flight mag yaw reset for RW vehicle, do not reset the quaternion states and corresponding variances unless there has been a change in yaw angle large enough to cause problems with navigation.
This is because the state estimates after a reset are more vulnerable to transient sensor errors, so a reset should be avoided if possible.
2017-11-13 07:05:56 +11:00
Paul Riseborough 9e47b6e1b6 EKF: don't reset quaternions unnecessarily
When performing the initial in-flight magnetic field reset for fixed wing vehicles, resetting the quaternion states and their corresponding covariances should be avoided unless yaw errors are large, because state estimates are vulnerable to transient sensor errors immediately following a reset.
2017-11-13 06:55:02 +11:00
Paul Riseborough 29d383edbf EKF: Allow mag field estimates to stabilise before use 2017-11-13 06:55:02 +11:00
Paul Riseborough 363edf5eb9 EKF: Fix yaw reset for fixed wing
Ensures that a complete reset of velocity and position states will always be performed if yaw has had to be reset using GPS velocity.
Ensures that the yaw_align status cannot be set to false once the filter has aligned.
2017-11-13 06:55:02 +11:00
Paul Riseborough 7852c0ed03
Merge pull request #312 from PX4/pr-ekfExtVisQuat
EKF: Enable operation with arbitrary External Vision reference frame
2017-11-12 08:35:39 +11:00
Paul Riseborough 5fd006ca48 EKF: remove redundant code 2017-11-11 07:06:01 +11:00
ChristophTobler e388e59f32 EKF: use uint64_t cast for XeY to avoid float casting of variables
The default type for XeY is float
2017-11-08 11:40:26 +01:00
Paul Riseborough bba3f70a0e EKF: reduce prediction time step from 12 to 8 sec
Reduces susceptibility to incorrect estimation of acceleration bias during sustained yaw rate.
Requires an increase in RAM allocation of 837 Bytes to allow for the longer IMU and output predictor buffers that can be created.
2017-11-02 09:27:33 +01:00
Paul Riseborough 01d68ef67c EKF: Enable use of rotated external nav estimates 2017-11-01 08:33:57 +11:00
Paul Riseborough 063533afae EKF: Add method to enable the IMU bias states to be reset externally 2017-10-26 10:41:39 +11:00
Paul Riseborough cd2ca57ec2 Merge pull request #339 from PX4/ekfPosCtrlLimits-wip
Ekf pos ctrl limits wip
2017-10-23 06:57:23 +11:00
Paul Riseborough 79995b2c15 Create total energy control system implementation
This is a new, clean and streamlined variant of the mathematical derivation I created a few years ago.
2017-10-22 20:37:40 +02:00
Paul Riseborough e10ec59058 EKF: Use consistent test for navigation validity reporting
This will enable controller to take advantage of non-inertial dead reckoning.
2017-10-20 14:44:38 +11:00
Paul Riseborough 19074fdd9e EKF: Use consistent time limit for inertial dead reckoning test 2017-10-20 14:44:38 +11:00
Paul Riseborough 55a2dc94df EKF: handle air data fusion covariance reset consistently
Both the sideslip and airspeed fusion should not be resetting covariances for states they do not modify.
2017-10-20 14:44:37 +11:00
Paul Riseborough 0d32128701 EKF: Use dead-reckoning status to determine if air data should modify non-wind states 2017-10-20 14:44:37 +11:00
Paul Riseborough e4ffe199ed EKF: fix bug in sideslip fusion activation 2017-10-20 14:44:37 +11:00
Paul Riseborough 59f1c3e19e EKF: Update dead-reckoning definition
Use of air data to navigate should be classified as dead-reckoning because neither ground relative velocity or position is observed directly and errors grow faster.
2017-10-20 14:44:37 +11:00
Paul Riseborough a2dcd5b9b6 EKF: Consolidate no aiding reset logic 2017-10-20 14:44:37 +11:00
Paul Riseborough 929c5c2b37 EKF: enable gps fusion flag to be false while fusing air data 2017-10-20 14:44:37 +11:00
Paul Riseborough 204a218ee6 EKF: Allow dead-reckoning using air data 2017-10-20 14:22:06 +11:00
ChristophTobler f5fd90533a fix gps and flow flag handling
gps flag was not turning false if there was flow

only reset states if we were relying on that sensor only
2017-10-20 14:22:06 +11:00
Paul Riseborough 9857fb9eb6 EKF: publish control limits for optical flow navigation 2017-10-20 14:22:06 +11:00
CarlOlsson 2e03084d34 EKF: If aligning yaw for fw with low GPS velocity, use mag 2017-10-19 16:49:54 +02:00
CarlOlsson c81cdfa1ce EKF: Fix bug when resetting position and velocities for fw due to something else than bad yaw estimate
Signed-off-by: CarlOlsson <carlolsson.co@gmail.com>
2017-10-17 15:08:09 +02:00
CarlOlsson 8c83167857 EKF: fixed comment
Signed-off-by: CarlOlsson <carlolsson.co@gmail.com>
2017-10-17 11:41:55 +02:00
Paul Riseborough 32b795ee10 EKF: Add readme file to EKF documentation directory 2017-10-13 21:46:41 +11:00
Paul Riseborough 8dd4800a2c EKF: Add preliminary documentation for filter mathematics 2017-10-13 21:34:49 +11:00
Paul Riseborough dbff89fbcb EKF: Fix error preventing selection of MAG_FUSE_TYPE_AUTOFW 2017-10-12 19:54:35 +11:00
Paul Riseborough 6f7f05fdc0 EKF: Move MAG_FUSE_TYPE_AUTOFW control to the expected place 2017-10-12 14:50:23 +11:00
Paul Riseborough e834522f62 EKF: Use fixed wing status flag in MAG_FUSE_TYPE_AUTOFW logic 2017-10-12 14:50:23 +11:00
Paul Riseborough 7b4c957ad4 ekf2: Add new mag fusion mode
Adds a mode where mag fusion is only used update the field estimates
2017-10-12 14:50:23 +11:00
Paul Riseborough 9c65968c3d Merge pull request #334 from PX4/pr-ekf_minor_flow_fix
ekf: fix optical flow bugs
2017-10-12 09:14:29 +11:00
Paul Riseborough 68bad48598 Merge pull request #330 from CarlOlsson/pr-add_get_wind_vel_var
EKF: added get_wind_velocity_var function
2017-10-12 09:12:54 +11:00
Paul Riseborough 4db23b7b2e EKF: Don't report terrain estimate invalid immediately when HAGL observations fail checks 2017-10-12 08:26:04 +11:00
Paul Riseborough 1119a9b0ac EKF: Enable optical flow reversion to work if flow data is lost
Also improve reporting.
2017-10-12 08:02:54 +11:00
ChristophTobler cdf6e6cd36 EKF: use delta_time to avoid division by zero 2017-10-11 15:15:06 +02:00
Paul Riseborough d293c4231d EKF: Protect against divide by zero caused by invalid optical flow 2017-10-11 21:54:47 +11:00
Paul Riseborough ab9b8e1964 EKF: Prevent bad optical flow quality causing loss of aiding when on ground 2017-10-11 21:22:33 +11:00
ChristophTobler b7e589b98a EKF: only fuse optical flow if terrain is valid 2017-10-10 17:51:56 +02:00
ChristophTobler 81a64c0479 ekf: fix flow direction when on ground 2017-10-10 14:39:44 +02:00
ChristophTobler 6cb99ce8a8 ekf: add function to get in air status 2017-10-03 22:36:33 +02:00
CarlOlsson 8200e4b218 EKF: added get_wind_velocity_var function
Signed-off-by: CarlOlsson <carlolsson.co@gmail.com>
2017-10-02 14:47:56 +02:00
CarlOlsson 0a7c3ecbc6 EKF: Parameterize maximum angle for rng fusion 2017-09-26 20:53:48 +02:00
Paul Riseborough 160e4d69c1 Merge pull request #323 from PX4/pr-ekfQuatMultOrder
EKF: use hamiltonian convention for quaternion multiplication order
2017-09-21 07:49:35 +10:00
Paul Riseborough 1d3e8edc46 EKF: Fix bug in accumulation of IMU data for flow sensor gyro bias calculation 2017-09-14 18:34:11 +10:00
Paul Riseborough dd5b8525c3 EKF: Use hamiltonian convention for quaternion product order 2017-08-31 11:14:02 +02:00
Paul Riseborough b0300b9723 Revert "attitude_fw delete unused and cleanup"
This reverts commit 25bd3ac5e6.
2017-08-30 16:23:40 +02:00
Daniel Agar 25bd3ac5e6
attitude_fw delete unused and cleanup 2017-08-26 17:44:24 -04:00
Daniel Agar 99ba1c3745
EKF trivial code style cleanup 2017-08-25 10:09:11 -04:00
ChristophTobler 89236ef275 Merge pull request #314 from PX4/pr-check_stuck_rng
Pr check stuck rng
2017-08-21 07:54:06 +02:00
Peter Dürr 305a95aef9 Integrate Python-based tests and benchmark into Travis
* 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
2017-08-14 12:02:03 +02:00
Peter Dürr 15c8c24418 Fix time units on plots
* Time in plots was of by a factor of 1e3 due to wrong conversion from us.
2017-08-14 12:02:03 +02:00
Peter Dürr b29067a188 Better handle Python dependencies
* Add requirements.txt file with required Python packages
* Read requirements.txt from CMakeLists.txt to check dependencies and alert the
  user if necessary.
2017-08-14 12:02:03 +02:00
Peter Dürr bb5719a0da Add Python wrapper to ecl and use it to test functionality
* 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
2017-08-14 12:02:03 +02:00
Peter Dürr 5988900044 Add getters for a few private variables of the EstimatorInterface
* For testing it is useful to have access to more internal states
* For the same reason I also promote the const FILTER_UPDATE_PERIOD_MS to
  public
2017-08-14 12:02:03 +02:00
Peter Dürr a2ed0a76f9 Make the destructor of EstimatorInterface virtual
* 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).
2017-08-14 12:02:03 +02:00
Paul Riseborough 3983ac23fa Merge pull request #316 from PX4/pr-ekfTrueAirspeed
EKF: Add true airspeed accessor
2017-08-11 08:18:04 +10:00
Paul Riseborough 35ffd55481 EKF: Fix incorrect use of double precision operation 2017-08-07 10:34:19 +10:00
Paul Riseborough cc5db74d1b EKF: Add true airspeed accessor 2017-08-07 09:19:48 +10:00
ChristophTobler 8ecec58292 Check for stuck range finder measurements in terrain estimator 2017-07-31 17:59:44 +02:00
ChristophTobler 7252284628 Add check for stuck range finder measurements 2017-07-31 17:59:16 +02:00
ChristophTobler 41f4b62cdb fix indentation 2017-07-31 17:58:03 +02:00
Paul Riseborough 596b8220e2 EKF: Output mag sensor isolation warning first time only 2017-07-31 19:39:07 +10:00
Paul Riseborough ce806768b7 EKF: Improve in-flight mag error detection, recovery and isolation for fixed wing 2017-07-31 19:39:07 +10:00
Paul Riseborough c230663b68 Merge pull request #309 from PX4/pr-ekfYawFusion
EKF: Improve efficiency of yaw fusion for External Vision
2017-07-31 19:37:15 +10:00
Paul Riseborough 3ee6898710 EKF: Enable origin to be maintained when starting aiding using EV only
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.
2017-07-29 15:31:34 +10:00
Paul Riseborough e08da1c599 EKF: Add ability to use EV and GPS data together
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.
2017-07-26 18:06:18 +10:00
Paul Riseborough f3909244f0 EKF: Correct units in comments 2017-07-25 09:17:18 +10:00
Paul Riseborough 20584ee997 EKF: Improve efficiency of heading fusion calculations when using EV heading
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.
2017-07-21 10:56:14 +10:00
Paul Riseborough df34b43c00 Merge pull request #308 from PX4/pr-ekfDoxygen
EKF: Update documentation and make compatible with Doxygen
2017-07-21 10:55:18 +10:00
Paul Riseborough aec01ce59c EKF: Update class variable documentation and make compatible with Doxygen 2017-07-20 20:16:42 +10:00
ChristophTobler 61a7991693 constrain _terrain_vpos to be a minimum of _params.rng_gnd_clearance larger than _state.pos(2) 2017-07-20 08:29:11 +02:00
Paul Riseborough e1fe5b2229 Revert "Revert "Split get_terrain_vert_pos() into valid and get_vpos"" 2017-07-19 17:52:35 +10:00
Paul Riseborough c887b02f21 Revert "Split get_terrain_vert_pos() into valid and get_vpos" 2017-07-19 17:33:48 +10:00
ChristophTobler e429ecab17 check if terrain valid instead of initialized 2017-07-17 16:43:23 +02:00
ChristophTobler eae0522dc2 split into get_terrain_valid and get_terrain_vert_pos 2017-07-17 16:42:42 +02:00
ChristophTobler 517fe8a71f rng aid: use hysteresis with lower hagl check 2017-07-17 13:36:51 +02:00
ChristophTobler 8ed61ac052 init rng offset with ground clearance param when on ground to avoid noisy init 2017-07-13 17:43:19 +02:00
ChristophTobler d2945abd85 return hagl valid false if update was rejected 2017-07-13 14:17:48 +02:00
Paul Riseborough 9ee35e38df EKF: Don't fallback when optical flow is lost if external vision data is being used 2017-07-13 20:21:41 +09:00
Paul Riseborough 1bb576c197 EKF: Allow fallback to non-aiding mode if external vision is lost. 2017-07-13 20:21:41 +09:00
Isaac f96685267e Fixed vision position fusion bug 2017-07-10 13:44:51 +10:00
Paul Riseborough ec2b54fde7 EKF: Ensure normal yaw alignment using mag is performed if GPS method is not 2017-07-08 11:13:40 +02:00
Paul Riseborough d446f66105 EKF: Add a fixed wing mode with setter function 2017-07-08 11:13:40 +02:00
Paul Riseborough f064915889 EKF: Enable planes to recover from bad mag data at start of flight
Adjusts yaw by the amount of the error between GPS and EKF course if innovations are large.
2017-07-08 11:13:40 +02:00
Paul Riseborough 929f205a00 EKF: Changes arising from code review 2017-07-04 08:12:15 +10:00
Paul Riseborough 7b5f55303a EKF: Prevent covariance instability in delta velocity bias state estimation 2017-07-03 21:04:07 +10:00
Paul Riseborough eb1e73ec81 Merge pull request #283 from PX4/ekf_matrix_cleanup
EKF matrix typedef cleanup
2017-07-03 21:02:24 +10:00
Paul Riseborough ae118940b1 Merge pull request #292 from PX4/pr-use_baro_align
use baro for the ekf alignment if range finder is primary height source
2017-07-03 20:31:16 +10:00
Paul Riseborough dfbc9de48e Merge pull request #291 from PX4/pr-ekfWindEstBugFix
EKF: Fix bug affecting wind estimation for planes
2017-07-01 11:06:58 +10:00
ChristophTobler ed8fa16678 use baro for the ekf alignment if range finder is primary height source 2017-06-30 10:28:57 +02:00
Paul Riseborough 59edccca4a EKF: Fix bug in wind estimation for fixed wing 2017-06-30 10:32:54 +10:00
Paul Riseborough ba4a311771 EKF: Update comments for wind estimation logic 2017-06-30 10:32:23 +10:00
Paul Riseborough 8e0cd1bc39 EKF: Add parameter to set initial and max allowed wind uncertainty
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.
2017-06-30 10:31:16 +10:00
ChristophTobler e1274ad28a move faultiness check above pop_first_older_than() and check independent of range aid to switch back to original sensor if available 2017-06-29 17:07:58 +02:00
ChristophTobler 0d9e535acb Use baro if reset to baro from gps and vice versa 2017-06-29 17:07:42 +02:00
ChristophTobler 4a4b0fa604 remove setting rng faulty in ev mode because not checked 2017-06-29 10:01:16 +02:00
ChristophTobler 066c641d61 range aid: switch to baro/gps even if rng aid conditions met and rng faulty 2017-06-29 09:47:02 +02:00
ChristophTobler 2f382c8e0e if hgt mode is range, switch to baro if range is faulty 2017-06-29 09:47:02 +02:00
ChristophTobler e4f36215cb if in range aid mode, check faultiness that otherwise would never change back 2017-06-29 09:47:02 +02:00
ChristophTobler e800de88b6 remove duplicate 2017-06-29 09:47:02 +02:00
Daniel Agar c44488fdb8
EKF matrix typedef cleanup 2017-06-19 11:10:01 -04:00
ChristophTobler 6f5cffafec fix type of range_aid parameter: int -> int32_t 2017-06-15 10:14:59 +02:00
ChristophTobler 1fed209804 fix formatting 2017-06-15 09:10:43 +02:00
Roman 5036967343 barometer does not special height sensor offset because a barometer
offset from the local origin is calculated if the primary source for
height is not baro

Signed-off-by: Roman <bapstroman@gmail.com>
2017-06-15 09:10:43 +02:00
Roman c5d464b821 make range sensor height offset computation more robust
- 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>
2017-06-15 09:10:43 +02:00
Roman 182ea43445 fixed baro offset calculation
- 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>
2017-06-15 09:10:43 +02:00
Roman 39983a7d55 range aid: added hysteresis for switching in and out of range aid
- prevents rapid switching
- added innovation consistency check for using range aid

Signed-off-by: Roman <bapstroman@gmail.com>
2017-06-15 09:10:43 +02:00
Roman 1b92c9b5b3 ekf_helper: fixed resetting height using range finder
- take range sensor offset wrt to IMU into account
- use projection to earth Z axis

Signed-off-by: Roman <bapstroman@gmail.com>
2017-06-15 09:10:43 +02:00
Roman 3778f0921a ekf: enable range finder to be used for estimating height even if it's not
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>
2017-06-15 09:10:43 +02:00
Roman 36bffd2571 ekf: calculate the delta time between consecutive baro measurments
(used for calculating filtered baro offset when primary height source
is not baro)

Signed-off-by: Roman <bapstroman@gmail.com>
2017-06-15 09:10:43 +02:00
Roman a0ab5cf0d7 ekf vel_pos_fusion: added height sensor offset to range innovation calculation
Signed-off-by: Roman <bapstroman@gmail.com>
2017-06-15 09:10:43 +02:00