Commit Graph

28322 Commits

Author SHA1 Message Date
Peter Barker 66d8be825f AP_Logger: move LogOriginType into AP_AHRS
only used to log the origins by the AHRS library
2021-12-07 11:31:44 +11:00
Peter Barker 1dd34d87e7 AP_AHRS: move LogOriginType into AP_AHRS
only used to log the origins by the AHRS library
2021-12-07 11:31:44 +11:00
Andrew Tridgell fe7e2ed657 AP_Scripting: added throttle and height controller to aerobatic example
changed rolling circle to take the radius and number of
circles. negative radius for negative yaw rate and negative number of
circles for left roll
2021-12-07 10:33:13 +11:00
Andrew Tridgell 140adc126a AP_Scripting: expand to 6 SCR_USER parameters 2021-12-07 10:33:13 +11:00
Andrew Tridgell 67649fe17d hwdef: added CarbonixL496 AP_Periph node 2021-12-07 10:23:54 +11:00
Andrew Tridgell c5fc2fa709 HAL_ChibiOS: enable DShot on L4 MCUs for AP_Periph 2021-12-07 10:23:54 +11:00
Andrew Tridgell fbadc24fca HAL_ChibiOS: support 12MHz crystal on L4xx MCUs 2021-12-07 10:23:54 +11:00
Hwurzburg d132f0f3fb AP_Vehicle: clean up short failsafe 2021-12-07 10:09:33 +11:00
Peter Barker d72d0578a3 AP_Scripting: correct compilation when HAL_LOGGER_FILE_CONTENTS_ENABLED is 0 2021-12-07 09:36:48 +11:00
Peter Barker cce14d8461 AP_HAL_SITL: remove unused _home_str member 2021-12-07 09:36:22 +11:00
Andrew Tridgell 9e5fcb4ced AP_UAVCAN: removed old vendor DSDL and add README.md
this DSDL is in https://github.com/DroneCAN/DSDL now
2021-12-06 20:17:02 +11:00
Andrew Tridgell 5afe055a46 AP_UAVCAN: use soft armed state for DroneCAN ARMING_STATUS
this fixes motortest on quadplanes, so that ESCs see an armed state
during the test
2021-12-06 20:16:23 +11:00
Peter Barker bedacac816 AP_Torqeedo: simplify conversion of master error code into string 2021-12-06 14:50:15 +11:00
Randy Mackay 6f98c26b67 AP_Torqeedo: display master error code 2021-12-06 14:50:15 +11:00
Bill Geyer 3b40df133e AP_Motors: add spool down complete flag 2021-12-05 22:12:13 -05:00
Peter Barker 8cc7f51de1 AP_HAL_SITL: tidy set/get of hw RTC 2021-12-06 12:58:43 +11:00
Peter Barker d8e4669e07 AP_HAL_Linux: tidy set/get of hw RTC 2021-12-06 12:58:43 +11:00
Peter Barker f50d48f005 AP_HAL: tidy set/get of hw RTC 2021-12-06 12:58:43 +11:00
Andrew Tridgell 0944c24978 SITL: revert compass parameter changes 2021-12-04 16:51:53 +11:00
Andrew Tridgell 468444bef9 AP_NavEKF3: revert compass parameter changes 2021-12-04 16:51:53 +11:00
Andrew Tridgell efc78359d7 AP_NavEKF2: revert compass parameter changes 2021-12-04 16:51:53 +11:00
Andrew Tridgell 0d12fa7937 AP_HAL_ESP32: revert compass parameter changes 2021-12-04 16:51:53 +11:00
Andrew Tridgell 2c2369bf03 AP_HAL_ChibiOS: revert compass parameter changes 2021-12-04 16:51:53 +11:00
Andrew Tridgell 8eb40bafc5 AP_Compass: revert compass parameter changes 2021-12-04 16:51:53 +11:00
Andrew Tridgell 7ab343dd66 AP_RangeFinder: fixed support for multiple Benewake_CAN CAN lidars 2021-12-04 16:31:35 +11:00
Peter Barker 308f4e99b4 AP_NavEKF3: correct structure used for logging
XKF4 and XKF5 are clones of NKF4 and NKF5, which is why this worked
2021-12-03 15:34:21 +09:00
Randy Mackay ec6ea03b80 AP_HAL_ChibiOS: update CubeBlack-pinout image
CAN1 and CAN2 port labels have been swapped
2021-12-03 13:49:20 +09:00
Rishabh 6dea779b1e AP_Proximity: Add Cygbot D1 2021-12-03 08:02:50 +09:00
Andrew Tridgell 05ec2be62b hwdef: updated KakuteH7 battery scale defaults
thanks to Vincent at Holybro
2021-12-02 18:17:49 +11:00
Iampete1 7ad1886667 AP_Compass: reinstate MOTCT underscore 2021-12-02 12:27:09 +11:00
Iampete1 bf21ce8af6 AP_Compass: add new line after old param metadata 2021-12-02 12:27:09 +11:00
Andrew Tridgell 0554fb2d4f RC_Channel: added QRTL mode on a switch 2021-12-02 08:29:07 +11:00
Shiv Tyagi 339a07b8d3 AP_Devo_Telem: compile out devo telemetry
Devo telemetry is one of the most rarely used features (almost never used since added) we should compile it out from our code
2021-12-01 19:16:44 +11:00
Andy Piper 5224468ec6 AP_RCProtocol: process CRSF crc per-byte 2021-12-01 19:04:19 +11:00
bugobliterator f9bb9b4fc0 AP_HAL_ChibiOS: log heap and bss memory regions if enough space 2021-12-01 18:17:50 +11:00
bugobliterator 3855767ff2 AP_FileSystem: mention of HAL_CRASH_DUMP_FLASHPAGE not required 2021-12-01 18:17:50 +11:00
bugobliterator 4efe75683a HAL_ChibiOS: mention of HAL_CRASH_DUMP_FLASHPAGE not required 2021-12-01 18:17:50 +11:00
bugobliterator 878940292d HAL_ChibiOS: no need to mention END reserve for Crash Dump anymore 2021-12-01 18:17:50 +11:00
bugobliterator ee35350129 HAL_ChibiOS: setup for recording crashdump at the remaining flash space 2021-12-01 18:17:50 +11:00
bugobliterator 52c7886270 HAL_ChibiOS: fix issue with failing to write final buffer 2021-12-01 18:17:50 +11:00
bugobliterator eae3fb016f HAL_ChibiOS: dump per thread stack for crash 2021-12-01 18:17:50 +11:00
bugobliterator f02a7b560b AP_HAL_ChibiOS: update last_crash_dump api 2021-12-01 18:17:50 +11:00
bugobliterator 0c69ebc50e AP_HAL: update last_crash_dump api 2021-12-01 18:17:50 +11:00
bugobliterator b1e25ec4fd AP_Filesystem: fetch crash_log directly rather than via buffer 2021-12-01 18:17:50 +11:00
Andrew Tridgell 312a6461b6 HAL_ChibiOS: enable UART7 on Swan-K1
useful extra UART for debug
2021-12-01 18:08:54 +11:00
Andrew Tridgell 06ef5aed14 AP_Scripting: added an example of OOP programming
very useful pattern for more complex scripts
2021-12-01 17:40:34 +11:00
Randy Mackay 4096a70a1f AP_Math: update_pos_vel_accel methods accept limit as const reference
also update some comments
2021-12-01 12:45:46 +09:00
Randy Mackay f6e6ca197f Location: get_vector_from_origin gets units comment 2021-12-01 09:03:40 +09:00
Randy Mackay a3886be920 AC_PosControl: minor formatting fix 2021-12-01 08:54:34 +09:00
Randy Mackay 3a492c8e3c AR_WPNav: minor comment improvement 2021-12-01 08:54:18 +09:00
Peter Barker 56b0f8b218 AC_Fence: void index when overwriting fence count on fencepoint-close 2021-11-30 20:50:32 +11:00
Andrew Tridgell 8a95a7d80d AC_Fence: fixed fence count for old upload
when uploading a fence that is smaller than an old fence we were not
correctly setting the inclusion fence size.
2021-11-30 20:50:32 +11:00
Peter Barker af92c9679f AC_Fence: make invalid polygon vertex count clearer 2021-11-30 20:50:32 +11:00
Andrew Tridgell c83da810da APM_Control: tweaks from review feedback 2021-11-30 16:19:26 +11:00
Andrew Tridgell d52f5a9034 AP_Scripting: added rolling circle to aerobatics example 2021-11-30 16:19:26 +11:00
Andrew Tridgell ab333d0708 Ap_Scripting: added earth frame yaw tracking off WPs
this uses the new yaw rate controller to do EF tracking, so we follow
towards the next WP while doing the roll
2021-11-30 16:19:26 +11:00
Andrew Tridgell 3a3cb92efd Ap_Scripting: fixed plane aerobatics for full yaw rate control 2021-11-30 16:19:26 +11:00
Andrew Tridgell 81d20ae49d APM_Control: support yaw rate controller autotune 2021-11-30 16:19:26 +11:00
Andrew Tridgell 6685ce0527 APM_Control: added yaw rate controller for fixed wing
enabled with YAW_RATE_ENABLE parameter
2021-11-30 16:19:26 +11:00
Andrew Tridgell 5a996f308b APM_Control: fixed code style of plane rate controllers 2021-11-30 16:19:26 +11:00
Peter Barker 99b1659e4b AP_Math: memcpy nanfs rather than iteratively setting them 2021-11-30 10:35:38 +11:00
Peter Barker b32b31aecd SRV_Channel: correct casting of servo function number 2021-11-30 10:32:16 +11:00
Andrew Tridgell 724301ea53 APM_Control: make 2nd reduction of P smaller
this prevents severe P reductions when we get a small oscillation
glitch after we've already got the primary P gain
2021-11-30 10:31:34 +11:00
Josh Henderson 34b3b7999e CubeYellow: define HAL_CHIBIOS_ARCH_CUBE 2021-11-30 10:20:54 +11:00
Josh Henderson 188c3a781e CubeSolo: define HAL_CHIBIOS_ARCH_CUBE 2021-11-30 10:20:54 +11:00
Josh Henderson e78edac2a0 CubePurple: define HAL_CHIBIOS_ARCH_CUBE 2021-11-30 10:20:54 +11:00
Josh Henderson b37c214f28 CubeOrange: define HAL_CHIBIOS_ARCH_CUBE 2021-11-30 10:20:54 +11:00
Josh Henderson db3be4d07c CubeBlack: define HAL_CHIBIOS_ARCH_CUBE 2021-11-30 10:20:54 +11:00
Josh Henderson 27bcec9d6e AP_InertialSensor: for all Cubes ensure use of non-isolated IMU 2021-11-30 10:20:54 +11:00
Josh Henderson a89f58a775 AP_NavEKF3: allow define for IMU_MASK_DEFAULT 2021-11-30 10:20:54 +11:00
Josh Henderson 9f2082496c AP_NavEKF2: allow define for IMU_MASK_DEFAULT 2021-11-30 10:20:54 +11:00
Josh Henderson c7b986f30a CubeYellow: set default EKF_IMU_MASK 2021-11-30 10:20:54 +11:00
Josh Henderson b8411c22c5 CubeOrange: set default EKF_IMU_MASK 2021-11-30 10:20:54 +11:00
Peter Barker a4b3c7eb46 AP_Terrain: cast result of labs to unsigned
Fixes:

