Michael du Breuil
a0475874a7
AP_GPS: UBLOX: Parse RELPOSNED messages
...
This does not yet:
- validate the receiver configuration
- manage timing out stale GPS heading info
- relPosNormalized usage isn't clear, which may defeat the STRICT_LENGTH_CHECK
2020-02-05 10:13:53 +11:00
Michael du Breuil
624ed28ef8
AP_Logger: Log GPS yaw accuracy
2020-02-05 10:13:53 +11:00
Michael du Breuil
7b9d3594fb
AP_Scripting: Fix generation of uint32_t arguments
...
This also fixes the message interval description not generating
correctly, it must have been manually edited before
2020-02-05 10:13:53 +11:00
Andrew Tridgell
45a6df0cee
HAL_ChibiOS: drop mRoControlZeroF7 DPS310 clock to 5MHz
2020-02-05 10:13:53 +11:00
Randy Mackay
ba8e916e44
GCS_Mavlink: handle_preflight_reboot made virtual
2020-02-05 10:13:53 +11:00
Henry Wurzburg
40af63daf3
AP_HAL_ChibiOS/hwdef: update KakuteF4 readme
2020-02-05 10:13:52 +11:00
Andy Piper
be2ef926b0
AP_HAL_ChibiOS: hardware definitions for Kakute F7 Mini
2020-02-05 10:13:52 +11:00
Andy Piper
3d289d105b
Filter: set the harmonic notch filter ref default to zero (disabled)
...
Modify parameter descriptions for tradheli
2020-02-05 10:13:52 +11:00
Leonard Hall
39f07e9ee7
AP_Motors: Add variable to record the final thrust value
...
Add Throttle_Out for other frames
2020-02-05 10:13:52 +11:00
Andrew Tridgell
4a16e791d6
AP_InertialSensor: publish an IMU temperature
...
makes testing of mavlink extension easier
2020-02-05 10:13:52 +11:00
Andrew Tridgell
a832c3bff0
GCS_MAVLink: supply IMU temperature in mavlink extensions
2020-02-05 10:13:52 +11:00
Andrew Tridgell
339da0d07f
HAL_ChibiOS: fixed padding of neopixel bits
...
lack of padding at start caused occasional glitches in colors
displayed
2020-02-05 10:12:13 +11:00
Peter Barker
7c5e84d572
AP_Proximity: declare RangeFinder as a class to avoid circular include issue
2020-02-05 10:12:13 +11:00
Peter Barker
f0ee5a6aea
AP_BoardConfig: correct include of AP_Vehicle_Type
2020-02-05 10:12:13 +11:00
Peter Barker
f5fc308f9e
DataFlash: adjust for new vehicle base class
2020-02-05 10:12:13 +11:00
Peter Barker
5818d86420
AP_Mission: adjust for new vehicle base class
2020-02-05 10:12:13 +11:00
Peter Barker
31065bc9d2
AP_Compass: adjust for new vehicle base class
2020-02-05 10:12:13 +11:00
Peter Barker
55eab1546d
AP_AccelCal: adjust for new vehicle base class
2020-02-05 10:12:13 +11:00
Peter Barker
245152e91b
AC_AttitudeControl: adjust for new vehicle base class
2020-02-05 10:12:13 +11:00
Peter Barker
dbb1f01445
AP_Vehicle: move many members up to base class
2020-02-05 10:12:13 +11:00
Peter Barker
6db60ec711
AP_Arming: remove bogus ARMING_CHECK_NONE 'bitmask value'
...
This looks like a bitmask value, but if you treat it like one (and
people have in the past!) by using logical operations then you get the
incorrect result.
Places which were checking for equivalence to ARMING_CHECK_NONE now
simply check the bitmask to see if it is all-empty.
2020-02-05 10:12:13 +11:00
murata
73a9f31424
AP_Motors: Change to description(NFC)
2020-02-05 10:12:13 +11:00
Andrew Tridgell
a34b135a57
AP_BoardConfig: fixed CAN init without SLCAN
2020-02-05 10:12:13 +11:00
Henry Wurzburg
2c3d57a373
Rover: implement steering trim save in armed/manual mode only
2020-02-05 10:12:13 +11:00
Randy Mackay
da0c1d1b42
AP_Follow: add clear_offsets_if_required method
...
this restores the offsets to zero if they were initialised from zero when the lead vehicle was first spotted
2020-02-05 10:10:37 +11:00
Ebin
767cabf8e5
SITL: Yaw rate calculation uses wheel offset
2020-02-05 10:10:37 +11:00
Peter Barker
63e8c5abcb
AP_WheelEncoder: add SITL backend
...
AP_WheelEncoder: added update function for SITL quadrature encoder
2020-02-05 10:10:37 +11:00
Peter Barker
e6346587d7
AP_Logger: tidy MessageWriter stages using enum class
2020-02-05 10:10:37 +11:00
Henry Wurzburg
d95cbc81b3
AP_BLHeli: Change descriptions in SERVO_BLH_PORT param to actual AP port
2020-02-05 10:10:37 +11:00
Andrew Tridgell
4638c57819
AP_Motors: enable docs for hover thr learning in plane
2020-02-05 10:10:37 +11:00
Randy Mackay
59f2b42bd9
AP_SmartRTL: fixup compile error
...
fix typo introduced by me attempting a minor fixup before merging
2020-02-05 10:10:37 +11:00
Peter Barker
2deea7835f
AP_Logger: correct uninitialised value when logging all rally points
2020-02-05 10:10:37 +11:00
Henry Wurzburg
6f5d9a686e
AP_SmartRTL: give warning buffer is about to fill-up
2020-02-05 10:10:37 +11:00
Henry Wurzburg
edc7fefe2a
AP_Follow: hide params not used by Rover
2020-02-05 10:10:37 +11:00
Randy Mackay
9f5d629503
GCS_MAVLink: add comment above set-message-interval
2020-02-05 10:10:37 +11:00
Randy Mackay
b3fbceccb2
GCS_MAVLink: minor fix to set_message_interval
2020-02-05 10:10:37 +11:00
Tatsuya Yamaguchi
ce588f004d
AP_Scripting: add set_message_interval binding
2020-02-05 10:10:37 +11:00
Tatsuya Yamaguchi
48307e2268
GCS_MAVLink: add set_message_interval functions
2020-02-05 10:10:37 +11:00
Andrew Tridgell
4e799be144
AP_Scheduler: use fill_nanf() on each scheduler function
2020-02-05 10:10:37 +11:00
Andrew Tridgell
161154bf05
AP_NavEKF2: fixed build
...
broken by recent common variable change
2020-02-05 10:10:37 +11:00
Andrew Tridgell
8984a8fa85
HAL_SITL: pre-fill stack on each loop with NaN
...
this allows us to catch use of uninitialised stack variables in SITL
without having valgrind running
2020-02-05 10:10:37 +11:00
Andrew Tridgell
b1e0299a0f
AP_NavEKF3: use parent class for intermediate static variables
...
this makes the code faster as well as using less memory when both EK2
and EK3 are enabled
2020-02-05 10:10:20 +11:00
Andrew Tridgell
da7dc71195
AP_NavEKF2: use parent class for intermediate static variables
...
this makes the code faster as well as using less memory when both EK2
and EK3 are enabled
2020-02-05 10:10:20 +11:00
IamPete1
b5e78f9260
AP_Motors: add reversed tricopter option
2020-02-05 10:10:20 +11:00
Peter Barker
3939a24f95
AP_ADSB: move is_valid_octal to is_valid_callsign and add tests for it
2020-02-05 10:10:20 +11:00
Peter Barker
6e4813cc92
AP_Math: move is_valid_octal into adsb
...
This doesn't ensure the value is octal digits - there's more magic in
it.
2020-02-05 10:10:20 +11:00
mhefny
919208c47c
SITL: removed unnecessary files of webots
2020-02-05 10:10:20 +11:00
Peter Barker
dae920634f
AP_Baro: exclude Sub pressure transducers from non-sub builds
2020-02-05 10:10:20 +11:00
Andrew Tridgell
f5cd193f71
AP_Common: removed fcntl overrides
...
not needed with AP_Filesystem, and fixes lots of warnings with newer
compilers
2020-02-05 10:10:20 +11:00
Andrew Tridgell
6ebfbb4b94
AP_HAL: fixed build on g++ 7.3 for stm32
...
the system maths headers don't like our maths defines, but are happy
if we include math.h first
2020-02-05 10:10:20 +11:00
Henry Wurzburg
df32ec154f
AP_OSD: add current averaging filter to reduce jitter (~5 sample timeconstant)
2020-02-05 10:10:20 +11:00
Randy Mackay
633fd0f6c9
AC_Avoidance: add enabled and margin accessors
2020-02-05 10:10:20 +11:00
Randy Mackay
f188f7e05e
RC_Channels: define surface tracking auxiliary function
2020-02-05 10:10:20 +11:00
Randy Mackay
1edac100ac
AC_Avoid: add support for complex fence types
...
AP_OABendyRuler: support exclusion polygons
AP_OADijkstra: support exclusion polygons
AC_Avoid: adjust_velocity supports exclusion polygons
AC_Avoidance: handle fence::get_boundary_points returning nullptr instead of setting num_points to zero
AC_Avoidance: Dijkstra's works with only exclusion polygons
AC_Avoidance: Dijkstra: check for fence counts instead of polyfence validity
We really only care whether fences can be returned - and they won't be
returned unless they are valid
AC_Avoidance: BendyRuler: just try to get inclusion fence rather than checking validity
AC_Avoidance: BendyRuler supports exclusion circles
AC_Avoid: Dijkstra support for exclusion circles
AC_Avoid: BendyRuler support for inclusion circles
AC_Avoid: stop an inclusion/exclusion circular fences
AC_Avoid: stop at inclusion/exclusion circular fences
AC_Avoid: fixes to Dijkstra's use of inclusion/exclusion circles and polygons
AP_Avoidance: take semaphores when interacting with AHRS and polyfence
AC_Avoid: Dijkstra's fix for some_fences_enabled inclusion circles
2020-02-05 10:09:54 +11:00
Randy Mackay
8674997a24
AP_Logger: add error code to Write_OADijkstra
2020-02-05 10:09:54 +11:00
Peter Barker
422aebce95
AP_Proximity: polyfence valid() has been renamed
2020-02-05 10:09:54 +11:00
Peter Barker
56473413d7
AC_Fence: support for multiple polygon fences
...
AC_Fence: add interface for retrieving exclusion polygons
AC_Fence: add interface to get exlusion polygons to polyfence loader
AC_Fence: add suport for inclusion circles
AC_Fence: add option for compiling-out FENCE_POINT protocol support
AC_Fence: get_exclusion_polygon and get_boundary_points set num_points to zero on failure
AC_Fence: use Debug(...) to hide debug messages
AC_PolyFence_loader: add methods to retrieve all inclusion zones
AC_PolyFence_loader: valid simply returns true if a polygon boundary can be returned
AC_Fence: add get_exclusion_circle
AC_Fence: add get_exclusion_circle_update_ms accessor
AC_Fence: PolyFence_loader gets inclusion circle accessors
AC_PolyFence_loader: add and use semaphore to protect loaded fence
AC_Fence: move fence breach check below fence type checks
This allows us to provide more information to the user about why they
are breached.
For example, if the radius is negative you are considered in breach of
it - but we'd tell you you were breached, not that your radius was
invalid
AC_Fence: clear the fence if we discover the user has set the fence count to zero
2020-02-05 10:09:54 +11:00
Peter Barker
179db476bf
GCS_MAVLink: allow upload of fence using mission item protocol
...
GCS_MAVLink: add support for fence inclusion circles
GCS_MAVLink: factor out a transfer_is_complete; start commenting properly
2020-02-05 10:09:54 +11:00
Peter Barker
107b9d95ba
AP_OADijkstra: cope with polyfence holding boundary points
2020-02-05 10:09:54 +11:00
Peter Barker
9c89f9cc8b
AP_OABendyRuler: cope with polyfence holding boundary points
2020-02-05 10:09:54 +11:00
Peter Barker
0c92a6d091
AC_Avoidance: cope with polyfence holding boundary points
2020-02-05 10:09:54 +11:00
Peter Barker
75b022378a
GCS_MAVLink: cope with polyfence holding boundary points
2020-02-05 10:09:54 +11:00
Peter Barker
c6aa243a2b
AP_Proximity: cope with polyfence holding boundary points
2020-02-05 10:09:54 +11:00
Peter Barker
6064f22615
AC_Fence: move polygon points into AC_Fence_Polygon
2020-02-05 10:09:54 +11:00
Peter Barker
63256a6df5
AP_Math: define != for Vector2<int>
2020-02-05 10:09:54 +11:00
Peter Barker
eea711be66
StorageManager: add write_uint8 alias for write_byte
2020-02-05 10:09:54 +11:00
Peter Barker
dc5852dad8
AP_InternalError: add a general should-not-be-here bit
2020-02-05 10:09:54 +11:00
Peter Barker
4e793e7169
GCS_MAVLink: squelched rally-points-received message
2020-02-05 10:09:54 +11:00
Willian Galvani
5c00aa5921
AP_TemperatureSensor: Update TSYS01 for Pixhawk2
2020-02-05 10:09:54 +11:00
Peter Barker
35ea916adf
AP_Relay: change parameter name from relay to instance
2020-02-05 10:09:54 +11:00
Peter Barker
47b9cb2e28
AP_Relay: tidy, reduce flash usage
2020-02-05 10:09:54 +11:00
Peter Hall
3a58aeb6c6
AR_WPNav: make get_stopping_location public
2020-02-05 10:09:54 +11:00
Henry Wurzburg
dffed8e008
AP_OSD: distance total fix for slow vehicles
2020-02-05 10:09:54 +11:00
Willian Galvani
8ad195dd51
APMotors_6DOF: Implement motor_is_enabled(), get_motor_angular_factors() and set_reversed();
2020-02-05 10:09:54 +11:00
Peter Hall
1e02cbe009
AP_Windvane: caculate vehicles current tack
2020-02-05 10:09:54 +11:00
Willian Galvani
ae8df5678a
AP_Motors_6DOF: Add missing 'break'
2020-02-05 10:09:54 +11:00
Henry Wurzburg
fb0b92cc94
AP_OSD: scale xtrack, add precision for distances <10 units
2020-02-05 10:09:54 +11:00
Patrick José Pereira
6c734b5006
AP_HAL_Linux: PCA9685: Check for device before accessing it
...
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
2020-02-05 10:09:54 +11:00
mhefny
9d67a9423f
SITL: adding Tricopter model in Webots
2020-02-05 10:09:54 +11:00
Randy Mackay
586b1f3c8c
GCS_MAVLink: allow proximity to send only upward facing distances
...
this removes the requirement that a horizontal proximity sensor be enabled
2020-02-05 10:09:54 +11:00
Henry Wurzburg
0f0ceb6499
AP_OSD: formatting fixes
2020-02-05 10:09:54 +11:00
bnsgeyer
5898986b0a
AP_Motor: tradheli align swash params btwn frames and fix metadata
2020-02-05 10:09:20 +11:00
Peter Barker
5871cdad23
AP_Math: remove unit_mod concept from wrap functions
...
devcall decided it would be clearer to have non-shared implementation
for the _cd variants
2020-02-05 10:09:20 +11:00
Peter Barker
5e9aaca8df
AP_NavEKF2: initialise Kfusion stack variable to fix compilation
...
This fixes the compilation, as previous patches have done.
2020-02-05 10:09:20 +11:00
Peter Barker
ec991969c7
AP_HAL_ChibiOS: correct include of mavlink header for analog debug
2020-02-05 10:09:20 +11:00
liang
9c44ebaced
AP_Baro: LPS22H: correct formatting
2020-02-05 10:09:20 +11:00
Andrew Tridgell
de12430977
AP_NavEKF2: fixed build with g++ 9.1
...
this is a false positive, but the cost of clearing this array is low,
and it saves a much more complex fix
2020-02-05 10:09:20 +11:00
murata
6de2311689
AP_Radio: Change direct value to define name
2020-02-05 10:09:20 +11:00
murata
a74123148b
AP_Compass: Change direct value to define name
2020-02-05 10:09:20 +11:00
Andrew Tridgell
5d67618968
AP_NavEKF2: added comment (review request)
2020-02-05 10:09:20 +11:00
Andrew Tridgell
164813bcc2
AP_NavEKF2: moved some of the intermediate vars to the stack
...
this keeps stack frames below 1k, while giving faster access to the
variables and saving more memory
2020-02-05 10:09:20 +11:00
Andrew Tridgell
6ffffff8c6
AP_NavEKF3: moved intermediate variables to common memory
...
this moves intermediate variables from being per-core to being common
between cores. This saves memory on systems with more than one core by
avoiding allocating this memory on every core.
This is an alternative to #11717 which moves memory onto the stack. It
doesn't save as much memory as #11717 , but avoids creating large stack
frames
2020-02-05 10:09:00 +11:00
Andrew Tridgell
a48d97c307
AP_NavEKF2: moved intermediate variables to common memory
...
this moves intermediate variables from being per-core to being common
between cores. This saves memory on systems with more than one core by
avoiding allocating this memory on every core.
This is an alternative to #11717 which moves memory onto the stack. It
doesn't save as much memory as #11717 , but avoids creating large stack
frames
2020-02-05 10:08:10 +11:00
Peter Barker
5ce16f81ff
AP_ADSB: use ObjectBuffer in place of AP_Buffer
2020-02-05 10:05:59 +11:00
Peter Barker
ed5848238c
AP_Buffer: remove as it is replaced with ObjectBuffer
2020-02-05 10:05:59 +11:00
Willian Galvani
8f6ca7bb8f
APMotors6DOF: add roll factor for motors 4 and 5 for SIMPLEROV_4 and SIMPLEROV_5
2020-02-05 10:05:59 +11:00
Willian Galvani
f5ba04d098
APMotors6DOF: add case for SIMPLEROV_3
2020-02-05 10:05:59 +11:00
Peter Barker
552cc4be5c
AP_HAL_SITL: catch SIGTERM and exit with zero exit status
2020-02-05 10:05:59 +11:00
Andrew Tridgell
7ecbec5b96
HAL_SITL: added MotorBoat
2020-02-05 10:05:59 +11:00
Andrew Tridgell
be083aab1a
SITL: added a MotorBoat class
...
a sailboat with zero sail area
2020-02-05 10:05:59 +11:00
Lucas De Marchi
77a06de66f
AP_RangeFinder: update minimum fw version of TFMiniPlus
...
Version 2.0.3 has important fixes to avoid having the sensor to lock up.
Let's make sure we check for it and warn on console.
2020-02-05 10:05:59 +11:00
Peter Hall
5b434e814a
APM_Control: AR_AttitudeControl: add description for new PID params
2020-02-05 10:05:59 +11:00
Andrew Tridgell
d85a7e4c4b
AP_Logger: fixed use of old irqsave() API
2020-02-05 10:04:08 +11:00
Michael du Breuil
af0c55b4df
AP_HAL_ChibiOS: Only include MAVLink when using the MAVLink debugging
2020-02-05 10:04:08 +11:00
Michael du Breuil
bfe4d6ee82
GCS_MAVLink: remove some unused includes
2020-02-05 10:04:08 +11:00
Peter Barker
506126cb44
AC_AutoTune: correct abs to fabsf for roll_cd and pitch_cd
2020-02-05 10:04:08 +11:00
Peter Barker
3e9f470bfb
AP_L1_Control: wrap_180_cd no longer solely returns floats
2020-02-05 10:04:08 +11:00
Peter Barker
7c2c809b06
APM_Control: wrap_180_cd no longer solely returns floats
2020-02-05 10:04:08 +11:00
Peter Barker
33ef991282
AP_Math: stop returning float for integer wrap_180/wrap_360 etc
2020-02-05 10:04:08 +11:00
Peter Barker
818402ab99
AP_Math: add more tests for wrap functions
2020-02-05 10:04:08 +11:00
Peter Barker
89cfdb678f
AC_WPNav: do not calculate NEU vector from invalid location
2020-02-05 10:04:08 +11:00
Michael du Breuil
14f43f24a9
AP_Common: Include altitude in the init check for a location
2020-02-05 10:04:08 +11:00
Andrew Tridgell
5bac7018b6
AP_GPS: use jitter correction on GPS_INPUT data
...
this allows for more accurate timing when using GPS_INPUT for indoor
positioning systems
2020-02-05 10:04:08 +11:00
Peter Barker
882d3b0c0d
GCS_MAVLink: use singleton to get AP_AdvancedFailsafe pointer
2020-02-05 10:04:08 +11:00
Peter Barker
7a1afc580d
AP_AdvancedFailSafe: add singleton getter
2020-02-05 10:04:08 +11:00
Andrew Tridgell
f1cb9ed956
AP_FileSystem: chunk IOs to max 4k
...
this prevents larger IOs from attempting to allocate too much memory
in DMA bouncebuffers
2020-01-18 12:27:51 +11:00
Andrew Tridgell
2d817db7f3
AP_IOMCU: added a health check based on status read errors
...
if we have more than 1 in 128 read status requests failing then mark
IOMCU unhealthy
2020-01-18 12:27:42 +11:00
Andrew Tridgell
630ccb2ef9
AP_IOMCU: reduce uart buffer sizes
2020-01-18 12:27:39 +11:00
Andrew Tridgell
23005e6f46
HAL_ChibiOS: use 4k bouncebuffer for sdcard
...
match AP_Logger IO size
2020-01-18 12:27:36 +11:00
Andrew Tridgell
c5b1c88948
HAL_ChibiOS: adjust dma reserve allocation
...
use larger target and allow for smaller allocation
2020-01-18 12:27:33 +11:00
Andrew Tridgell
64dc29cf98
HAL_ChibiOS: don't extend alloc of iomcu uart
2020-01-18 12:27:29 +11:00
Andrew Tridgell
7c0cb85361
HAL_ChibiOS: added checking on bouncebuffer allocation
...
fail operations if DMA bouncebuffer alloc fails
# Conflicts:
# libraries/AP_HAL_ChibiOS/I2CDevice.cpp
2020-01-18 12:27:23 +11:00
Andrew Tridgell
b60fd97f32
AP_Logger: add a semaphore to protect creation of new log formats
2020-01-18 12:26:29 +11:00
Andrew Tridgell
66b14f4aaf
AP_Filesystem: fixed set_mtime semaphore
2020-01-18 12:26:25 +11:00
Michael du Breuil
0fe9763e19
AP_Param: Fix failing to invalidate the cached parameter count
...
This would cause a GCS to download fewer then the requested number of
parameters
2020-01-15 14:03:36 +11:00
Andrew Tridgell
e9f60ede1b
AP_SerialManager: ensure users can't break SERIAL0_PROTOCOL
...
this prevents users from setting SERIAL0_PROTOCOL to something that
prevents them accessing the board. This can happen when users are
trying to setup SLCAN
2020-01-10 19:12:10 +11:00
Andrew Tridgell
7d91460e85
AP_Declination: re-generate mag tables
...
max interpolate error between -60 and 60 latitude is 13.86 mGauss
2020-01-10 19:12:10 +11:00
Andrew Tridgell
3584f1b779
AP_Declination: update generate script
...
added ability to display max error
2020-01-10 19:12:10 +11:00
Andrew Tridgell
9261b32430
AP_GPS: fixed build
2020-01-10 19:12:10 +11:00
Andrew Tridgell
0ed02b1d88
AP_Compass: added mag_cal_fixed_yaw()
...
this is a fast compass calibration that uses a yaw value provided by
the user.
2020-01-10 18:48:52 +11:00
Andrew Tridgell
aea2238936
GCS_MAVLink: support MAV_CMD_FIXED_MAG_CAL_YAW
2020-01-10 18:48:49 +11:00
Andrew Tridgell
b95a31ccfc
AP_RCProtocol: fixed support for 22ms multi-frame DSM
2020-01-10 18:48:42 +11:00
Andrew Tridgell
0dc22331d0
AP_Frsky_Telem: fixed a race condition with statustext handling
...
this fixes an issue that can cause a hardfault. See this bug report:
https://discuss.ardupilot.org/t/hexa-crash-after-watchdog-reset/50917
ObjectArray is not thread safe
2020-01-10 18:48:17 +11:00
Andrew Tridgell
b834796f3b
HAL_ChibiOS: fixed clock src for I2C4 on H7
2020-01-08 06:02:46 +11:00
Andrew Tridgell
17118977dc
HAL_ChibiOS: automatically set AP_FEATURE_RTSCTS
2020-01-02 07:50:35 +11:00
Andrew Tridgell
5c4802ce25
AP_Compass: limit rotations we try to ROTATION_MAX_AUTO_ROTATION
2020-01-01 09:08:31 +11:00
Andrew Tridgell
686b9322cd
AP_Math: define ROTATION_MAX_AUTO_ROTATION
...
we don't want to use ROTATION_PITCH_7 in our auto rotation mix, as it
is too close to level
2020-01-01 09:08:19 +11:00
Andrew Tridgell
8311a5be63
HAL_ChibiOS: fixed H7 I2C timing
...
we were running the clock at too low speed. This affected the SSD1306 display
# Conflicts:
# libraries/AP_HAL_ChibiOS/I2CDevice.cpp
2019-12-30 14:35:57 +11:00
Peter Barker
abe1a09c7a
AP_HAL: stop emitting extra CR before a LF as part of our printf
2019-12-25 12:00:37 +11:00
Pierre Kancir
ecdd07e793
AP_Compass: add register to checked ones and remove single-use goto
...
Also fix comment on TMRC register setting
2019-12-23 20:20:12 +11:00
Pierre Kancir
d9edd3c8b5
AP_Compass: probe for RM3100
2019-12-23 20:20:01 +11:00
Andrew Tridgell
318c0a958d
HAL_ChibiOS: removed PB1 and PB0 TIM1 complementary channels for F76x
...
these do not work, possibly a datasheet bug
2019-12-23 19:42:04 +11:00
Andrew Tridgell
24e48b5e81
HAL_ChibiOS: switch MatekF765 to timer 12
...
fixes PWM 5 and 6
2019-12-23 19:42:02 +11:00
Andrew Tridgell
af04f1eb93
HAL_ChibiOS: ensure bootloader flash is multiple of 32 bytes
2019-12-23 17:36:28 +11:00
Andrew Tridgell
9c2caf5b12
AP_InertialSensor: default fast sampling on
...
if we have a first IMU capable of fast sampling then we want it
enabled by default
2019-12-23 09:56:26 +11:00
Andrew Tridgell
f733e963df
HAL_ChibiOS: scale uart rx buffer size with baudrate
...
this ensures we have enough buffer space for a RTK GPS, as well as for
high speed comms with a companion computer
2019-12-23 09:56:26 +11:00
Peter Barker
48a04d21ce
AP_NMEA_Output: NavEKF constructors no longer take rangefinder
2019-12-23 09:56:26 +11:00
Randy Mackay
e206134fa6
AP_NMEA_Output: 10hz rate limiting uses uint32_t
2019-12-23 09:56:26 +11:00
Peter Barker
46c384b412
AP_NMEA_Output: correct 10Hz rate limiting
...
integer promotion issue
2019-12-23 09:56:26 +11:00
Peter Barker
9fd53b0dbc
AP_NMEA_Output: add example
2019-12-23 09:56:26 +11:00