ardupilot/libraries
Paul Riseborough 410b5825fb AP_NavEKF3: Enable use of EKF-GSF yaw estimate
AP_NavEKF3: Add emergency yaw reset using a Gussian Sum Filter estimate

AP_NavEKF3: Reduce default minimum GPS velocity noise for Copters

Enables fail-safe to be set with more sensitivity and improves tracking accuracy.
Origin values were set using typical GPS performance for receivers on sale 6 years ago. Receiver performance has improved since then.

AP_NavEKF3: Prevent constant mag anomaly yaw resets

Prevents constant magnetic anomaly induced resets that can be triggered when flying with vehicle generated magnetic interference.
Allows for two resets per takeoff. Allowance for two resets is required, becasue a large ground based magnetic yaw anomaly can cause a sufficiently large yaw innovation that two resets in close succession are required.

AP_NavEKF3: Add option to fly without magnetometer

AP_NavEKF3: Rework emergency yaw reset logic

Use a separate external accessor function to request the yaw reset.
Allow reset requests to remain active for a defined period of time.
Tidy up reset function to split out accuracy check.

AP_NavEKF3: Fix vulnerability to lane switch race condition

Prevents the situation where a lane switch results in a lane being selected that does not have the correct yaw. This can occur if the primary lane becomes unhealthy before the external failsafe monitor has time to react.

AP_NavEKF3: Fix EKF_MAG_CAL = 6 behaviours

Fix bug causing the yaw alignment to be performed at startup before the GSF had a valid estimate.
Fix bug causing emergency yaw message to be output for a normal reset.
Fix vulnerability to reported negative yaw variance.
Remove duplicate timer checks.

AP_NavEKF3: Update EK3_MAG_CAL documentation

AP_NavEKF3: Relax yaw gyro bias convergence check when not using mag

AP_NavEKF3: Reduce yaw drift in hover with no yaw sensor