../../libraries/AP_Terrain/TerrainGCS.cpp: In member function ‘void AP_Terrain::
handle_terrain_data(const mavlink_message_t&)’:
../../libraries/AP_Terrain/AP_Terrain.h:65:55: error: comparison between signed
and unsigned integer expressions [-Werror=sign-compare]
 #define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= unsigned(margin.get()*
100))
                                       ~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~
~~~~
../../libraries/AP_Terrain/AP_Terrain.h:65:55: note: in definition of macro ‘TER
RAIN_LATLON_EQUAL’
 #define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= unsigned(margin.get()*
100))
                                                       ^~
compilation terminated due to -Wfatal-errors.
cc1plus: some warnings being treated as errors

In file included from ../../libraries/AP_Terrain/TerrainUtil.cpp:24:0:
../../libraries/AP_Terrain/TerrainUtil.cpp: In member function ‘AP_Terrain::grid
_cache& AP_Terrain::find_grid_cache(const AP_Terrain::grid_info&)’:
../../libraries/AP_Terrain/AP_Terrain.h:65:55: error: comparison between signed
and unsigned integer expressions [-Werror=sign-compare]
 #define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= unsigned(margin.get()*
100))
                                       ~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~
~~~~

The return value of labs is signed
2021-11-30 10:16:01 +11:00
Iampete1 e24c90a871 AP_Compass: reinstate old param descriptions 2021-11-30 08:14:43 +09:00
Iampete1 6ba87dfe9a AP_Compass: add param conversion 2021-11-30 08:14:43 +09:00
Iampete1 e818decc39 AP_NavEKF3: update compass param discription 2021-11-30 08:14:43 +09:00
Iampete1 4303b61f94 AP_NavEKF2: update compass param discription 2021-11-30 08:14:43 +09:00
Iampete1 95713959ec SITL: exmaples: use new compass params 2021-11-30 08:14:43 +09:00
Iampete1 ab9609022b AP_HAL_ESP32: use new compass param names 2021-11-30 08:14:43 +09:00
Iampete1 0c519db602 hwdef: use new compass param names in defualts.parm 2021-11-30 08:14:43 +09:00
Iampete1 2fa2e70e7e AP_Compass: SITL: use new scale param 2021-11-30 08:14:43 +09:00
Iampete1 071ff39ff8 AP_Compass: move instance params to shared table 2021-11-30 08:14:43 +09:00
Shiv Tyagi e1a528213d AP_Rangefinder: Use default address for TFMiniPlus I2C unless configured
This fixes the issue #13419. If RNGFNDx_ADDR is not configured, it uses default address for TFmini i2c
2021-11-30 10:09:24 +11:00
Josh Henderson 04ba26a080 AP_InertialNav: rename for neu & cm/cms 2021-11-30 10:08:07 +11:00
Josh Henderson e10edabd5d AC_WPNav: INAV rename for neu & cm/cms 2021-11-30 10:08:07 +11:00
Josh Henderson bd9361b701 AC_AutoTune: INAV rename for neu & cm/cms 2021-11-30 10:08:07 +11:00
Josh Henderson e11529ac01 AC_AttitudeControl: INAV rename for neu & cm/cms 2021-11-30 10:08:07 +11:00
Josh Henderson da418ed520 AC_AttitudeControl: rename Inav get_position_xy() & get_velocity_xy() 2021-11-30 10:08:07 +11:00
Josh Henderson 027336dbb8 AP_InertialNav: rename to get_position_xy() & get_velocity_xy() 2021-11-30 10:08:07 +11:00
Josh Henderson 28d9be1cc0 AP_Math: get_horizontal_cm() simplify 2021-11-30 10:08:07 +11:00
Josh Henderson 9e11f09a7f AC_WPNav: inav use _xy() 2021-11-30 10:08:07 +11:00
Josh Henderson 77711e1505 AP_PosControl: inav use _xy() 2021-11-30 10:08:07 +11:00
Josh Henderson 6243532e69 AC_AttitudeControl: get_bearing & get_horizontal_distance use Vector2f 2021-11-30 10:08:07 +11:00
Josh Henderson 2a15cf86ad AP_Math: Location get_bearing & get_horizontal_distance use Vector2f 2021-11-30 10:08:07 +11:00
Josh Henderson d5769f70ac AC_WPNav: get_bearing & get_horizontal_distance use Vector2f 2021-11-30 10:08:07 +11:00
Andrew Tridgell 5fe5d3a3d3 AP_Arming: support Benewake CAN 2021-11-30 09:49:20 +11:00
Andrew Tridgell 4f6da39bb7 AP_CANManager: support Benewake CAN 2021-11-30 09:49:20 +11:00
Andrew Tridgell 3f85eab272 AP_RangeFinder: added Benewake CAN Lidars
includes support for setting CAN ID and min SNR
2021-11-30 09:49:20 +11:00
Peter Barker ba63e9a17b GCS_MAVLink: correct send_scaled_imu gyro-count check 2021-11-29 15:08:23 +11:00
Peter Barker 7abf07f233 hwdef: remove unused HAL_NO_GCS defines
This became HAL_GCS_ENABLED, off by default on Periph
2021-11-26 12:25:40 +11:00
Charlie-Burge a9c4895514 SITL: reduce SLV2 logger message size 2021-11-26 12:24:46 +11:00
Ryan Beall beecca8da9 AP_TECS: Connsider throttle saturation in height demand limiting 2021-11-25 15:02:09 +11:00
m c729fc7796 AP_Mission: Decode MAV_CMD_DO_PAUSE_CONTINUE commands 2021-11-25 08:18:27 +09:00
Peter Barker 11cbd68296 AP_HAL_SITL: remove incorrect use of ARRAY_SIZE
This was converted to a linked list....
2021-11-24 18:26:17 +11:00
Peter Barker 139c460fa5 hwdef: remove unused define NO_DATAFLASH 2021-11-24 18:18:06 +11:00
Josh Henderson c7a4ae9cce SITL: comment for sim_i2c parameters 2021-11-24 13:54:49 +11:00
Andrew Tridgell 0141ec5be7 AP_AHRS: fixed switching airspeed sensor based on EKF3 affinity
we need to use the EKF selected airspeed sensor when the EKF is setup
to run a different sensor on each lane
2021-11-24 13:52:13 +11:00
Peter Barker f848fa3a86 AP_Logger: turn dataflash logging off by default 2021-11-24 13:23:40 +11:00
Peter Barker ee68072c62 AP_HAL_ChibiOS: chibios_hwdef: use ifndef pattern for AP_FETTEC_ONEWIRE_ENABLED 2021-11-24 12:01:22 +11:00
Peter Barker bd63ce3eb6 AP_FETtecOneWire: rely on AP_FETTEC_ONEWIRE_ENABLED being set in hwdef.h 2021-11-24 12:01:22 +11:00
Peter Barker fd97d79cb4 SRV_Channels: move fetteconewire out of AP_Periph #if 2021-11-24 12:01:22 +11:00
Peter Barker 2bfd2f1c32 SRV_Channel: rename HAL_AP_FETTEC_ONEWIRE_ENABLED to AP_FETTEC_ONEWIRE_ENABLED 2021-11-24 12:01:22 +11:00
Peter Barker 5d005df92f AP_HAL_ChibiOS: rename HAL_AP_FETTEC_ONEWIRE_ENABLED to AP_FETTEC_ONEWIRE_ENABLED 2021-11-24 12:01:22 +11:00
Peter Barker 1590fcf0bf AP_FETtecOneWire: rename HAL_AP_FETTEC_ONEWIRE_ENABLED to AP_FETTEC_ONEWIRE_ENABLED 2021-11-24 12:01:22 +11:00
Peter Barker e1b32d16b7 AP_Arming: rename HAL_AP_FETTEC_ONEWIRE_ENABLED to AP_FETTEC_ONEWIRE_ENABLED 2021-11-24 12:01:22 +11:00
Andrew Tridgell a4a0607160 AP_Compass: added AP_RM3100_REVERSAL_MASK
this allows for fixing setups where the RM3100 has been installed on a
board with one or more axes reversed
2021-11-24 07:17:13 +11:00
Peter Barker f9580c0dfe AP_Airspeed: add date for parameter conversion code 2021-11-23 12:27:14 +00:00
Andrew Tridgell 1b0631669c AC_AttitudeControl: fixed limiting of throttle mix values
use constrain instead of reset to keep as much of user requested value
as possible

