Andrew Tridgell
51223409be
HAL_ChibiOS: fixed iomcu build with flash driver
2019-05-28 17:47:19 +09:00
Andrew Tridgell
25aaefa0e6
HAL_SITL: added empty flash driver
2019-05-28 17:47:19 +09:00
Andrew Tridgell
33eecbb696
HAL_Linux: added empty flash driver
2019-05-28 17:47:19 +09:00
Andrew Tridgell
c9eb9d8076
HAL_Empty: added empty flash driver
2019-05-28 17:47:19 +09:00
Andrew Tridgell
e4aae50e44
HAL_ChibiOS: implement flash driver
2019-05-28 17:47:19 +09:00
Andrew Tridgell
608fd54f62
AP_HAL: added hal.flash driver
...
needed for semaphore
2019-05-28 17:47:19 +09:00
Andrew Tridgell
2fbe6edf47
AP_HAL: added save/restore of attitude in backup registers
2019-05-28 17:47:19 +09:00
Andrew Tridgell
952ef7c361
HAL_ChibiOS: added save/restore of attitude in backup registers
2019-05-28 17:47:19 +09:00
Andrew Tridgell
46bb88173e
AP_AHRS: added save/restore of attitude in backup registers
2019-05-28 17:47:19 +09:00
Andrew Tridgell
3bd1a08c5e
HAL_ChibiOS: fixed build with older gcc
2019-05-28 17:47:19 +09:00
Andrew Tridgell
4fc4573f81
AP_AHRS: save/restore home to backup registers
...
restore on watchdog reset
2019-05-28 17:47:19 +09:00
Andrew Tridgell
db35064c95
HAL_ChibiOS: save/restore home position in backup registers
2019-05-28 17:47:19 +09:00
Andrew Tridgell
a42293b986
AP_HAL: added save/restore of home to backup registers
2019-05-28 17:47:19 +09:00
Andrew Tridgell
12dfccf65a
AP_InertialSensor: prevent watchdog in accelcal
2019-05-28 17:47:19 +09:00
Andrew Tridgell
020ce245b9
HAL_ChibiOS: allow for delay in bootloader flash
2019-05-28 17:47:19 +09:00
Andrew Tridgell
3222084f2d
HAL_ChibiOS: fixed watchdog timeout setting
2019-05-28 17:47:19 +09:00
Andrew Tridgell
756a629b24
GCS_MAVLink: added method to lockup autopilot
...
used for watchdog testing
# Conflicts:
# libraries/GCS_MAVLink/GCS_Common.cpp
2019-05-28 17:47:19 +09:00
Andrew Tridgell
27aba29109
AP_Logger: prevent log erase from triggering watchdog
...
# Conflicts:
# libraries/DataFlash/DataFlash_File.cpp
2019-05-28 17:47:19 +09:00
Andrew Tridgell
a378f2b8fa
AP_Logger: force logging on an armed watchdog reset
...
and don't clear sdcard space
2019-05-28 17:47:19 +09:00
Andrew Tridgell
f217f504e5
HAL_ChibiOS: implement was_watchdog_armed()
2019-05-28 17:47:19 +09:00
Andrew Tridgell
44e3b20038
AP_HAL: added was_watchdog_armed()
...
allow decisions to be based on whether this is a watchdog reset and we
were armed
2019-05-28 17:47:19 +09:00
Andrew Tridgell
682362945c
AP_BoardConfig: auto-restore safety state on watchdog reset
...
# Conflicts:
# libraries/AP_BoardConfig/board_drivers.cpp
2019-05-28 17:47:19 +09:00
Andrew Tridgell
4edd270bd9
HAL_ChibiOS: added ability to restore safety state on watchdog reset
...
# Conflicts:
# libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c
2019-05-28 17:47:19 +09:00
Andrew Tridgell
92f12deb51
AP_HAL: added was_watchdog_safety_off()
...
used to restore safety state on watchdog reset
2019-05-28 17:47:19 +09:00
Andrew Tridgell
6c7fd8e9ed
HAL_ChibiOS: change to 2s timeout on watchdog
...
a bit more of a safety net against false positives for stable release
2019-05-28 17:47:19 +09:00
Andrew Tridgell
6361482ba6
HAL_ChibiOS: fixed watchdog on H7
2019-05-28 17:47:19 +09:00
Andrew Tridgell
f4d8026d6d
AP_Compass: flag compass cal as long expected delay
2019-05-28 17:47:19 +09:00
Andrew Tridgell
de2ae7ad24
HAL_ChibiOS: implement scheduler->expect_delay_ms()
...
# Conflicts:
# libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
# libraries/AP_HAL_ChibiOS/Scheduler.h
2019-05-28 17:47:19 +09:00
Andrew Tridgell
2590457c75
AP_Logger: handle long delays in opening log files
2019-05-28 17:47:19 +09:00
Andrew Tridgell
a341eebe69
AP_HAL: added expect_delay_ms() to Scheduler
...
used to notify scheduler of long expected delay in main thread
2019-05-28 17:47:19 +09:00
Andrew Tridgell
8cd0133a4d
HAL_ChibiOS: added commented out test code for watchdog
2019-05-28 17:47:19 +09:00
Andrew Tridgell
43dfc67b96
AP_Baro: skip cal on watchdog reset
2019-05-28 17:47:19 +09:00
Andrew Tridgell
69528a9892
AP_Airspeed: skip cal on watchdog reset
2019-05-28 17:47:19 +09:00
Andrew Tridgell
e105bf258c
AP_InertialSensor: skip gyro cal on watchdog reset
2019-05-28 17:47:19 +09:00
Andrew Tridgell
0f0fdf1398
HAL_ChibiOS: implement was_watchdog_reset()
...
# Conflicts:
# libraries/AP_HAL_ChibiOS/Util.h
2019-05-28 17:47:19 +09:00
Andrew Tridgell
44b6a70377
AP_HAL: added was_watchdog_reset()
...
# Conflicts:
# libraries/AP_HAL/Util.h
2019-05-28 17:47:19 +09:00
Andrew Tridgell
4858506a0b
HAL_ChibiOS: record reason for reset
...
allows us to tell if reset was due to watchdog
2019-05-28 17:47:19 +09:00
Andrew Tridgell
96923da60c
HAL_ChibiOS: use BRD_OPTIONS to enable watchdog
...
# Conflicts:
# libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
2019-05-28 17:47:19 +09:00
Andrew Tridgell
78e234bb6f
AP_BoardConfig: added BRD_OPTIONS
...
used to enable STM32 watchdog
# Conflicts:
# libraries/AP_BoardConfig/AP_BoardConfig.cpp
# libraries/AP_BoardConfig/AP_BoardConfig.h
2019-05-28 17:47:19 +09:00
Andrew Tridgell
a7906f9e42
HAL_ChibiOS: added IWDG watchdog support
...
this resets the MCU if the main loop stops for 1 second
# Conflicts:
# libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
2019-05-28 17:47:19 +09:00
Guglielmo
234b3391a9
AP_HAL_SITL: fix pthread SITL build on MacOS
2019-05-28 17:47:19 +09:00
Andrew Tridgell
d58bb700a3
HAL_ChibiOS: fixed brick2 valid status in POWR flags for fmuv5
...
and fixed sense of VBUS
2019-05-03 10:34:08 +10:00
Phillip Kocmoud
57f2f1488e
AP_Compass: Increase default MAX compass offset
...
After discussing the @tridge and @rmackay9 it was suggested that raising the maximum allowable compass offset value would allow users of the LIS3MDL and possibly others with larger compass offsets to fly with the default setting.
This has been deemed a fairly safe change that still allows for sufficient overhead to prevent saturation.
2019-04-30 12:42:14 +09:00
Michael du Breuil
35706def4d
AP_GPS: Log reciever status to GPS SD card
...
This improves log analysis of bad GPS health messages when you have a
report of bad GPS health but lost the MAVLink message, or didn't have
access to the autopilot log with the information for some reason.
2019-04-30 10:48:59 +09:00
Michael du Breuil
94cc27a2f6
AP_GPS: Remove external event from GPS data stream
...
If the event pin floats, this can lead to UART congestion, causing the
EKF to reject the GPS data, and the vehicle will drift around the sky in
a most disturbing manner
2019-04-30 10:48:56 +09:00
Francisco Ferreira
09c210e10f
AP_GPS: use proper macro in array sizes
2019-04-30 10:48:54 +09:00
Francisco Ferreira
75527ef567
AP_GPS: correct blending check
2019-04-30 10:48:51 +09:00
Francisco Ferreira
d88d8fc178
AP_GPS: fix out-of-bounds array access
2019-04-30 10:48:49 +09:00
Michael du Breuil
958b7866c9
AP_GPS: Ensure a lag value is always provided
...
The value may not be the optimal value for the driver, but we should
always try to provide a value for the caller
2019-04-30 10:48:46 +09:00
Andrew Tridgell
b1f441abd4
HAL_ChibiOS: mark SDIO and SDMMC IO as pullup
...
this is needed for boards such as PixhackV3 which don't have hardware
pullups. Thanks to Hongle for reporting this.
2019-04-30 10:48:00 +09:00
Randy Mackay
2d1e02fada
AP_OpticalFlow: support cx-of on all boards
2019-04-30 10:47:49 +09:00
Andrew Tridgell
b26ae4594f
HAL_ChibiOS: change CUAVv5Nano default PWM count to 11
2019-04-30 10:47:38 +09:00
Andrew Tridgell
fc86a7db11
HAL_ChibiOS: fixed CUAVv5Nano uarts
2019-04-30 10:47:36 +09:00
Andrew Tridgell
a9c868a154
HAL_ChibiOS: support for CUAVv5Nano board
...
F765 with no IOMCU
2019-04-30 10:47:34 +09:00
Andrew Tridgell
06cfdedfb2
HAL_ChibiOS: fixed fallback to microSD for storage
...
this is used when FRAM fails on a board with microSD support. The
double init caused the validate() in the FATFS code to fail
2019-04-30 10:47:31 +09:00
Andrew Tridgell
481a6ea570
AP_Rangefinder: probe all I2C buses for rangefinders
2019-04-30 10:47:28 +09:00
Andrew Tridgell
87ae7ac422
AP_InertialSensor: don't set INS_ENABLE_MASK to found IMUs
...
this is needed for detection of failed cubes
2019-04-24 12:24:12 +10:00
Andrew Tridgell
edffc3001b
AP_AHRS: ensure AHRS never uses an unhealthy gyro
2019-04-24 11:47:56 +10:00
Jonathan Challinger
c630a87e37
AP_BoardConfig: add targetted check for cube black internal sensors
2019-04-24 11:47:56 +10:00
Jonathan Challinger
10c930d62d
AP_Baro: make crc4 a static member of AP_Baro_MS56xx
2019-04-24 11:47:56 +10:00
Jonathan Challinger
b02d58444f
AP_HAL_ChibiOS: add define HAL_CHIBIOS_ARCH_CUBEBLACK to cubeblack hwdef
2019-04-24 11:47:08 +10:00
Andrew Tridgell
a9b5a0fea0
AC_WPNav: prevent I term buildup during landing
...
this prevents I term buildup in the XY velocity controller during
landing. This to account for the EKF giving a non-zero horizontal
velocity when we have touched down. The I term buildup in the XY
velocity controller can lead to the attitude error going above the
level for disabling the relax function as the throttle mix is
changed. That results in large motor outputs which can tip over the
vehicle after touchdown.
Thanks to Leonard for the suggestion
2019-02-27 20:06:15 +09:00
Andrew Tridgell
6668a2e602
AP_RangeFinder: fixed lightware serial with LW20 lidar
...
it needs a longer serial write to force it to serial mode from i2c
2019-02-27 20:06:06 +09:00
Andrew Tridgell
f04efe7985
HAL_ChibiOS: allocate threads from any heap
...
this fixes a failure on MatekF405-Wing where it fails to allocate the
SPI thread for the IMU
2019-02-27 11:59:45 +11:00
Andrew Tridgell
5ce1c14674
AP_NavEKF3: fixed EKF compass switching
...
when we had 3 compasses the lack of the 'break' meant when we switched
compass in flight we would always switch back instantly to the one
that we had just rejected.
2019-02-09 16:02:08 +11:00
Andrew Tridgell
95522b5486
AP_NavEKF2: fixed EKF compass switching
...
when we had 3 compasses the lack of the 'break' meant when we switched
compass in flight we would always switch back instantly to the one
that we had just rejected.
2019-02-09 16:02:08 +11:00
Andrew Tridgell
f614dcbb18
AP_Compass: change to 3 compasses in SITL
2019-02-09 16:02:08 +11:00
Andrew Tridgell
30d11f6a40
Filter: fixed crash on zero cutoff frequency
...
this fixes #10435
2019-02-09 16:02:08 +11:00
Andrew Tridgell
5a0e0179d8
HAL_ChibiOS: fixed mini-pix uart order
2019-02-09 16:02:08 +11:00
Andrew Tridgell
2f7121a073
HAL_ChibiOS: fixed CAN on Pixhawk4 and PH4-mini
...
the silent pins floating disabled CAN
2019-02-09 16:02:08 +11:00
Andrew Tridgell
b72378db9c
HAL_ChibiOS: setup APJ board IDs in environment
2019-02-09 12:27:35 +09:00
Randy Mackay
835c0d8991
AC_PosControl: remove unnecessary init of last_update_xy_ms
2019-02-02 11:34:38 +09:00
hongle
44da0d03d7
AP_RSSI: add V5 Nano to the RSSI_ANA_PIN param description
2019-02-02 10:34:49 +09:00
Michael du Breuil
d93eb0306d
AP_RSSI: Remove APM doc references
2019-02-02 10:34:48 +09:00
Randy Mackay
df4dcf3c8f
AC_PosControl: constify dt calcs
2019-02-02 10:34:47 +09:00
Randy Mackay
0929d0333b
AC_WPNav: use dt from pos controller
2019-02-02 10:34:46 +09:00
Randy Mackay
4f74075e53
AC_PosControl: increase accuracy of dt calcs
2019-02-02 10:34:45 +09:00
Peter Barker
2550c9922d
AP_RSSI: make RSSI work on ChibiOS
2019-02-01 14:01:10 +09:00
Rob Ratcliff
6af9be44a7
RC_Channel: treat UINT16_MAX as a value of 0 in set_override
...
Addresses ignore R/C override issue documented here:
https://github.com/ArduPilot/ardupilot/issues/1667
2019-01-24 11:20:10 +09:00
Andrew Tridgell
fa365b6f8d
HAL_ChibiOS: disable USART6_TX on fmuv5
...
this prevents it acting as a pullup on SBUS input for Pixhawk4. Thanks
to David Sidrane for the suggestion.
This also enables the extra 3 PWMs for PH4-mini
2019-01-18 09:45:00 +11:00
Andrew Tridgell
55e362e470
AP_HAL_ChibiOS: Fix FMUv2 LED lighting up
2019-01-14 12:22:47 +11:00
Andrew Tridgell
d9b6c6e0c9
AP_RCProtocol: on DSM sync error don't reset channel count
...
this fixes the issue noticed by Andreyl in 3.6.5rc1
2019-01-14 12:05:29 +11:00
Andrew Tridgell
bbe09c4b59
AP_BoardConfig: fixed build
2019-01-11 12:02:59 +11:00
Andrew Tridgell
ee87621ed4
HAL_ChibiOS: fixes for DrotekP3Pro
2019-01-11 12:02:59 +11:00
Kevin Lopez Alvarez
71412f4deb
AP_BoardConfig: add ChibiOS FMUv4pro defines
2019-01-11 12:02:59 +11:00
Kevin Lopez Alvarez
85e79f87f6
AP_HAL: add ChibiOS FMUv4pro
2019-01-11 12:02:59 +11:00
Kevin Lopez Alvarez
dd66c8919c
HAL_ChibiOS: add MCU tables for STM32F469
2019-01-11 12:02:59 +11:00
Kevin Lopez Alvarez
3a06e866a7
HAL_ChibiOS: add DrotekP3Pro hardware definitions
2019-01-11 12:02:59 +11:00
Andrew Tridgell
9ed3e9eec5
HAL_ChibiOS: fixed build of sdcard
2019-01-11 09:48:16 +09:00
Andrew Tridgell
a03b569d43
DataFlash: allow startup with no microSD
...
this allows logging to work with insert after boot
2019-01-11 09:48:16 +09:00
Andrew Tridgell
02987b7614
HAL_ChibiOS: try to mount microSD after boot
2019-01-11 09:48:16 +09:00
Andrew Tridgell
638b3b80d2
HAL_ChibiOS: log stdout to USB on mindpx-v2
2019-01-11 09:48:16 +09:00
Andrew Tridgell
ff67c83bc1
HAL_ChibiOS: allow mount of microSD after boot
...
when disarmed, try to mount sd card every 3s
2019-01-11 09:48:16 +09:00
Andrew Tridgell
da21947fe9
HAL_ChibiOS: fixed card inserted test for SDC
2019-01-11 09:48:16 +09:00
Andrew Tridgell
bccddf3701
AP_BoardConfig: added BRD_SD_SLOWDOWN parameter
...
allows for reduction in microSD clock speed
2019-01-11 09:48:16 +09:00
Andrew Tridgell
6fb84cfa6b
HAL_ChibiOS: support microSD slowdown
...
allow use of BRD_SD_SLOWDOWN to slow down clock on microSD
2019-01-11 09:48:16 +09:00
Andrew Tridgell
e1889fbf66
AP_HAL: added set_slowdown() to SPIDevice
...
used to slow down a SPI device below normal high speed operation
2019-01-11 09:48:16 +09:00
Andrew Tridgell
058980a94d
AP_HAL: added fs_init() to Util API
2019-01-11 09:48:16 +09:00
Andrew Tridgell
32d0137c08
AP_RCProtocol: bring up to date with master
...
this adds new RC protocol decoders for SRXL, SUMD and ST24 as well as
updating to latest soft-serial decoder
2019-01-11 09:31:27 +09:00
Siddharth Purohit
043c303146
HAL_ChibiOS: add CubePurple/PH2Slim board config
2019-01-11 09:16:16 +09:00