Uses the GSF yaw estimate if available which is better than the EKF's own yaw when no yaw sensor is available.
2020-04-24 09:43:22 +10:00
..
AC_AttitudeControl AC_PosControl: Replace update_vel_controller_xy() with update_xy_controller() 2020-04-21 09:22:45 +10:00
AC_Autorotation AC_Autorotation: convert to new get_rpm() API 2020-03-12 08:36:40 +11:00
AC_AutoTune AC_AutoTune: add ATDE log message documentation 2020-04-12 08:36:48 +10:00
AC_Avoidance AC_Avoidance: rename APMrover2 to Rover 2020-04-14 09:50:34 +09:00
AC_Fence AC_Fence: rename APMrover2 to Rover 2020-04-14 09:50:34 +09:00
AC_InputManager AC_InputManager: tradheli-Fix parameter metadata errors 2020-01-13 12:41:30 -05:00
AC_PID AC_PID: added AC_PI controller 2019-11-02 16:31:04 +11:00
AC_PrecLand AC_PrecLand: POS param range of 5m and 1cm increment 2020-02-01 08:46:03 +09:00
AC_Sprayer AC_Sprayer: make configurable in hwdef.dat 2020-01-18 13:48:48 +11:00
AC_WPNav AC_Circle: z-axis target only updated during terrain following 2020-04-21 11:39:38 +09:00
AP_AccelCal AP_AccelCal: adjust for new vehicle base class 2019-10-08 11:26:04 +11:00
AP_ADC AP_ADC: remove keywords.txt 2019-02-17 22:19:08 +11:00
AP_ADSB AP_ADSB: add missing break statement 2020-01-15 13:55:42 +11:00
AP_AdvancedFailsafe AP_AdvancedFailsafe: correct WP_GPS_LOSS param documentation block 2020-02-19 15:09:16 +11:00
AP_AHRS AP_AHRS: remove writeExtNavData sensOffset argument 2020-04-14 10:28:03 +10:00
AP_Airspeed AP_Airspeed: rename APMrover2 to Rover 2020-04-14 09:50:34 +09:00
AP_Arming AP_Arming: Display mag field value 2020-04-21 10:51:48 +09:00
AP_Avoidance AP_Avoidance: make all semaphores recursive 2020-01-19 20:19:30 +11:00
AP_Baro AP_Baro: fixed build warning 2020-04-20 07:10:21 +10:00
AP_BattMonitor AP_BattMonitor: rename APMrover2 to Rover 2020-04-14 09:50:34 +09:00
AP_Beacon AP_Beacon: pozyx: remove dead and pointless code 2020-04-01 15:42:47 +09:00
AP_BLHeli AP_BlHeli: always report test results and report band channel once 2020-02-04 10:38:20 +11:00
AP_BoardConfig AP_BoardConfig: add HEAT log message documentation 2020-04-12 08:36:48 +10:00
AP_Button AP_Button: add crude debouncing and get_button_state function 2020-03-19 14:59:34 -07:00
AP_Camera AP_Camera: add RunCam device type 2 documentation 2020-04-06 20:27:32 +10:00
AP_Common AP_Common: use standard realloc method from HAL 2020-03-24 10:32:14 +11:00
AP_Compass AP_Compass: add documentation for COFS, compass-learning message 2020-04-14 07:34:59 +10:00
AP_Declination AP_Declination: re-generate mag tables 2019-12-24 11:33:10 +11:00
AP_Devo_Telem AP_Devo_Telem: add floating point constant designators 2019-04-05 23:04:17 -07:00
AP_EFI AP_EFI: add EFI log message documentation 2020-04-12 08:36:48 +10:00
AP_ESC_Telem AP_ESC_Telem: wrapper for ESCs with feedback 2020-02-12 11:58:34 +09:00
AP_Filesystem AP_Filesystem: use @ROMFS 2020-03-28 15:28:03 +11:00
AP_FlashStorage AP_FlashStorage: fixed build warning 2020-04-19 13:36:24 +10:00
AP_Follow AP_Follow: rename APMrover2 to Rover 2020-04-14 09:50:34 +09:00
AP_Frsky_Telem AP_Frsky_Telem: fix for protocol=4 GAlt=0 and GSPd=0 2020-03-31 13:09:35 +11:00
AP_GPS AP_GPS: leave uart2 config enabled when using uart2 MB setup 2020-04-21 15:30:54 +10:00
AP_Gripper AP_Gripper: use https:// scheme for ardupilot URLs 2019-12-10 07:53:46 +11:00
AP_GyroFFT AP_GyroFFT: inline used-only-once Log_Write parameters 2020-03-22 18:35:14 +11:00
AP_HAL AP_HAL: added wait_pin() API 2020-04-23 07:28:13 +10:00
AP_HAL_ChibiOS HAL_ChibiOS: enable IMU temp control on CUAV-X7 2020-04-23 09:05:52 +10:00
AP_HAL_Empty AP_HAL_Empty: empty implementation of HAL FFT 2020-02-22 11:15:37 +11:00
AP_HAL_Linux AP_HAL_Linux: Add missing wscript for GPIOTest 2020-04-17 15:59:25 +10:00
AP_HAL_SITL AP_HAL_SITL: add simulated mavlink-attached rangefinder 2020-04-21 20:44:59 +10:00
AP_Hott_Telem AP_Hott_Telem: fixed GPS display for mz-32 2020-04-17 11:23:06 +10:00
AP_ICEngine AP_ICEngine: convert to new get_rpm() API 2020-03-12 08:36:40 +11:00
AP_InertialNav AP_InertialNav: use ekf::get_vert_pos_rate during high vibration 2019-10-18 11:15:25 +09:00
AP_InertialSensor AP_InertialSensor: use wait_pin() to wait for DRDY pin if available 2020-04-23 07:28:13 +10:00
AP_InternalError AP_InternalError: add a bit for infinite recursion in switch_full_sector 2020-04-12 09:43:13 +10:00
AP_IOMCU AP_IOMCU: add IOMC log message documentation 2020-04-12 08:36:48 +10:00
AP_IRLock AP_IRLock: removed unusued AP_Common/Semaphore.h 2019-05-15 15:33:48 +10:00
AP_JSButton
AP_KDECAN AP_KDECAN: fixed build error on Linux 2019-12-31 11:38:30 +11:00
AP_L1_Control AP_L1_Control: wrap_180_cd no longer solely returns floats 2019-09-18 12:57:02 +10:00
AP_Landing AP_Landing: add LAND log message documentation 2020-04-12 08:36:48 +10:00
AP_LandingGear AP_LandingGear: add OPTIONS param to auto deploy and retract 2020-02-26 08:01:00 +09:00
AP_LeakDetector AP_LeakDetector: Mark Leak pins RebootRequired 2019-09-09 09:53:28 -07:00
AP_Logger AP_Logger: fix examples 2020-04-23 11:33:41 +09:00
AP_LTM_Telem AP_LTM_Telem: LTM telemetry support 2019-11-26 12:14:13 +11:00
AP_Math AP_Math: alternative quaternion rotation test 2020-04-09 19:41:08 +09:00
AP_Menu AP_Menu: use strtof() instead of atof() 2019-10-28 15:53:16 +11:00
AP_Mission AP_Mission: Added immediate trigger for DO_SET_CAM_TRIGG_DIST 2020-03-31 10:05:40 +11:00
AP_Module AP_Module: update example baro include 2019-06-27 14:56:21 +10:00
AP_Motors AP_Motors: MotorsMulticopter fix floating boost output 2020-03-02 18:22:30 +09:00
AP_Mount AP_Mount: convert Solo gimbal messages to TimeUS from TimeMS 2020-04-15 16:11:04 +10:00
AP_NavEKF AP_NavEKF: Add yaw estimator class using Gaussian Sum Filter 2020-04-24 09:43:22 +10:00
AP_NavEKF2 AP_NavEKF2: CorrectExtNavForSensorOffset made const 2020-04-21 10:21:23 +10:00
AP_NavEKF3 AP_NavEKF3: Enable use of EKF-GSF yaw estimate 2020-04-24 09:43:22 +10:00
AP_Navigation
AP_NMEA_Output AP_NMEA_Output: EKF objects have moved into AP_AHRS_NavEKF 2020-01-21 11:53:18 +11:00
AP_Notify AP_Notify: remove recursive call to play in next_action 2020-03-31 11:06:30 +11:00
AP_OpticalFlow AP_OpticalFlow: add orient-yaw parameter units 2020-02-03 19:35:40 +09:00
AP_OSD AP_OSD: avoid build when OSD disabled 2020-03-28 15:28:03 +11:00
AP_Parachute AP_Parachute: default to parachute enabled 2020-01-18 13:48:48 +11:00
AP_Param AP_Param: panic if defaults file load fails 2020-04-18 21:51:16 +10:00
AP_PiccoloCAN AP_PiccoloCAN: fixed build error on Linux 2019-12-31 11:38:30 +11:00
AP_Proximity AP_Proximity: TeraRangerTower uses intermediate serial class 2020-02-19 11:12:37 +09:00
AP_Radio AP_Radio: correct for recent semaphore bool/void changes 2020-03-03 21:56:33 +09:00
AP_Rally AP_Rally: rename APMrover2 to Rover 2020-04-14 09:50:34 +09:00
AP_RAMTRON AP_RAMTRON: fixed build with gcc 9.x 2020-04-01 17:08:48 +11:00
AP_RangeFinder AP_RangeFinder: rename APMrover2 to Rover 2020-04-14 09:50:34 +09:00
AP_RCMapper AP_RCMapper: add singleton 2019-12-30 13:02:04 +11:00
AP_RCProtocol AP_RCProtocol: fixed buffer overflow in st24 parser 2020-04-21 06:02:29 +10:00
AP_Relay AP_Relay: change parameter name from relay to instance 2019-09-27 12:02:38 +10:00
AP_RobotisServo AP_RobotisServo: fix includes place and order 2019-03-26 10:27:54 +11:00
AP_ROMFS AP_ROMFS: added directory listing interface 2020-03-28 15:28:03 +11:00
AP_RPM AP_RPM: allow harmonic notch driver to appear as RPM values. 2020-04-14 09:43:16 +10:00
AP_RSSI AP_RSSI: Fix duplicate values in ANA_PIN 2020-03-24 10:26:04 +11:00
AP_RTC AP_RTC: make all semaphores recursive 2020-01-19 20:19:30 +11:00
AP_SBusOut AP_SBusOut: fix includes place and order 2019-03-26 10:27:54 +11:00
AP_Scheduler AP_Scheduler: allow registration of tasks at loop rate 2020-02-22 11:15:37 +11:00
AP_Scripting AP_Scripting: Cleanups to remove false posive warnings 2020-03-28 21:16:09 +11:00
AP_SerialLED AP_SerialLED: support ProfiLEDs 2020-03-10 10:37:26 +11:00
AP_SerialManager AP_SerialManager: Add a description 2020-02-26 12:18:40 +11:00
AP_ServoRelayEvents AP_ServoRelayEvents: do-set-servo affects sprayer and gripper 2020-02-11 11:08:02 +11:00
AP_SmartRTL AP_SmartRTL: EKF objects have moved into AP_AHRS_NavEKF 2020-01-21 11:53:18 +11:00
AP_Soaring AP_Soaring: Add log documentation. 2020-04-08 09:11:54 +10:00
AP_SpdHgtControl AP_TECS: Add flags to indicate gliding flight, and use these with AP_Soaring. 2020-04-08 09:11:54 +10:00
AP_Stats AP_Stats: make all semaphores recursive 2020-01-19 20:19:30 +11:00
AP_TECS AP_TECS: Update descriptions of pitch feed-forward parameters. 2020-04-08 09:11:54 +10:00
AP_TempCalibration AP_TempCalibration: Include needed AP_Baro.h 2019-06-27 14:56:21 +10:00
AP_TemperatureSensor AP_TemperatureSensor: fix TSYS01 warning on SITL 2020-02-05 17:10:58 -05:00
AP_Terrain AP_Terrain: Avoid update() IO operations when not enabled 2020-01-26 10:35:29 +11:00
AP_ToshibaCAN AP_ToshibaCAN: Using the maximum number of ESCs definition 2020-04-20 10:12:57 +09:00
AP_Tuning AP_Tuning: add documentation for PRTN message 2020-04-14 07:34:59 +10:00
AP_UAVCAN AP_UAVCAN: make all semaphores recursive 2020-01-19 20:19:30 +11:00
AP_Vehicle AP_Vehicle: rename APMrover2 to Rover 2020-04-14 09:50:34 +09:00
AP_VisualOdom AP_VisualOdom: T265 supports vision-position-delta 2020-04-18 08:07:20 +09:00
AP_Volz_Protocol
AP_WheelEncoder AP_WheelEncoder: add param docs for new PID filter parameters 2020-02-19 15:09:16 +11:00
AP_Winch AP_Winch: use enum-class for SRV_CHANNEL_LIMIT_TRIM and friends 2019-11-26 10:17:17 +11:00
AP_WindVane AP_WindVane: Fix duplicate values in Param 2020-03-24 10:26:04 +11:00
APM_Control APM_Control: validate parameter ARSPD_FBW_MIN 2020-04-02 19:43:06 -07:00
AR_WPNav AR_WPNav: remove unneeded overshoot methods 2019-10-23 08:28:39 +08:00
doc
Filter Copter: port betaflight in-flight fft analysis to arducopter and expose as a log message 2020-02-22 11:15:37 +11:00
GCS_MAVLink GCS_MAVLink: remove ahrs3 2020-04-22 14:11:17 +09:00
PID Global: rename desired to target in PID info 2019-07-25 17:38:15 +09:00
RC_Channel RC_Channel: rover option param desc gets Viso Align 2020-04-22 10:34:18 +09:00
SITL SITL: update flightaxis defaults 2020-04-22 12:36:03 +10:00
SRV_Channel SRV_Channels: fix unannotated fall-through between switch labels 2020-04-01 17:10:36 +11:00
StorageManager StorageManager: use pragmas to set storage layout rather than call 2020-01-28 11:34:51 +11:00