also raise limit for MIX_MIN to 0.5 after discussion with Leonard
2021-11-23 16:47:25 +09:00
Peter Barker ca232bb510 GCS_MAVLink: signal quality reporting 2021-11-23 18:20:58 +11:00
Peter Barker f6aeb01994 AP_RangeFinder: signal quality reporting 2021-11-23 18:20:58 +11:00
Peter Barker 8843c17f9d SITL: LightwareSerial: return 130m when out-of-range-high 2021-11-23 18:20:58 +11:00
Peter Barker 2dd3263650 SITL: cap digits in LightWareSerial measurements
this was hitting the buffer-length limit in the ArduPilot rangefinder
driver as soon as we hit the 100m mark
2021-11-23 18:20:58 +11:00
Shiv Tyagi 4483b9d6fe AP_Motors: add matrix for deca-cwx frame
This adds a missing matrix for deca-cwx frame
2021-11-23 15:52:25 +09:00
Iampete1 6162775dd0 AC_PID: P 1D, P 2D: remove unused limit flags 2021-11-23 13:49:02 +09:00
Iampete1 be6598708e AC_PosControl: remove unused limit flags 2021-11-23 13:49:02 +09:00
Iampete1 460df9bb50 AP_Math: control: remove unneeded normalisation. 2021-11-23 13:47:10 +09:00
Peter Hall 82dd216195 AC_PID_2D: correct limit caculation 2021-11-23 13:47:10 +09:00
Peter Barker 6a13613a0f AP_BoardConfig: correct va_list memory over-read error
A va_list can only be used once - so take a copy each time we want to
use it
2021-11-23 11:46:09 +11:00
Iampete1 467caa5259 RC_Channel: remove landinggear switch message 2021-11-23 11:40:44 +11:00
Iampete1 b818401563 AP_LandingGear: add enable param 2021-11-23 11:40:44 +11:00
Peter Barker bd33267fd3 AP_Logger: do not use dataflash on SITL 2021-11-23 11:24:46 +11:00
Peter Barker ea03d4e44b AP_Logger: eliminate HAL_LOGGING_DATAFLASH
This define didn't add anything over HAL_LOGGING_DATAFLASH_ENABLED - and
predates it.
2021-11-23 11:24:46 +11:00
Peter Barker 9a2d9898ba AP_HAL_ChibiOS: eliminate HAL_LOGGING_DATAFLASH
This define didn't add anything over HAL_LOGGING_DATAFLASH_ENABLED - and
predates it.
2021-11-23 11:24:46 +11:00
Tom Pittenger 684ad39a02 AP_Mission: PLANE to refuse NAV_SPLINE_WAYPOINT missions items 2021-11-23 11:23:02 +11:00
Randy Mackay 7cd767fe6d AR_WPNav: improve pivot turn accuracy to 5deg (was 10) 2021-11-23 11:18:15 +11:00
Samuel Tabor 27078bccda AP_TECS: Log input height demands. 2021-11-23 11:15:50 +11:00
Peter Barker 494dcc6ba3 SITL: make SITL::ADSB a SITL::SerialDevice 2021-11-23 11:09:29 +11:00
Peter Barker cdccc67fb8 AP_HAL_SITL: make SITL::ADSB a SITL::SerialDevice 2021-11-23 11:09:29 +11:00
Tom Pittenger 659c35d1a9 SITL: expire stationary sim_adsb targets after an hour 2021-11-23 09:16:04 +11:00
Tom Pittenger ec5820044b AP_Math: add defines for AP_SEC_PER_HOUR and AP_MSEC_PER_HOUR 2021-11-23 09:16:04 +11:00
Andrew Tridgell 6b249aefbc AP_DAL: support 9 uarts 2021-11-22 22:48:59 +11:00
Andrew Tridgell 0b567e95dc hwdef: added OTG2 for MatekF765-SE 2021-11-22 22:48:59 +11:00
Andrew Tridgell 1815ed32e9 AP_SerialManager: support up to 9 UARTs 2021-11-22 22:48:59 +11:00
Andrew Tridgell 3b3abdeef0 AP_HAL_SITL: support up to 9 UARTs 2021-11-22 22:48:59 +11:00
Andrew Tridgell 018ac68061 AP_HAL_Linux: support up to 9 UARTs 2021-11-22 22:48:59 +11:00
Andrew Tridgell 8c2074907b AP_HAL: support up to 9 UARTs 2021-11-22 22:48:59 +11:00
Andrew Tridgell ccf89c2031 AP_HAL_ESP32: support up to 9 UARTs 2021-11-22 22:48:59 +11:00
Andrew Tridgell e2618bdc06 AP_HAL_Empty: support up to 9 UARTs 2021-11-22 22:48:59 +11:00
Andrew Tridgell fc6a82de1b AP_HAL_ChibiOS: support up to 9 UARTs 2021-11-22 22:48:59 +11:00
Peter Barker bcee8b56ee AP_Param: simplify set_defaults_from_table error path 2021-11-22 22:43:02 +11:00
李孟晓 dfe2ade495 CUAV-X7: Add servo voltage detection pin 2021-11-22 16:39:15 +11:00
Andrew Tridgell a78200fa24 RC_Channel: added parachute for plane 2021-11-22 13:22:54 +11:00
Hwurzburg 1162d556c6 RC_Channel: fix flare rc switch action with flight option bit 10 active 2021-11-21 21:00:04 +11:00
Peter Barker e7f1a273e5 AP_HAL_ChibiOS: remove unused pin-related defines
Unused
2021-11-20 11:08:48 +11:00
Hwurzburg 2f4bcfb21c AP_Motors: change H_COLL_HOVER to H_COL_HOVER for consistency 2021-11-18 14:37:05 -05:00
Peter Barker 409147a291 AP_RCProtocol: add support for DJI Fast SBUS
It's just SBUS... but with increased opportunities for corruption
2021-11-18 17:19:04 +11:00
Randy Mackay 0de96f3f4a AP_InertialSensor: vibe units m/s/s
also specify no multiplier
2021-11-18 13:23:06 +09:00
Andrew Tridgell bee44b03b0 AP_Notify: make the buzzer pin configurable on all boards
this allows any board to setup a buzzer pin on any available
GPIO. Previously the pin if set in hwdef.dat was not configurable
2021-11-18 15:22:03 +11:00
Andrew Tridgell c5ff9ac23f AP_Parachute: added arming check for chute released 2021-11-18 15:21:15 +11:00
Wynn, Jesse Stewart a7321cbae1 AP_RangeFinder_LightWareSerial: check dist for lost signal flags
consider messages valid only if they are non-negative AND if the value is not a known lost-signal reading
2021-11-18 12:06:57 +11:00
Andy Piper 77acf9bcc2 AP_Vehicle: correct update_dynamic_notch_at_specified_rate() 2021-11-17 13:35:34 +00:00
Andy Piper ac263e5659 AP_Vehicle: make sure notch update rate is configurable 2021-11-17 13:35:34 +00:00
Andrew Tridgell fbeaa3be6b hwdef: change MatekH743 to -Os
leave space for more features
2021-11-17 19:39:26 +11:00
Randy Mackay e85a95f21c AR_AttitudeControl: reduce some param defaults
These reductions are based on experirence helping users setup new vehicle.  In the vast majority of cases the existing values are too high

