From 8318e106da4c093b0f0c60c2ed7882010c936595 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 29 Nov 2024 15:15:11 +1100 Subject: [PATCH 1/7] hwdef: Ottano defaults: enable ADSB rx --- .../AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index ae58f19d68..99c3c5a337 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -1,8 +1,17 @@ @include ../CarbonixCommon/defaults.parm # Ottano-specific parameters +ADSB_LIST_ALT,3000 +ADSB_LIST_MAX,40 +ADSB_LIST_RADIUS,30000 +ADSB_TYPE,1 AIRSPEED_CRUISE,26 AIRSPEED_MAX,36 AIRSPEED_MIN,23 +AVD_ENABLE,1 +AVD_F_DIST_XY,1000 +AVD_F_DIST_Z,200 +AVD_W_DIST_XY,5000 +AVD_W_DIST_Z,1000 # Battery 1: VTOL Battery (Combined) BATT_CAPACITY,30000 # Sum of BATT4_CAPACITY and BATT5_CAPACITY BATT_MONITOR,10 # Sum From d8ea67c40cce6cdbc909482b89ad9dd189e0cce1 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 29 Nov 2024 15:15:47 +1100 Subject: [PATCH 2/7] hwdef: Ottano defaults: tweak idle governor --- libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index 99c3c5a337..0be7c34bce 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -77,8 +77,9 @@ GPS_POS1_Y,-1.05 GPS_POS2_X,-0.135 GPS_POS2_Y,1.05 ICE_ENABLE,1 +ICE_IDLE_DB,100 ICE_IDLE_RPM,2400 -ICE_IDLE_SLEW,2 +ICE_IDLE_SLEW,4 ICE_OPTIONS,4 ICE_RPM_CHAN,1 ICE_START_CHAN,6 From 2354887b2dac1fbb638e50a15af508ad7ad52142 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 29 Nov 2024 15:16:22 +1100 Subject: [PATCH 3/7] hwdef: Ottano defaults: FBWB_CLIMB_RATE to 2 This parameter is actually an integer, not a float (though it probably should be a float). --- libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index 0be7c34bce..1b1c86cd02 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -71,7 +71,6 @@ EFI_THRLIN_COEF3,0.0002301534 EFI_THRLIN_EN,1 EFI_THRLIN_OFS,6 EFI_TYPE,8 -FBWB_CLIMB_RATE,2.4 GPS_POS1_X,-0.135 GPS_POS1_Y,-1.05 GPS_POS2_X,-0.135 From 8c3b713d4ef84b9e86c69ae68af216c1e6d4cf95 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 29 Nov 2024 15:18:32 +1100 Subject: [PATCH 4/7] hwdef: Ottano defaults: increase ICE start thr --- libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index 1b1c86cd02..9c52e28ad9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -83,6 +83,7 @@ ICE_OPTIONS,4 ICE_RPM_CHAN,1 ICE_START_CHAN,6 ICE_START_DELAY,3 +ICE_START_PCT,10 ICE_STARTCHN_MIN,950 ICE_STARTER_TIME,5 INS_ACCEL_FILTER,10 From ddb6c43abfc6255e3df9311d8c1bbe7f3a80ed9a Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 29 Nov 2024 15:32:24 +1100 Subject: [PATCH 5/7] hwdef: CarbonixCommon: move pitch limits out --- libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm | 2 -- libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm | 2 ++ libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm | 2 ++ 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm index 2301497613..d2439ebdb4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm @@ -61,8 +61,6 @@ LOG_FILE_DSRMROT,1 LOG_FILE_MB_FREE,5000 # DISABLE_CHECKS: we want to reserve 5GB for logs; ArduPilot suggests max of 1GB LOG_REPLAY,1 MIN_GROUNDSPEED,8 -PTCH_LIM_MAX_DEG,16 -PTCH_LIM_MIN_DEG,-13 Q_A_THR_MIX_MAN,0.25 Q_A_THR_MIX_MAX,0.65 Q_A_THR_MIX_MIN,0.25 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index 9c52e28ad9..1d823576bd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -111,6 +111,8 @@ INS_POS3_X,0.82 KFF_RDDRMIX,1 NAVL1_LIM_BANK,35 # Set to match ROLL_LIMIT_DEG NAVL1_PERIOD,27 +PTCH_LIM_MAX_DEG,16 +PTCH_LIM_MIN_DEG,-13 PTCH_RATE_D,0.0065 PTCH_RATE_FF,0.7402687 PTCH_RATE_FLTD,11 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm index 10843d3209..0fbddeb744 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm @@ -84,6 +84,8 @@ INS_POS3_Z,-0.03 KFF_RDDRMIX,0.9 NAVL1_LIM_BANK,40 # Set to match ROLL_LIMIT_DEG NAVL1_PERIOD,19 +PTCH_LIM_MAX_DEG,16 +PTCH_LIM_MIN_DEG,-13 PTCH_RATE_D,0.0029344 PTCH_RATE_FF,0.36 PTCH_RATE_FLTD,10 From ebdd61bd3c142584db268f8e22a7a9333ac13a73 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 29 Nov 2024 15:24:57 +1100 Subject: [PATCH 6/7] hwdef: Ottano defaults: fixed-wing tuning --- .../hwdef/CubeOrange-Ottano/defaults.parm | 55 +++++++++---------- 1 file changed, 26 insertions(+), 29 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index 1d823576bd..9e120af521 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -110,21 +110,22 @@ INS_POS2_X,0.82 INS_POS3_X,0.82 KFF_RDDRMIX,1 NAVL1_LIM_BANK,35 # Set to match ROLL_LIMIT_DEG -NAVL1_PERIOD,27 -PTCH_LIM_MAX_DEG,16 -PTCH_LIM_MIN_DEG,-13 -PTCH_RATE_D,0.0065 -PTCH_RATE_FF,0.7402687 +NAVL1_PERIOD,25 +PTCH_LIM_MAX_DEG,8 +PTCH_LIM_MIN_DEG,-10 +PTCH_RATE_D,0.0019006 +PTCH_RATE_FF,0.7802848 PTCH_RATE_FLTD,11 -PTCH_RATE_FLTT,3.183099 -PTCH_RATE_I,0.7402687 # DISABLE_CHECKS: it is recommended for RATE_I to match RATE_FF on planes, but the metadata gives a limit of 0.6 for this and 3.0 for FF +PTCH_RATE_FLTT,1.768388 # DISABLE_CHECKS: slightly below recommended 2.0 +PTCH_RATE_I,0.7802848 # DISABLE_CHECKS: it is recommended for RATE_I to match RATE_FF on planes, but the metadata gives a limit of 0.6 for this and 3.0 for FF PTCH_RATE_IMAX,0.4 -PTCH_RATE_P,0.2194594 +PTCH_RATE_P,0.2409001 PTCH_RATE_SMAX,110 -PTCH_TRIM_DEG,3 -PTCH2SRV_RLL,1.05 -PTCH2SRV_RMAX_DN,45 -PTCH2SRV_RMAX_UP,75 +PTCH_TRIM_DEG,1 +PTCH2SRV_RLL,1.5 +PTCH2SRV_RMAX_DN,60 +PTCH2SRV_RMAX_UP,60 +PTCH2SRV_TCONST,0.9 Q_A_ACCEL_P_MAX,8800 Q_A_ACCEL_R_MAX,9000 Q_A_ACCEL_Y_MAX,4000 @@ -200,15 +201,16 @@ Q_WVANE_GAIN,1 RELAY1_FUNCTION,4 RELAY2_FUNCTION,2 RELAY2_PIN,108 -RLL_RATE_D,0.001917198 -RLL_RATE_FF,0.7728607 +RLL_RATE_D,0.0077308 +RLL_RATE_FF,0.6552786 RLL_RATE_FLTD,11 -RLL_RATE_FLTT,3.183099 -RLL_RATE_I,0.7728607 # DISABLE_CHECKS: it is recommended for RATE_I to match RATE_FF on planes, but the metadata gives a limit of 0.6 for this and 3.0 for FF +RLL_RATE_FLTT,2.652582 +RLL_RATE_I,0.2274013 RLL_RATE_IMAX,0.4 -RLL_RATE_P,0.09429314 +RLL_RATE_P,0.2274013 RLL_RATE_SMAX,125 -RLL2SRV_RMAX,75 +RLL2SRV_RMAX,60 +RLL2SRV_TCONST,0.6 RNGFND1_GNDCLEAR,27 RNGFND1_POS_X,0.93 RNGFND1_TYPE,24 @@ -259,19 +261,14 @@ SERVO8_MAX,2000 SERVO8_MIN,1000 SERVO9_MAX,2000 SERVO9_MIN,1000 -TECS_CLMB_MAX,4 -TECS_INTEG_GAIN,0.15 +TECS_CLMB_MAX,3.5 TECS_LAND_ARSPD,24 -TECS_PITCH_MAX,16 -TECS_PITCH_MIN,-8 -TECS_PTCH_DAMP,0.4 -TECS_RLL2THR,20 -TECS_SINK_MAX,2.7 -TECS_SINK_MIN,2.4 -TECS_SPDWEIGHT,0.5 -TECS_THR_DAMP,0.4 +TECS_PITCH_MAX,0 +TECS_PTCH_DAMP,0.5 +TECS_RLL2THR,5 +TECS_SINK_MAX,4.2 +TECS_SINK_MIN,3 TECS_TIME_CONST,4 -TECS_VERT_ACC,6 THR_SLEWRATE,50 TRIM_THROTTLE,60 WP_LOITER_RAD,250 From 04a0cca5909f7f9568395a34a5805143303cbc48 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 29 Nov 2024 15:26:42 +1100 Subject: [PATCH 7/7] hwdef: Ottano defaults: reduce hover gains O10 was having occasional oscillations --- .../hwdef/CubeOrange-Ottano/defaults.parm | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm index 9e120af521..cfd17b873e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -130,20 +130,20 @@ Q_A_ACCEL_P_MAX,8800 Q_A_ACCEL_R_MAX,9000 Q_A_ACCEL_Y_MAX,4000 Q_A_ANG_YAW_P,2 # DISABLE_CHECKS: AP limits are based on small quadcopters -Q_A_RAT_PIT_D,0.03447478 +Q_A_RAT_PIT_D,0.02 Q_A_RAT_PIT_FLTD,11 Q_A_RAT_PIT_FLTE,8 Q_A_RAT_PIT_FLTT,11 -Q_A_RAT_PIT_I,0.4894217 +Q_A_RAT_PIT_I,0.45 Q_A_RAT_PIT_IMAX,0.4 -Q_A_RAT_PIT_P,0.4894217 +Q_A_RAT_PIT_P,0.45 Q_A_RAT_PIT_SMAX,15 -Q_A_RAT_RLL_D,0.02028733 +Q_A_RAT_RLL_D,0.01 Q_A_RAT_RLL_FLTD,11 Q_A_RAT_RLL_FLTE,8 Q_A_RAT_RLL_FLTT,11 -Q_A_RAT_RLL_I,0.8448284 -Q_A_RAT_RLL_P,0.8448284 # DISABLE_CHECKS: AP limits are based on small quadcopters +Q_A_RAT_RLL_I,0.75 +Q_A_RAT_RLL_P,0.75 # DISABLE_CHECKS: AP limits are based on small quadcopters Q_A_RAT_RLL_SMAX,15 Q_A_RAT_YAW_D,0.002 Q_A_RAT_YAW_FLTD,11