From bb0631b679c83b0c1f337b7e8c506e2cf6cf03c3 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Wed, 25 Sep 2024 19:12:30 +1000 Subject: [PATCH] hwdef: CarbonixCommon: fix ARSPD_TYPE default The default value in defaults.parm was being used correctly, but the default value was reported to the GCS incorrectly. AP_Airspeed overwrites the default for airspeed 1 at runtime, though not in a way that messes up the parameter value. --- libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc | 3 +++ libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm | 1 - libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm | 1 - .../AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm | 1 - 4 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc index 19420ff7ea..97520bad4a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc @@ -16,4 +16,7 @@ PB7 VDD_BRICK2_VALID INPUT PULLUP undef HAL_IMU_TEMP_DEFAULT define HAL_IMU_TEMP_DEFAULT 60 +# Set default airspeed type to DroneCAN +define HAL_AIRSPEED_TYPE_DEFAULT TYPE_UAVCAN + USE_BOOTLOADER_FROM_BOARD CubeOrange diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm index 822750cfc0..ea6f0e659c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm @@ -5,7 +5,6 @@ ARMING_MIS_ITEMS,22 ARMING_RUDDER,0 ARSPD_RATIO,1.6 ARSPD_SKIP_CAL,1 -ARSPD_TYPE,8 ARSPD_USE,1 ARSPD_WIND_MAX,25 ARSPD_WIND_WARN,12 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index d4f459fc28..ff0a032746 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -3,7 +3,6 @@ AIRSPEED_CRUISE,26 AIRSPEED_MAX,36 AIRSPEED_MIN,23 -ARSPD_TYPE,8 BATT_ARM_MAH,10000 BATT_ARM_VOLT,24 BATT_CAPACITY,30600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm index ac310fb73a..f300b1cb79 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm @@ -3,7 +3,6 @@ AIRSPEED_CRUISE,21 AIRSPEED_MAX,28 AIRSPEED_MIN,20 -ARSPD_TYPE,8 BATT_CAPACITY,22000 BATT_CRT_VOLT,44.4 BATT_FS_LOW_ACT,1