STEER_ANG_P is the default for the angle-to-rate controller and is used during pivot turns.  This value may still be slightly too high.
STEER_RATE_MAX is the maximum turn rate so the new value allows a 360 turn in 3 seconds
STEER_ACCEL_MAX is the acceleration for the turn rate meaning a vehicle can get to 120 deg/sec in 1 sec
THR_ACCEL_MAX is the maximum acceleration.  This new value means a vehicle can accelerate to 1m/s in 1 second.
2021-11-17 19:18:23 +11:00
Randy Mackay 9c54b3d252 AR_AttitudeControl: move param defines from .h to .cpp 2021-11-17 19:18:23 +11:00
Iampete1 7b0f059968 AP_Logger: file content: log only file name if directory won't fit 2021-11-17 19:16:46 +11:00
Iampete1 09dfcdb574 AP_Logger: add scripting log structures 2021-11-17 19:16:46 +11:00
Iampete1 58ef0d0137 AP_Scripting: log files and runtime stats 2021-11-17 19:16:46 +11:00
Iampete1 f32f14b19c AP_Logger: log_file_content: copy filename 2021-11-17 19:16:46 +11:00
Iampete1 817864ce74 AP_Scripting: convert DEBUG_LVL to DEBUG_OPTS bitmask 2021-11-17 19:16:46 +11:00
Andrew Tridgell 42412b2a60 AP_BattMonitor: added VLT_OFFSET for analog
useful for diode bias in voltage monitors

thanks to Charles from ASW and Jeff Wurzbach
2021-11-17 19:09:40 +11:00
Peter Barker c559e27c55 AP_Vehicle: allow specification of Scheduler table priorities 2021-11-17 19:00:04 +11:00
Peter Barker e1310b2082 AP_Scheduler: allow specification of Scheduler table priorities 2021-11-17 19:00:04 +11:00
Peter Barker 1835a63bfb AP_Camera: don't use stale image number in CAMERA_FEEDBACK 2021-11-17 18:48:00 +11:00
Peter Barker 8f1c255693 AP_Camera: stash information required for camera_feedback message
This means the data sent in the mavlink message is closer to the
information when the picture was taken, rather than when we decide we
have the space to send the mavlink message.  When we process the
deferred request to send the camera feedback message is up to the
vagaries of mavlink scheduling, so the data can become quite out-of-date
2021-11-17 18:48:00 +11:00
Peter Barker 411ed0f50e AP_RCProtocol: use data structure for serial configurations 2021-11-16 22:06:24 +11:00
Peter Barker c1cdfb448c AP_RCProtocol: move uart flow control set out of CRSF code
11:32 AM] AndrewTridgell: @Peter Barker we should disable flow control when we first add the uart - none of the RC protocols use flow control
[11:32 AM] AndrewTridgell: the blocking writes call isn't needed
[11:32 AM] Peter Barker: Thanks, I'll make a patch.
2021-11-16 22:06:24 +11:00
Rishabh 647cbe8b68 AC_Avoid: Convert Dijkstras to A-star 2021-11-16 15:08:16 +09:00
TunaLobster 0b2ebfefda AP_WindVane: fix ADC scaling on IOMCU 2021-11-16 14:12:43 +11:00
TunaLobster ba9381f40c AP_RangeFinder: fix ADC scaling on IOMCU 2021-11-16 14:12:43 +11:00
TunaLobster 206a25fbcc AP_RSSI: fix ADC scaling on IOMCU 2021-11-16 14:12:43 +11:00
TunaLobster db6383eee7 AP_IOMCU: fix ADC scaling on IOMCU 2021-11-16 14:12:43 +11:00
TunaLobster 11f98f7421 AP_HAL_ChibiOS: fix ADC scaling on IOMCU 2021-11-16 14:12:43 +11:00
HefnySco 5aa3714e71 WEBOTS_SITL: adjust_params model 2021-11-16 13:30:12 +11:00
Josh Henderson fb28b39206 AP_BattMonitor: remove old parameter conversion to allow setting BATT_MONITOR to 0 2021-11-16 11:58:01 +11:00
Shiv Tyagi a747a4a19a AP_Devo_Telem: fix gpsDdToDmsFormat method
This fixes gpsDdToDmsFormat method to correctly convert decimal degrees to degrees minutes with less precision loss
2021-11-16 11:37:10 +11:00
Peter Barker 514368537b GCS_MAVLink: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker 6b9ef0aba8 AP_Vehicle: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker f4651f0287 AP_Scripting: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker 65b335ae0c AP_Notify: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker 55cdbd208d AP_Motors: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker ff58afd4a2 AP_Mission: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker 64aaf9d93d AP_Frsky_Telem: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker 13dc37fdcc AP_DAL: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker a729ba165e AP_Arming: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker 8e15bf09a6 AC_AttitudeControl: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED 2021-11-15 20:27:40 +11:00
Peter Barker fd128066ad GCS_MAVLink: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Peter Barker c090ddc65c AP_Vehicle: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Peter Barker 6b4de23630 AP_Scripting: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Peter Barker 4eaba21e15 AP_Notify: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Peter Barker 9e8126d07c AP_Motors: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Peter Barker 6fef352b8f AP_Mission: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Peter Barker 39a4f0b3b2 AP_Frsky_Telem: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Peter Barker c153225ccf AP_Arming: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Peter Barker 38479905c0 AC_AttitudeControl: ensure ENABLE_SCRIPTING is always defined 2021-11-15 20:27:40 +11:00
Pierre Kancir 4037104f59 AP_UAVCAN: hide -Wcast-function-type warning on GCC11 2021-11-13 17:28:30 +11:00
Shiv Tyagi 516eafa45b AP_Rangefinder: fail RF prearm checks for NoData/NotConnected statuses
Earlier we only failed RF checks if we could not detect an RF instance but we should also fail it if the RF is not connected or we receive no data.
2021-11-13 09:47:39 +09:00
Iampete1 c83ff858b8 Remove AP_SpdHgtControl 2021-11-13 08:05:39 +11:00
Iampete1 e0f03a3e09 AP_TECS: no longer child of SpdHgtController 2021-11-13 08:05:39 +11:00
Iampete1 7bf1fe1277 AP_Soaring: remove SpdHgt and use TECS direct 2021-11-13 08:05:39 +11:00
Iampete1 1c195d01b8 AP_Landing: remove SpdHgt and use TECS direct 2021-11-13 08:05:39 +11:00
Iampete1 29455adab4 AP_L1_Control: remove SpdHgt and use TECS direct 2021-11-13 08:05:39 +11:00
Peter Barker eb6da9512f AP_HAL_SITL: quieten i2c-device-creation diagnostics 2021-11-12 10:17:28 +11:00
Peter Barker 60453b2250 SITL: quieten MKFIFO warning in case of EEXIST 2021-11-12 09:56:28 +11:00
Peter Barker 5e18f98b8e AP_RCProtocol: number all of the RC Protocols supported
Needed this as soon as we got the RC_PROTOCOL bitmask
2021-11-12 09:00:45 +11:00
Andy Piper 00da3520bc Filter: set output slew rate to zero when max is zero. 2021-11-11 08:13:23 +09:00
Andy Piper 819645d1f6 AC_AutoTune: set slew rate to 0 while twitching 2021-11-11 08:13:23 +09:00
Andy Piper e84a05d5ba AC_PID: add slew_rate modifier 2021-11-11 08:13:23 +09:00
Bill Geyer d2c37daa66 AP_Motors: change internal variable names and methods for mid collective to be more accurate 2021-11-10 16:45:17 -05:00
Bill Geyer 183b5e9e6d AP_Motors: update H_SV_MAN parameter to reflect zero thrust collective 2021-11-10 16:45:17 -05:00
Bill Geyer d02097bf1c AP_Motors: add protection for new tradheli parameters 2021-11-10 16:45:17 -05:00
Bill Geyer 1a50dce206 AP_Motors: coll setup uses actual blade pitch angle 2021-11-10 16:45:17 -05:00
Andrew Tridgell c3442d0143 hwdef: added alternative Durandal 20602 IMU 2021-11-11 08:28:51 +11:00
Patrick José Pereira 6ac7c2dbea AP_HAL_Linux: Update SPIDevice for Navigator R4
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
2021-11-10 18:11:34 -03:00
Patrick José Pereira 176c70b5ff AP_HAL: Update Navigator board to R4
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
2021-11-10 18:11:34 -03:00
Patrick José Pereira 91ea129be3 AP_Compass: Add support to AK09915
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
2021-11-10 18:11:34 -03:00
torsten 14c9de4d95 AP_FETtecOneWire: reset buf_used
if byte is missing due to electrical noise it can now resync
2021-11-11 07:44:57 +11:00
Andrew Tridgell 3f936baf5c AC_AttitudeControl: adjust docs for rate max limits
after discussion with Leonard
2021-11-11 07:22:38 +11:00
bugobliterator 6d07a512e9 StorageManager: fix storage manager counts and merge common areas 2021-11-10 19:03:59 +11:00
Andrew Tridgell 71faeb926c RC_Channel: added fixed wing autotune rc option 2021-11-10 18:46:34 +11:00
Jaime 5d117c6ae7 hwdef: CubeOrange Enable Serial2 and Serial3 in bootloader hwdef 2021-11-10 18:10:20 +11:00
bugobliterator 60e0bec628 AP_Common: add support for setting custom external buffer 2021-11-10 17:21:35 +11:00
bugobliterator 09096cb355 AP_HAL_SITL: add get_storage_ptr method 2021-11-10 17:21:35 +11:00
bugobliterator f57f106c7f AP_HAL_Linux: add get_storage_ptr method 2021-11-10 17:21:35 +11:00
bugobliterator 7a1044309c AP_HAL_ESP32: add get_storage_ptr method 2021-11-10 17:21:35 +11:00
bugobliterator b025c17ec4 AP_HAL_ChibiOS: add get_storage_ptr method 2021-11-10 17:21:35 +11:00
bugobliterator 6d4ac999d0 AP_HAL: add get_storage_ptr method 2021-11-10 17:21:35 +11:00
bugobliterator 528e57c2ae AP_Filesystem: add support for downloading raw storage via ftp sysfs 2021-11-10 17:21:35 +11:00
Iampete1 6c29eb73d2 AP_Motors: Coax: correct array indexnig offset 2021-11-10 11:52:19 +09:00
Iampete1 291ab5b5f2 AP_Motors: Coax: remvoe servo outs from motor mask 2021-11-10 11:52:19 +09:00
Willian Galvani 4c756fd7ef AP_Compass: update MMMC5XX3 driver to support only mmc5983
Registers changed
Product ID changed
Data is now Big endian
Results are now 18 bits instead of 16, but we only consume 16.
Added SPI support

Co-authored-by: Patrick Pereira <patrickelectric@gmail.com>
Co-authored-by: Jacob Walser <jwalser90@gmail.com>
2021-11-10 11:38:25 +11:00
Iampete1 1771481779 AP_Compass: never override custom orentation in calabration 2021-11-10 09:28:54 +11:00
Kirill Shilov f97182f48a hwdef: AIRLink board support 2021-11-10 08:47:21 +11:00
Andrew Tridgell e1c9da85b9 AP_BoardConfig: allow for heater polarity setting on FMU 2021-11-10 08:47:21 +11:00
Andrew Tridgell f7bc7b0d9b HAL_ChibiOS: support more enable pins for late enable 2021-11-10 08:47:21 +11:00
Andrew Tridgell 61cc86b911 GCS_MAVLINK: fixed build of boards with APJ_BOARD_ID>32768
this impacts modalai_fc_v1
2021-11-10 08:46:52 +11:00
Peter Barker 7c774d02bb AP_RCProtocol: remove pointless 100kbaud speed change
added.opened is set to false.  Next time we check_added_uart, the baud
rate is unconditionally set in each of the phases.  Thus this line has
no effect except to confuse the reader
2021-11-10 07:04:47 +11:00
Samuel Tabor 266fbabb6f AP_Landing: Fix slope calculation. 2021-11-10 06:55:14 +11:00
Peter Barker 065cb2decb AP_GPS_UBLOX: tidy reading of uart data
Neither of the return types used for data and numc were actually correct for the values being returned from the uartdriver functions.
2021-11-09 10:31:25 +11:00