From ffafdba81431588e45e92b3821a86fe376c9168a Mon Sep 17 00:00:00 2001 From: Pradeep CK Date: Thu, 15 Aug 2024 11:38:15 +1000 Subject: [PATCH] HWDEF : Squash of all Carbonix HWDEFs --- .../cpn_params/Ottano/Ottano-LTail.parm | 7 + .../cpn_params/Ottano/Ottano-LWing.parm | 8 + .../cpn_params/Ottano/Ottano-M1.parm | 9 + .../cpn_params/Ottano/Ottano-M2.parm | 9 + .../cpn_params/Ottano/Ottano-M3.parm | 9 + .../cpn_params/Ottano/Ottano-M4.parm | 9 + .../cpn_params/Ottano/Ottano-M5.parm | 13 + .../cpn_params/Ottano/Ottano-RTail.parm | 8 + .../cpn_params/Ottano/Ottano-RWing.parm | 8 + .../cpn_params/Volanti/Volanti-LTail.parm | 7 + .../cpn_params/Volanti/Volanti-LWing.parm | 8 + .../cpn_params/Volanti/Volanti-M1.parm | 12 + .../cpn_params/Volanti/Volanti-M2.parm | 12 + .../cpn_params/Volanti/Volanti-M3.parm | 12 + .../cpn_params/Volanti/Volanti-M4.parm | 12 + .../cpn_params/Volanti/Volanti-M5.parm | 16 + .../cpn_params/Volanti/Volanti-RTail.parm | 8 + .../cpn_params/Volanti/Volanti-RWing.parm | 8 + .../hwdef/CarbonixCommon/cubeorange.inc | 18 + .../hwdef/CarbonixCommon/defaults.parm | 167 +++++++++ .../hwdef/CarbonixCommon/features.inc | 332 ++++++++++++++++++ .../CarbonixCommon/payloads/A7R1/Cube.param | 4 + .../payloads/A7R1/cpn_15(SerialGPS).parm | 2 + .../payloads/A7R1/cpn_19(DroneCANGPS).parm | 2 + .../payloads/A7R1/cpn_29(DroneCANGPS).parm | 2 + .../CarbonixCommon/payloads/CM62/Cube.param | 5 + .../payloads/Nighthawk/Cube.param | 6 + .../scripts/cx_built_in_test.lua | 243 +++++++++++++ .../CarbonixCommon/scripts/cx_led_driver.lua | 49 +++ .../CarbonixF405-no-crystal/hwdef-bl.dat | 7 + .../hwdef/CarbonixF405-no-crystal/hwdef.dat | 7 + .../hwdef/CarbonixF405/hwdef-bl.dat | 6 +- .../hwdef/CarbonixF405/hwdef.dat | 44 +-- .../hwdef/CarbonixL496/hwdef-bl.dat | 72 ---- .../hwdef/CarbonixL496/hwdef.dat | 143 -------- .../hwdef/CubeOrange-Ottano/defaults.parm | 227 ++++++++++++ .../hwdef/CubeOrange-Ottano/hwdef.dat | 1 + .../scripts/cx_built_in_test.lua | 1 + .../scripts/cx_led_driver.lua | 1 + .../hwdef/CubeOrange-Volanti/defaults.parm | 188 ++++++++++ .../hwdef/CubeOrange-Volanti/hwdef.dat | 1 + .../scripts/cx_built_in_test.lua | 1 + .../scripts/cx_led_driver.lua | 1 + 43 files changed, 1467 insertions(+), 238 deletions(-) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-LTail.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-LWing.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M1.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M2.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M3.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M4.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M5.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-RTail.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-RWing.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-LTail.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-LWing.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M1.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M2.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M3.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M4.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M5.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-RTail.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-RWing.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/features.inc create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/Cube.param create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_15(SerialGPS).parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_19(DroneCANGPS).parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_29(DroneCANGPS).parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/CM62/Cube.param create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/Nighthawk/Cube.param create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/scripts/cx_built_in_test.lua create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/scripts/cx_led_driver.lua create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405-no-crystal/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405-no-crystal/hwdef.dat delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/hwdef.dat create mode 120000 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/scripts/cx_built_in_test.lua create mode 120000 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/scripts/cx_led_driver.lua create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/hwdef.dat create mode 120000 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/scripts/cx_built_in_test.lua create mode 120000 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/scripts/cx_led_driver.lua diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-LTail.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-LTail.parm new file mode 100644 index 0000000000..edb92689e8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-LTail.parm @@ -0,0 +1,7 @@ +CAN_NODE 17 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_FUNCTION 56 +OUT2_MIN 1000 +OUT2_MAX 2000 +OUT2_FUNCTION 61 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-LWing.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-LWing.parm new file mode 100644 index 0000000000..1b399c4b47 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-LWing.parm @@ -0,0 +1,8 @@ +CAN_NODE 26 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_FUNCTION 60 +OUT2_MIN 200 +OUT2_MAX 10000 +OUT2_TRIM 5000 +OUT2_FUNCTION 59 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M1.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M1.parm new file mode 100644 index 0000000000..85fc50dc6a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M1.parm @@ -0,0 +1,9 @@ +CAN_NODE 11 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 33 +OUT2_FUNCTION 0 +ESC_PWM_TYPE 1 +ESC_TELEM_PORT 1 +ESC_APD_SERIAL_1 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M2.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M2.parm new file mode 100644 index 0000000000..d87c3b6cc3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M2.parm @@ -0,0 +1,9 @@ +CAN_NODE 12 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 34 +OUT2_FUNCTION 0 +ESC_PWM_TYPE 1 +ESC_TELEM_PORT 1 +ESC_APD_SERIAL_1 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M3.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M3.parm new file mode 100644 index 0000000000..ce7d30d719 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M3.parm @@ -0,0 +1,9 @@ +CAN_NODE 23 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 35 +OUT2_FUNCTION 0 +ESC_PWM_TYPE 1 +ESC_TELEM_PORT 1 +ESC_APD_SERIAL_1 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M4.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M4.parm new file mode 100644 index 0000000000..bdfeaf97c1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M4.parm @@ -0,0 +1,9 @@ +CAN_NODE 24 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 36 +OUT2_FUNCTION 0 +ESC_PWM_TYPE 1 +ESC_TELEM_PORT 1 +ESC_APD_SERIAL_1 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M5.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M5.parm new file mode 100644 index 0000000000..7d507518ee --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-M5.parm @@ -0,0 +1,13 @@ +CAN_NODE 15 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 37 +OUT2_FUNCTION 0 +ESC_PWM_TYPE 1 +ESC_TELEM_PORT 1 +ESC_APD_SERIAL_1 1 +RNGFND_PORT 2 +RNGFND1_TYPE 8 +RNGFND1_MAX_CM 15800 +RNGFND1_GNDCLEAR 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-RTail.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-RTail.parm new file mode 100644 index 0000000000..8de58672d2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-RTail.parm @@ -0,0 +1,8 @@ +CAN_NODE 27 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_REVERSED 1 +OUT1_FUNCTION 56 +OUT2_MIN 1000 +OUT2_MAX 2000 +OUT2_FUNCTION 61 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-RWing.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-RWing.parm new file mode 100644 index 0000000000..40c506799b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Ottano/Ottano-RWing.parm @@ -0,0 +1,8 @@ +CAN_NODE 16 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_FUNCTION 60 +OUT2_MIN 200 +OUT2_MAX 10000 +OUT2_TRIM 5000 +OUT2_FUNCTION 59 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-LTail.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-LTail.parm new file mode 100644 index 0000000000..edb92689e8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-LTail.parm @@ -0,0 +1,7 @@ +CAN_NODE 17 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_FUNCTION 56 +OUT2_MIN 1000 +OUT2_MAX 2000 +OUT2_FUNCTION 61 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-LWing.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-LWing.parm new file mode 100644 index 0000000000..1b399c4b47 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-LWing.parm @@ -0,0 +1,8 @@ +CAN_NODE 26 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_FUNCTION 60 +OUT2_MIN 200 +OUT2_MAX 10000 +OUT2_TRIM 5000 +OUT2_FUNCTION 59 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M1.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M1.parm new file mode 100644 index 0000000000..2036ebea51 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M1.parm @@ -0,0 +1,12 @@ +CAN_NODE 11 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 33 +OUT2_FUNCTION 0 +OUT_BLH_MASK 3 +OUT_BLH_OTYPE 6 +OUT_BLH_POLES 28 +OUT_BLH_EXTLM 1 +ESC_PWM_TYPE 6 +ESC_TELEM_PORT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M2.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M2.parm new file mode 100644 index 0000000000..7f9c2193ce --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M2.parm @@ -0,0 +1,12 @@ +CAN_NODE 12 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 34 +OUT2_FUNCTION 0 +OUT_BLH_MASK 3 +OUT_BLH_OTYPE 6 +OUT_BLH_POLES 28 +OUT_BLH_EXTLM 1 +ESC_PWM_TYPE 6 +ESC_TELEM_PORT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M3.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M3.parm new file mode 100644 index 0000000000..af91360a5f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M3.parm @@ -0,0 +1,12 @@ +CAN_NODE 23 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 35 +OUT2_FUNCTION 0 +OUT_BLH_MASK 3 +OUT_BLH_OTYPE 6 +OUT_BLH_POLES 28 +OUT_BLH_EXTLM 1 +ESC_PWM_TYPE 6 +ESC_TELEM_PORT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M4.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M4.parm new file mode 100644 index 0000000000..e923709e29 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M4.parm @@ -0,0 +1,12 @@ +CAN_NODE 24 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 36 +OUT2_FUNCTION 0 +OUT_BLH_MASK 3 +OUT_BLH_OTYPE 6 +OUT_BLH_POLES 28 +OUT_BLH_EXTLM 1 +ESC_PWM_TYPE 6 +ESC_TELEM_PORT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M5.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M5.parm new file mode 100644 index 0000000000..4c8f9bd33a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-M5.parm @@ -0,0 +1,16 @@ +CAN_NODE 15 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_TRIM 1000 +OUT1_FUNCTION 37 +OUT2_FUNCTION 0 +OUT_BLH_MASK 3 +OUT_BLH_OTYPE 6 +OUT_BLH_POLES 28 +OUT_BLH_EXTLM 0 +ESC_PWM_TYPE 6 +ESC_TELEM_PORT 1 +RNGFND_PORT 2 +RNGFND1_TYPE 8 +RNGFND1_MAX_CM 15800 +RNGFND1_GNDCLEAR 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-RTail.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-RTail.parm new file mode 100644 index 0000000000..8de58672d2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-RTail.parm @@ -0,0 +1,8 @@ +CAN_NODE 27 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_REVERSED 1 +OUT1_FUNCTION 56 +OUT2_MIN 1000 +OUT2_MAX 2000 +OUT2_FUNCTION 61 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-RWing.parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-RWing.parm new file mode 100644 index 0000000000..40c506799b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cpn_params/Volanti/Volanti-RWing.parm @@ -0,0 +1,8 @@ +CAN_NODE 16 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT1_FUNCTION 60 +OUT2_MIN 200 +OUT2_MAX 10000 +OUT2_TRIM 5000 +OUT2_FUNCTION 59 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc new file mode 100644 index 0000000000..209c017ee5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/cubeorange.inc @@ -0,0 +1,18 @@ +# hw definition file for processing by chibios_hwdef.py + +include ../CubeOrange/hwdef.dat +include ./features.inc + +# The Carbonix carrier board (CX13042008) uses uninverted logic for these pins, +# as opposed to how the CubePilot carrier hardware is designed. We have to +# redefine these pin assignments. +undef PB5 +undef PB7 +PB5 VDD_BRICK_VALID INPUT PULLUP +PB7 VDD_BRICK2_VALID INPUT PULLUP + +# Set board heater target to 60C +undef HAL_IMU_TEMP_DEFAULT +define HAL_IMU_TEMP_DEFAULT 60 + +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 new file mode 100644 index 0000000000..bfe437e901 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/defaults.parm @@ -0,0 +1,167 @@ +# Carbonix Common Defaults +AHRS_GPS_MINSATS,20 +AHRS_GPS_USE,2 +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 +ARSPD2_RATIO,1.6 +ARSPD2_SKIP_CAL,1 +ARSPD2_TYPE,8 +ARSPD2_USE,1 +BRD_RTC_TYPES,7 +BRD_SAFETYOPTION,3 +CAM_AUTO_ONLY,1 +CAM_DURATION,1 +CAM_MIN_INTERVAL,800 +CAM_RELAY_ON,0 +CAM_SERVO_OFF,1000 +CAM_TRIGG_TYPE,1 +CAN_D1_UC_OPTION,10 +CAN_D2_UC_NODE,20 +CAN_D2_UC_OPTION,10 +CAN_LOGLEVEL,4 +CAN_P1_DRIVER,1 +CAN_P2_DRIVER,2 +COMPASS_MOTCT,2 +COMPASS_OPTIONS,1 +CRASH_ACC_THRESH,40 +CRASH_DETECT,1 +EK3_AFFINITY,13 +EK3_SRC1_POSZ,3 +FENCE_AUTOENABLE,3 +FENCE_ENABLE,1 +FENCE_OPTIONS,0 +FLTMODE1,11 +FLTMODE3,10 +FLTMODE4,19 +FLTMODE5,7 +FS_GCS_ENABL,1 +FS_LONG_ACTN,1 +FS_LONG_TIMEOUT,10 +GPS_TYPE,9 +GPS_TYPE2,9 +GPS1_CAN_OVRIDE,19 +GPS2_CAN_OVRIDE,29 +INITIAL_MODE,11 +INS_TCAL1_ENABLE,1 +INS_TCAL2_ENABLE,1 +INS_TCAL3_ENABLE,1 +LAND_DISARMDELAY,3 +LAND_THEN_NEUTRL,1 +LEVEL_ROLL_LIMIT,6 +LIM_PITCH_MAX,1600 +LIM_PITCH_MIN,-1300 +LOG_DISARMED,1 +LOG_FILE_DSRMROT,1 +LOG_FILE_MB_FREE,5000 # Old logs on memory card with be deleted to create atleast 5GB memory. +LOG_REPLAY,1 +MIN_GNDSPD_CM,800 +Q_A_THR_MIX_MAN,0.25 +Q_A_THR_MIX_MAX,0.65 +Q_A_THR_MIX_MIN,0.25 +Q_ENABLE,1 +Q_LAND_FINAL_ALT,10 +Q_RC_SPEED,400 +Q_RTL_ALT,45 +Q_RTL_MODE,1 +Q_TRAN_PIT_MAX,2 +Q_TRANS_FAIL,30 +Q_TRANSITION_MS,2000 +Q_VELZ_MAX,200 +Q_VELZ_MAX_DN,180 +Q_VFWD_ALT,5 +Q_WVANE_HGT_MIN,5 +Q_WVANE_TAKEOFF,0 +RC_PROTOCOLS,520 +RC1_MAX,2000 +RC1_MIN,1000 +RC10_MAX,2000 +RC10_MIN,1000 +RC11_MAX,2000 +RC11_MIN,1000 +RC12_MAX,2000 +RC12_MIN,1000 +RC13_MAX,2000 +RC13_MIN,1000 +RC14_MAX,2000 +RC14_MIN,1000 +RC15_MAX,2000 +RC15_MIN,1000 +RC16_MAX,2000 +RC16_MIN,1000 +RC2_MAX,2000 +RC2_MIN,1000 +RC2_REVERSED,1 +RC3_MAX,2000 +RC3_MIN,1000 +RC4_MAX,2000 +RC4_MIN,1000 +RC5_MAX,2000 +RC5_MIN,1000 +RC6_MAX,2000 +RC6_MIN,1000 +RC7_MAX,2000 +RC7_MIN,1000 +RC8_MAX,2000 +RC8_MIN,1000 +RC9_MAX,2000 +RC9_MIN,1000 +RNGFND_LANDING,1 +RNGFND1_MAX_CM,15800 +RNGFND1_MIN_CM,5 +RTL_AUTOLAND,2 +RTL_RADIUS,200 +SCHED_LOOP_RATE,200 # Loop Rate for Control in flight Controller set to 200Hz from 400Hz Results SW-171. +SCR_ENABLE,1 +SCR_HEAP_SIZE,200000 +SCR_VM_I_COUNT,100000 +SERVO1_FUNCTION,33 # Motor 1 +SERVO1_MAX,2000 # Setting all servos to 2000/1000, overriding in platforms if needed +SERVO1_MIN,1000 +SERVO10_FUNCTION,4 # Aileron +SERVO10_MAX,2000 +SERVO10_MIN,1000 +SERVO11_FUNCTION,21 # Rudder +SERVO11_MAX,2000 +SERVO11_MIN,1000 +SERVO12_MAX,2000 +SERVO12_MIN,1000 +SERVO13_MAX,2000 +SERVO13_MIN,1000 +SERVO14_FUNCTION,0 # PLB Servo/GPIO +SERVO14_MAX,2000 +SERVO14_MIN,1000 +SERVO15_MAX,2000 +SERVO15_MIN,1000 +SERVO16_MAX,2000 +SERVO16_MIN,1000 +SERVO2_FUNCTION,34 # Motor 2 +SERVO2_MAX,2000 +SERVO2_MIN,1000 +SERVO3_FUNCTION,35 # Motor 3 +SERVO3_MAX,2000 +SERVO3_MIN,1000 +SERVO4_FUNCTION,36 # Motor 4 +SERVO4_MAX,2000 +SERVO4_MIN,1000 +SERVO5_FUNCTION,70 # Pusher throttle +SERVO5_MAX,2000 +SERVO5_MIN,1000 +SERVO6_FUNCTION,19 # Elevator +SERVO6_MAX,2000 +SERVO6_MIN,1000 +SERVO7_FUNCTION,0 # PLB Servo/GPIO +SERVO7_MAX,2000 +SERVO7_MIN,1000 +SERVO8_FUNCTION,-1 # IGN relay GPIO +SERVO8_MAX,2000 +SERVO8_MIN,1000 +SERVO9_FUNCTION,94 # Scripting function for LEDs +SERVO9_MAX,2000 +SERVO9_MIN,1000 +TERRAIN_FOLLOW,72 # Enabled Auto and Guided (the command being executed must have the terrain frame though) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/features.inc b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/features.inc new file mode 100644 index 0000000000..46d95e40b5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/features.inc @@ -0,0 +1,332 @@ +undef HAL_NAVEKF3_AVAILABLE +undef HAL_NAVEKF2_AVAILABLE +undef HAL_EXTERNAL_AHRS_ENABLED +undef HAL_INS_TEMPERATURE_CAL_ENABLE +undef HAL_VISUALODOM_ENABLED +undef EK3_FEATURE_EXTERNAL_NAV +undef AP_VOLZ_ENABLED +undef AP_ROBOTISSERVO_ENABLED +undef AP_FETTEC_ONEWIRE_ENABLED +undef AP_AIRSPEED_ANALOG_ENABLED +undef AP_AIRSPEED_ASP5033_ENABLED +undef AP_AIRSPEED_DLVR_ENABLED +undef AP_AIRSPEED_MS4525_ENABLED +undef AP_AIRSPEED_MS5525_ENABLED +undef AP_AIRSPEED_MSP_ENABLED +undef AP_AIRSPEED_NMEA_ENABLED +undef AP_AIRSPEED_SDP3X_ENABLED +undef AP_AIRSPEED_UAVCAN_ENABLED +undef AP_BATTMON_FUELFLOW_ENABLE +undef AP_BATTMON_FUELLEVEL_PWM_ENABLE +undef AP_BATTMON_FUELLEVEL_ANALOG_ENABLE +undef AP_BATTMON_SMBUS_ENABLE +undef HAL_BATTMON_INA2XX_ENABLED +undef HAL_RUNCAM_ENABLED +undef MODE_ZIGZAG_ENABLED +undef MODE_SYSTEMID_ENABLED +undef MODE_SPORT_ENABLED +undef MODE_FOLLOW_ENABLED +undef MODE_TURTLE_ENABLED +undef MODE_GUIDED_NOGPS_ENABLED +undef MODE_FLOWHOLD_ENABLED +undef MODE_FLIP_ENABLED +undef HAL_PICCOLO_CAN_ENABLE +undef HAL_TORQEEDO_ENABLED +undef AP_GPS_UBLOX_ENABLED +undef AP_GPS_SBP2_ENABLED +undef AP_GPS_SBP_ENABLED +undef AP_GPS_ERB_ENABLED +undef AP_GPS_GSOF_ENABLED +undef AP_GPS_NMEA_ENABLED +undef AP_GPS_MAV_ENABLED +undef AP_GPS_NOVA_ENABLED +undef AP_GPS_SBF_ENABLED +undef AP_GPS_SIRF_ENABLED +undef HAL_MOUNT_ENABLED +undef HAL_MOUNT_ALEXMOS_ENABLED +undef HAL_MOUNT_GREMSY_ENABLED +undef HAL_MOUNT_SERVO_ENABLED +undef HAL_MOUNT_SIYI_ENABLED +undef HAL_SOLO_GIMBAL_ENABLED +undef HAL_MOUNT_STORM32MAVLINK_ENABLED +undef HAL_MOUNT_STORM32SERIAL_ENABLED +undef AP_ICENGINE_ENABLED +undef HAL_EFI_ENABLED +undef HAL_EFI_NWPWU_ENABLED +undef HAL_GENERATOR_ENABLED +undef HAL_ADSB_ENABLED +undef HAL_ADSB_SAGETECH_ENABLED +undef HAL_ADSB_SAGETECH_MXS_ENABLED +undef HAL_ADSB_UAVIONIX_MAVLINK_ENABLED +undef HAL_ADSB_UCP_ENABLED +undef AP_AIS_ENABLED +undef HAL_MSP_ENABLED +undef HAL_MSP_SENSORS_ENABLED +undef HAL_MSP_GPS_ENABLED +undef HAL_MSP_COMPASS_ENABLED +undef HAL_MSP_OPTICALFLOW_ENABLED +undef HAL_MSP_RANGEFINDER_ENABLED +undef HAL_WITH_MSP_DISPLAYPORT +undef OSD_ENABLED +undef HAL_PLUSCODE_ENABLE +undef OSD_PARAM_ENABLED +undef HAL_OSD_SIDEBAR_ENABLE +undef HAL_WITH_DSP +undef HAL_DISPLAY_ENABLED +undef HAL_NMEA_OUTPUT_ENABLED +undef HAL_BARO_WIND_COMP_ENABLED +undef GRIPPER_ENABLED +undef HAL_SPRAYER_ENABLED +undef LANDING_GEAR_ENABLED +undef WINCH_ENABLED +undef HAL_QUADPLANE_ENABLED +undef HAL_SOARING_ENABLED +undef HAL_LANDING_DEEPSTALL_ENABLED +undef AP_RANGEFINDER_ENABLED +undef AP_RANGEFINDER_ANALOG_ENABLED +undef AP_RANGEFINDER_BBB_PRU_ENABLED +undef AP_RANGEFINDER_BEBOP_ENABLED +undef AP_RANGEFINDER_BENEWAKE_CAN_ENABLED +undef AP_RANGEFINDER_BENEWAKE_TF02_ENABLED +undef AP_RANGEFINDER_BENEWAKE_TF03_ENABLED +undef AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED +undef AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED +undef AP_RANGEFINDER_BLPING_ENABLED +undef AP_RANGEFINDER_GYUS42V2_ENABLED +undef AP_RANGEFINDER_HC_SR04_ENABLED +undef AP_RANGEFINDER_LANBAO_ENABLED +undef AP_RANGEFINDER_LEDDARONE_ENABLED +undef AP_RANGEFINDER_LEDDARVU8_ENABLED +undef AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED +undef AP_RANGEFINDER_LWI2C_ENABLED +undef AP_RANGEFINDER_MAVLINK_ENABLED +undef AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED +undef AP_RANGEFINDER_MAXSONARI2CXL_ENABLED +undef AP_RANGEFINDER_NMEA_ENABLED +undef AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED +undef AP_RANGEFINDER_PWM_ENABLED +undef AP_RANGEFINDER_SIM_ENABLED +undef AP_RANGEFINDER_TRI2C_ENABLED +undef AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED +undef AP_RANGEFINDER_UAVCAN_ENABLED +undef AP_RANGEFINDER_USD1_CAN_ENABLED +undef AP_RANGEFINDER_USD1_SERIAL_ENABLED +undef AP_RANGEFINDER_VL53L0X_ENABLED +undef AP_RANGEFINDER_VL53L1X_ENABLED +undef AP_RANGEFINDER_WASP_ENABLED +undef HAL_PARACHUTE_ENABLED +undef AP_FENCE_ENABLED +undef HAL_PROXIMITY_ENABLED +undef AC_AVOID_ENABLED +undef AC_OAPATHPLANNER_ENABLED +undef AP_OPTICALFLOW_ENABLED +undef AP_OPTICALFLOW_CXOF_ENABLED +undef AP_OPTICALFLOW_HEREFLOW_ENABLED +undef AP_OPTICALFLOW_MAV_ENABLED +undef AP_OPTICALFLOW_ONBOARD_ENABLED +undef AP_OPTICALFLOW_PX4FLOW_ENABLED +undef AP_OPTICALFLOW_PIXART_ENABLED +undef AP_OPTICALFLOW_UPFLOW_ENABLED +undef AP_BARO_BMP085_ENABLED +undef AP_BARO_BMP280_ENABLED +undef AP_BARO_BMP388_ENABLED +undef AP_BARO_DPS280_ENABLED +undef AP_BARO_DUMMY_ENABLED +undef AP_BARO_EXTERNALAHRS_ENABLED +undef AP_BARO_FBM320_ENABLED +undef AP_BARO_ICM20789_ENABLED +undef AP_BARO_KELLERLD_ENABLED +undef AP_BARO_LPS2XH_ENABLED +undef AP_BARO_MS56XX_ENABLED +undef AP_BARO_MSP_ENABLED +undef AP_BARO_SPL06_ENABLED +undef AP_BARO_UAVCAN_ENABLED +undef AP_BARO_ICP101XX_ENABLED +undef AP_BARO_ICP201XX_ENABLED +undef RPM_ENABLED +undef AP_AIRSPEED_ENABLED +undef BEACON_ENABLED +undef GPS_MOVING_BASELINE +undef HAL_CRSF_TELEM_ENABLED +undef HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED +undef HAL_HIGH_LATENCY2_ENABLED +undef HAL_HOTT_TELEM_ENABLED +undef HAL_SPEKTRUM_TELEM_ENABLED +undef AP_LTM_TELEM_ENABLED +undef AP_MOTORS_FRAME_QUAD_ENABLED +undef AP_MOTORS_FRAME_HEXA_ENABLED +undef AP_MOTORS_FRAME_OCTA_ENABLED +undef AP_MOTORS_FRAME_DECA_ENABLED +undef AP_MOTORS_FRAME_DODECAHEXA_ENABLED +undef AP_MOTORS_FRAME_Y6_ENABLED +undef AP_MOTORS_FRAME_OCTAQUAD_ENABLED +undef HAL_SMARTAUDIO_ENABLED +undef AP_TRAMP_ENABLED +undef AP_ICENGINE_TCA9554_STARTER_ENABLED + + +define HAL_NAVEKF3_AVAILABLE 1 +define HAL_NAVEKF2_AVAILABLE 0 +define HAL_EXTERNAL_AHRS_ENABLED 1 +define HAL_INS_TEMPERATURE_CAL_ENABLE 1 +define HAL_VISUALODOM_ENABLED 0 +define EK3_FEATURE_EXTERNAL_NAV 1 +define AP_VOLZ_ENABLED 0 +define AP_ROBOTISSERVO_ENABLED 0 +define AP_FETTEC_ONEWIRE_ENABLED 0 +define AP_AIRSPEED_ANALOG_ENABLED 0 +define AP_AIRSPEED_ASP5033_ENABLED 0 +define AP_AIRSPEED_DLVR_ENABLED 1 +define AP_AIRSPEED_MS4525_ENABLED 0 +define AP_AIRSPEED_MS5525_ENABLED 0 +define AP_AIRSPEED_MSP_ENABLED 0 +define AP_AIRSPEED_NMEA_ENABLED 0 +define AP_AIRSPEED_SDP3X_ENABLED 0 +define AP_AIRSPEED_UAVCAN_ENABLED 1 +define AP_BATTMON_FUELFLOW_ENABLE 1 +define AP_BATTMON_FUELLEVEL_PWM_ENABLE 1 +define AP_BATTMON_FUELLEVEL_ANALOG_ENABLE 1 +define AP_BATTMON_SMBUS_ENABLE 0 +define HAL_BATTMON_INA2XX_ENABLED 0 +define HAL_RUNCAM_ENABLED 0 +define MODE_ZIGZAG_ENABLED 0 +define MODE_SYSTEMID_ENABLED 0 +define MODE_SPORT_ENABLED 0 +define MODE_FOLLOW_ENABLED 0 +define MODE_TURTLE_ENABLED 0 +define MODE_GUIDED_NOGPS_ENABLED 0 +define MODE_FLOWHOLD_ENABLED 0 +define MODE_FLIP_ENABLED 0 +define HAL_PICCOLO_CAN_ENABLE 0 +define HAL_TORQEEDO_ENABLED 0 +define AP_GPS_UBLOX_ENABLED 1 +define AP_GPS_SBP2_ENABLED 0 +define AP_GPS_SBP_ENABLED 0 +define AP_GPS_ERB_ENABLED 0 +define AP_GPS_GSOF_ENABLED 0 +define AP_GPS_NMEA_ENABLED 0 +define AP_GPS_MAV_ENABLED 1 +define AP_GPS_NOVA_ENABLED 0 +define AP_GPS_SBF_ENABLED 0 +define AP_GPS_SIRF_ENABLED 0 +define HAL_MOUNT_ENABLED 1 +define HAL_MOUNT_ALEXMOS_ENABLED 1 +define HAL_MOUNT_GREMSY_ENABLED 1 +define HAL_MOUNT_SERVO_ENABLED 1 +define HAL_MOUNT_SIYI_ENABLED 1 +define HAL_SOLO_GIMBAL_ENABLED 1 +define HAL_MOUNT_STORM32MAVLINK_ENABLED 1 +define HAL_MOUNT_STORM32SERIAL_ENABLED 1 +define AP_ICENGINE_ENABLED 1 +define HAL_EFI_ENABLED 1 +define HAL_EFI_NWPWU_ENABLED 0 +define HAL_GENERATOR_ENABLED 1 +define HAL_ADSB_ENABLED 1 +define HAL_ADSB_SAGETECH_ENABLED 1 +define HAL_ADSB_SAGETECH_MXS_ENABLED 1 +define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED 1 +define HAL_ADSB_UCP_ENABLED 1 +define AP_AIS_ENABLED 0 +define HAL_MSP_ENABLED 0 +define HAL_MSP_SENSORS_ENABLED 0 +define HAL_MSP_GPS_ENABLED 0 +define HAL_MSP_COMPASS_ENABLED 0 +define HAL_MSP_OPTICALFLOW_ENABLED 0 +define HAL_MSP_RANGEFINDER_ENABLED 0 +define HAL_WITH_MSP_DISPLAYPORT 0 +define OSD_ENABLED 0 +define HAL_PLUSCODE_ENABLE 0 +define OSD_PARAM_ENABLED 0 +define HAL_OSD_SIDEBAR_ENABLE 0 +define HAL_WITH_DSP 1 +define HAL_DISPLAY_ENABLED 0 +define HAL_NMEA_OUTPUT_ENABLED 0 +define HAL_BARO_WIND_COMP_ENABLED 0 +define GRIPPER_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 +define LANDING_GEAR_ENABLED 0 +define WINCH_ENABLED 0 +define HAL_QUADPLANE_ENABLED 1 +define HAL_SOARING_ENABLED 0 +define HAL_LANDING_DEEPSTALL_ENABLED 0 +define AP_RANGEFINDER_ENABLED 1 +define AP_RANGEFINDER_ANALOG_ENABLED 0 +define AP_RANGEFINDER_BBB_PRU_ENABLED 0 +define AP_RANGEFINDER_BEBOP_ENABLED 0 +define AP_RANGEFINDER_BENEWAKE_CAN_ENABLED 0 +define AP_RANGEFINDER_BENEWAKE_TF02_ENABLED 0 +define AP_RANGEFINDER_BENEWAKE_TF03_ENABLED 0 +define AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED 0 +define AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED 0 +define AP_RANGEFINDER_BLPING_ENABLED 0 +define AP_RANGEFINDER_GYUS42V2_ENABLED 0 +define AP_RANGEFINDER_HC_SR04_ENABLED 0 +define AP_RANGEFINDER_LANBAO_ENABLED 0 +define AP_RANGEFINDER_LEDDARONE_ENABLED 0 +define AP_RANGEFINDER_LEDDARVU8_ENABLED 0 +define AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED 1 +define AP_RANGEFINDER_LWI2C_ENABLED 0 +define AP_RANGEFINDER_MAVLINK_ENABLED 0 +define AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED 0 +define AP_RANGEFINDER_MAXSONARI2CXL_ENABLED 0 +define AP_RANGEFINDER_NMEA_ENABLED 0 +define AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED 0 +define AP_RANGEFINDER_PWM_ENABLED 0 +define AP_RANGEFINDER_SIM_ENABLED 0 +define AP_RANGEFINDER_TRI2C_ENABLED 0 +define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED 0 +define AP_RANGEFINDER_UAVCAN_ENABLED 1 +define AP_RANGEFINDER_USD1_CAN_ENABLED 0 +define AP_RANGEFINDER_USD1_SERIAL_ENABLED 0 +define AP_RANGEFINDER_VL53L0X_ENABLED 0 +define AP_RANGEFINDER_VL53L1X_ENABLED 0 +define AP_RANGEFINDER_WASP_ENABLED 0 +define HAL_PARACHUTE_ENABLED 1 +define AP_FENCE_ENABLED 1 +define HAL_PROXIMITY_ENABLED 1 +define AC_AVOID_ENABLED 1 +define AC_OAPATHPLANNER_ENABLED 1 +define AP_OPTICALFLOW_ENABLED 0 +define AP_OPTICALFLOW_CXOF_ENABLED 0 +define AP_OPTICALFLOW_HEREFLOW_ENABLED 0 +define AP_OPTICALFLOW_MAV_ENABLED 0 +define AP_OPTICALFLOW_ONBOARD_ENABLED 0 +define AP_OPTICALFLOW_PX4FLOW_ENABLED 0 +define AP_OPTICALFLOW_PIXART_ENABLED 0 +define AP_OPTICALFLOW_UPFLOW_ENABLED 0 +define AP_BARO_BMP085_ENABLED 0 +define AP_BARO_BMP280_ENABLED 0 +define AP_BARO_BMP388_ENABLED 0 +define AP_BARO_DPS280_ENABLED 0 +define AP_BARO_DUMMY_ENABLED 0 +define AP_BARO_EXTERNALAHRS_ENABLED 1 +define AP_BARO_FBM320_ENABLED 0 +define AP_BARO_ICM20789_ENABLED 0 +define AP_BARO_KELLERLD_ENABLED 0 +define AP_BARO_LPS2XH_ENABLED 0 +define AP_BARO_MS56XX_ENABLED 1 +define AP_BARO_MSP_ENABLED 0 +define AP_BARO_SPL06_ENABLED 0 +define AP_BARO_UAVCAN_ENABLED 1 +define AP_BARO_ICP101XX_ENABLED 0 +define AP_BARO_ICP201XX_ENABLED 0 +define RPM_ENABLED 1 +define AP_AIRSPEED_ENABLED 1 +define BEACON_ENABLED 0 +define GPS_MOVING_BASELINE 1 +define HAL_CRSF_TELEM_ENABLED 1 +define HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED 0 +define HAL_HIGH_LATENCY2_ENABLED 1 +define HAL_HOTT_TELEM_ENABLED 0 +define HAL_SPEKTRUM_TELEM_ENABLED 0 +define AP_LTM_TELEM_ENABLED 0 +define AP_MOTORS_FRAME_QUAD_ENABLED 1 +define AP_MOTORS_FRAME_HEXA_ENABLED 0 +define AP_MOTORS_FRAME_OCTA_ENABLED 0 +define AP_MOTORS_FRAME_DECA_ENABLED 0 +define AP_MOTORS_FRAME_DODECAHEXA_ENABLED 0 +define AP_MOTORS_FRAME_Y6_ENABLED 0 +define AP_MOTORS_FRAME_OCTAQUAD_ENABLED 0 +define HAL_SMARTAUDIO_ENABLED 0 +define AP_TRAMP_ENABLED 0 +define AP_ICENGINE_TCA9554_STARTER_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/Cube.param b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/Cube.param new file mode 100644 index 0000000000..8159a75248 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/Cube.param @@ -0,0 +1,4 @@ +#File Details : ./Payload/A7R1/Cube.param, 8136862ae2560ff3efe2e54ff4447b23, CxPilot-5.1.3, 5118f344eb1777a8a4c33cf1b455be42b40dbeae +GPS_DRV_OPTIONS,16 +SERVO14_FUNCTION,-1 +RELAY_PIN,55 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_15(SerialGPS).parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_15(SerialGPS).parm new file mode 100644 index 0000000000..fdb6a0cf30 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_15(SerialGPS).parm @@ -0,0 +1,2 @@ +#File Details : ./Payload/A7R1/cpn_15(SerialGPS).parm, bec0e54ab38a90cbd892f6a0d0b50460, CxPilot-5.1.3, 5118f344eb1777a8a4c33cf1b455be42b40dbeae +GPS_DRV_OPTIONS,16 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_19(DroneCANGPS).parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_19(DroneCANGPS).parm new file mode 100644 index 0000000000..54efef1907 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_19(DroneCANGPS).parm @@ -0,0 +1,2 @@ +#File Details : ./Payload/A7R1/cpn_19(DroneCANGPS).parm, bec0e54ab38a90cbd892f6a0d0b50460, CxPilot-5.1.3, 5118f344eb1777a8a4c33cf1b455be42b40dbeae +GPS_DRV_OPTIONS,16 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_29(DroneCANGPS).parm b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_29(DroneCANGPS).parm new file mode 100644 index 0000000000..4396074a12 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/A7R1/cpn_29(DroneCANGPS).parm @@ -0,0 +1,2 @@ +#File Details : ./Payload/A7R1/cpn_29(DroneCANGPS).parm, bec0e54ab38a90cbd892f6a0d0b50460, CxPilot-5.1.3, 5118f344eb1777a8a4c33cf1b455be42b40dbeae +GPS_DRV_OPTIONS,16 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/CM62/Cube.param b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/CM62/Cube.param new file mode 100644 index 0000000000..9862cf8008 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/CM62/Cube.param @@ -0,0 +1,5 @@ +#File Details : ./Payload/CM62/Cube.param, 3a31ae1ae9aed276a9981fe4a5f81577, CxPilot-5.1.3, 5118f344eb1777a8a4c33cf1b455be42b40dbeae +MNT1_TYPE,6 +MNT1_RC_RATE,90 +MNT1_DEFLT_MODE,3 +SERIAL1_PROTOCOL,2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/Nighthawk/Cube.param b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/Nighthawk/Cube.param new file mode 100644 index 0000000000..f0b44a7ec3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/payloads/Nighthawk/Cube.param @@ -0,0 +1,6 @@ +#File Details : ./Payload/Nighthawk/Cube.param, 5955537d58b87986411fbcff3f946f58, CxPilot-5.1.3, 5118f344eb1777a8a4c33cf1b455be42b40dbeae +SERIAL5_PROTOCOL,2 +SERIAL5_BAUD,115 +SR2_EXTRA1,25 +SR2_EXT_STAT,2 +SR2_POSITION,10 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/scripts/cx_built_in_test.lua b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/scripts/cx_built_in_test.lua new file mode 100644 index 0000000000..1abb8d649a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/scripts/cx_built_in_test.lua @@ -0,0 +1,243 @@ +--[[ + File Name: cx_built_in_test.lua + Description: This script performs a continuous built-in test for various functionalities on Carbonix Aircrafts, focusing on ESC status check and fault detection. + Owner: [Carbonix - Software Team] +]] + +-- ******************* Macros ******************* + +local SCRIPT_NAME = 'CX_BIT' +local SCRIPT_VERSION = 1.0 -- Script Version + + +-------- MAVLINK/AUTOPILOT 'CONSTANTS' -------- +-- MAVLink Severity Levels +local MAV_SEVERITY_CRITICAL = 2 +local MAV_SEVERITY_ERROR = 3 +local MAV_SEVERITY_WARNING = 4 +local MAV_SEVERITY_INFO = 6 + +-- Engine Types +local HIRTH_EFI_TYPE = 8 + +local ESC_WARMUP_TIME = 3000 +local SERVO_OUT_THRESHOLD = 1010 +local ESC_RPM_THRESHOLD = 10 +-- ******************* Variables ******************* + +local number_of_esc = 5 --default value for Volanti + +-- Add a new table to store the warm-up end times for each ESC +local esc_warmup_end_time = {} + +local srv_number = { + [1] = {"Motor1", 33}, + [2] = {"Motor2", 34}, + [3] = {"Motor3", 35}, + [4] = {"Motor4", 36}, + [5] = {"Motor5", 70}, + [6] = {"Motor6", 38}, + [7] = {"Elevator", 19}, + [8] = {"Rudder", 21}, + [9] = {"GPIO", -1}, + [10] = {"Script1", 94}, + [11] = {"Aileron", 4} +} + +local srv_prv_telem_ms = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +local srv_telem_in_err_status = {false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false} +local srv_rpm_in_err_status = {false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false} + +-- ******************* Objects ******************* + +local auth_id = arming:get_aux_auth_id() +assert(auth_id, SCRIPT_NAME .. ": could not get a prearm check auth id") + +local params = { + EFI_TYPE = Parameter() +} + + +-- ******************* Functions ******************* + +-- wrapper for gcs:send_text() +local function gcs_msg(severity, txt) + if type(severity) == 'string' then + -- allow just a string to be passed for simple/routine messages + txt = severity + severity = MAV_SEVERITY_INFO + end + gcs:send_text(severity, string.format('%s: %s', SCRIPT_NAME, txt)) +end + +local function check_aircraft_type() + if params.EFI_TYPE:get() == HIRTH_EFI_TYPE then + number_of_esc = 4 + else + number_of_esc = 5 + end + return true +end + +local function init_param() + for param_name, param in pairs(params) do + if not param:init(param_name) then + return false + end + end + return true +end + +local function arming_check_init() + -- check param fetch + if not init_param() then + arming:set_aux_auth_failed(auth_id, "Parameter Init Failed") + gcs_msg(MAV_SEVERITY_WARNING, "Parameter Init Failed") + return false + end + -- check aircraft Type + if not check_aircraft_type() then + arming:set_aux_auth_failed(auth_id, "Aircraft Type Check Failed") + gcs_msg(MAV_SEVERITY_WARNING, "Aircraft Type Check Failed") + return false + end + gcs_msg(MAV_SEVERITY_INFO, "Script Version " .. SCRIPT_VERSION .. " Initialized") + arming:set_aux_auth_passed(auth_id) + return true +end + +-- Call this function whenever a motor starts running +local function esc_is_started(i) + -- Set the warm-up end time for this ESC to 3 seconds from now + esc_warmup_end_time[i] = millis() + ESC_WARMUP_TIME +end + +-- Call this function whenever a motor stops running +local function esc_is_stopped(i) + -- Clear the warm-up end time for this ESC + esc_warmup_end_time[i] = nil +end + +-- Counters to debounce nil checks on esc rpm and servo output, this is a +-- workaround to avoid giving the pilot a critical warning for an unexplained +-- one-loop dropout we saw recently +local NIL_WARN_THRESHOLD = 3 +local esc_rpm_nil_counter = {0, 0, 0, 0, 0} +local servo_out_nil_counter = {0, 0, 0, 0, 0} + +local function esc_check_loop() + for i = 1, number_of_esc do + local esc_last_telem_data_ms = esc_telem:get_last_telem_data_ms(i-1):toint() + local esc_rpm = esc_telem:get_rpm(i-1) + local servo_out = SRV_Channels:get_output_pwm(srv_number[i][2]) + -- Telem data timestamp check + if not esc_last_telem_data_ms or esc_last_telem_data_ms == 0 or esc_last_telem_data_ms == srv_prv_telem_ms[i] then + if srv_telem_in_err_status[i] == false then + gcs_msg(MAV_SEVERITY_CRITICAL, "ESC " .. i .. " Telemetry Lost") + srv_telem_in_err_status[i] = true + end + -- Nil check for RPM reading + elseif not esc_rpm then + esc_rpm_nil_counter[i] = esc_rpm_nil_counter[i] + 1 + if esc_rpm_nil_counter[i] < NIL_WARN_THRESHOLD then + gcs_msg(MAV_SEVERITY_INFO, "ESC " .. i .. " RPM nil") + elseif srv_rpm_in_err_status[i] == false then + gcs_msg(MAV_SEVERITY_CRITICAL, "ESC " .. i .. " RPM nil") + srv_telem_in_err_status[i] = true + end + -- Nil check for servo output + elseif not servo_out then + servo_out_nil_counter[i] = servo_out_nil_counter[i] + 1 + if servo_out_nil_counter[i] < NIL_WARN_THRESHOLD then + gcs_msg(MAV_SEVERITY_INFO, "ESC " .. i .. " Servo Out nil") + elseif srv_rpm_in_err_status[i] == false then + gcs_msg(MAV_SEVERITY_CRITICAL, "ESC " .. i .. " Servo Out nil") + srv_telem_in_err_status[i] = true + end + -- Telemetry data is fresh and valid + else + if srv_telem_in_err_status[i] == true then + gcs_msg(MAV_SEVERITY_INFO, "ESC " .. i .. " Telemetry Recovered") + srv_telem_in_err_status[i] = false + servo_out_nil_counter[i] = 0 + esc_rpm_nil_counter[i] = 0 + end + -- If armed, check that the motor is actually turning when it is commanded to + if arming:is_armed() then + -- If the PWM is below the threshold, it is okay for the motor to be stopped + if servo_out < SERVO_OUT_THRESHOLD then + esc_is_stopped(i) + -- If the PWM has just gone above the threshold, start the warm-up timer + elseif servo_out > SERVO_OUT_THRESHOLD and not esc_warmup_end_time[i] then + esc_is_started(i) + -- If the motor is running, and the warmup timer has expired, check that the motor is spinning + elseif esc_warmup_end_time[i] and millis() > esc_warmup_end_time[i] then + if servo_out > SERVO_OUT_THRESHOLD and esc_rpm < ESC_RPM_THRESHOLD then + if srv_rpm_in_err_status[i] == false then + gcs_msg(MAV_SEVERITY_CRITICAL, "ESC " .. i .. " RPM Drop") + srv_rpm_in_err_status[i] = true + end + else + if srv_rpm_in_err_status[i] == true then + gcs_msg(MAV_SEVERITY_INFO, "ESC " .. i .. " RPM Recovered") + srv_rpm_in_err_status[i] = false + end + end + end + end + end + -- Update srv_prv_telem_ms[i] if it had valid data this loop + if esc_last_telem_data_ms and esc_last_telem_data_ms ~= 0 then + srv_prv_telem_ms[i] = esc_last_telem_data_ms + end + end +end + +local function arming_checks() + -- check for status in srv_telem_in_err_status and also CX_SERVO_ERROR bit status + local pre_arm_status = false-- check for status in srv_telem_in_err_status and also CX_SERVO_ERROR bit status + arming:set_aux_auth_passed(auth_id) + + for i, status in ipairs(srv_telem_in_err_status) do + if status == true then + arming:set_aux_auth_failed(auth_id, "Actuator ".. i .. " Telemetry Error") + return false + end + end + if pre_arm_status == false then + arming:set_aux_auth_passed(auth_id) + end + +end + +local function update() + esc_check_loop() + arming_checks() +end + +-- wrapper around update(). This calls update() and if update faults +-- then an error is displayed, but the script is not stopped +local function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs_msg(MAV_SEVERITY_ERROR, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + return protected_wrapper, 1000 + end + return protected_wrapper, 200 +end + +local function script_exit() + -- pre arm failure SCRIPT_NAME not Running + arming:set_aux_auth_failed(auth_id, SCRIPT_NAME .. " Not Running") + gcs_msg(MAV_SEVERITY_CRITICAL, "LUA SCRIPT EXIT ... Need Reboot to Reinitialize") +end + + +-- ******************* Main ******************* +if arming_check_init() then + return protected_wrapper, 10000 +end + +script_exit() diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/scripts/cx_led_driver.lua b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/scripts/cx_led_driver.lua new file mode 100644 index 0000000000..7af9391232 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixCommon/scripts/cx_led_driver.lua @@ -0,0 +1,49 @@ + +-- LED is switched on using motor function +local MOTOR_LED_FUNCTION = 94 + +-- Ensure that the out2_function min = 200 and max = 10000 +local MOTOR_LED_PWM_VAL_TRIM = 5000 +local MOTOR_LED_PWM_VAL_MIN = 200 +local MOTOR_LED_PWM_VAL_MAX = 10000 +local MOTOR_LED_PWM_VAL_OFF = 0 + +-- Arming check interval +local LED_CYCLE_TIME = 2000 + + +local LED_servo = SRV_Channels:find_channel(MOTOR_LED_FUNCTION) + + +gcs:send_text(0, "LED -- BEGIN") + + +-- LED is switched ON using a PWM signal configured as MOTOR_LED_FUNCTION +-- This is done to overcome the design limitations on CPN +local function switch_LED(LED_val) + + if (LED_servo ~= null) then + SRV_Channels:set_output_pwm_chan_timeout(LED_servo, LED_val, LED_CYCLE_TIME) + end + + return check_arming, LED_CYCLE_TIME +end + + + +-- Function to continuously check if the vehicle is armed or not +-- ARMED -> LED_ON +-- DISARMED -> LED_OFF +local function check_arming() + vehicle_armed = arming:is_armed() + + if vehicle_armed == true then + switch_LED(MOTOR_LED_PWM_VAL_MAX) + else + switch_LED(MOTOR_LED_PWM_VAL_MIN) + end + + return check_arming, LED_CYCLE_TIME +end + +return check_arming(), 10000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405-no-crystal/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405-no-crystal/hwdef-bl.dat new file mode 100644 index 0000000000..aad40c5703 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405-no-crystal/hwdef-bl.dat @@ -0,0 +1,7 @@ +include ../CarbonixF405/hwdef-bl.dat + +undef OSCILLATOR_HZ +OSCILLATOR_HZ 0 + +undef CAN_APP_NODE_NAME +define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405-no-crystal" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405-no-crystal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405-no-crystal/hwdef.dat new file mode 100644 index 0000000000..fca76cfa1e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405-no-crystal/hwdef.dat @@ -0,0 +1,7 @@ +include ../CarbonixF405/hwdef.dat + +undef OSCILLATOR_HZ +OSCILLATOR_HZ 0 + +undef CAN_APP_NODE_NAME +define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405-no-crystal" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat index ef2963d19d..9c713c3b26 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat @@ -15,8 +15,8 @@ APJ_BOARD_ID 1064 # setup build for a peripheral firmware env AP_PERIPH 1 -# crystal frequency set to 0 to use internal clock -OSCILLATOR_HZ 0 +# crystal frequency set to 0 to use internal clock; currently configured for external crystal 12MHZ +OSCILLATOR_HZ 12000000 # assume 1024K flash part FLASH_SIZE_KB 1024 @@ -69,3 +69,5 @@ define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 + +define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat index 6bfaadd6db..c2fbe6d555 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat @@ -16,8 +16,8 @@ APJ_BOARD_ID 1064 # setup build for a peripheral firmware env AP_PERIPH 1 -# crystal frequency set to 0 to use internal clock -OSCILLATOR_HZ 0 +# crystal frequency set to 0 to use internal clock; currently configured for external crystal 12MHZ +OSCILLATOR_HZ 12000000 #MCU F405 Flash 1024 FLASH_SIZE_KB 1024 @@ -27,10 +27,6 @@ SERIAL_ORDER OTG1 USART2 USART3 UART4 define HAL_CAN_POOL_SIZE 6000 -#STDOUT_SERIAL SD1 -#STDOUT_BAUDRATE 57600 - - # PWM outputs PA9 TIM1_CH2 TIM1 PWM(1) GPIO(50) PA8 TIM1_CH1 TIM1 PWM(2) GPIO(51) @@ -115,31 +111,37 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 -define HAL_PERIPH_ENABLE_MAG -define HAL_PERIPH_ENABLE_BARO -define HAL_PERIPH_ENABLE_RC_OUT - # enable ESC control +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ARM_MONITORING_ENABLE define HAL_SUPPORT_RCOUT_SERIAL 1 define HAL_WITH_ESC_TELEM 1 +define NUM_SERVO_CHANNELS 2 # enable GPS define HAL_PERIPH_ENABLE_GPS -define HAL_PERIPH_GPS_PORT_DEFAULT 2 -#define HAL_PERIPH_ENABLE_NOTIFY -#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY - -# default ADSB off by setting 0 baudrate -define HAL_PERIPH_ENABLE_ADSB -define HAL_PERIPH_ADSB_PORT_DEFAULT 3 -define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600 - -BARO MS56XX I2C:0:0x76 -COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE +define HAL_PERIPH_GPS_PORT_DEFAULT -1 +define HAL_PERIPH_ENABLE_NOTIFY +# enable Compass +define HAL_PERIPH_ENABLE_MAG +define AP_COMPASS_ENABLE_DEFAULT 0 define AP_COMPASS_QMC5883P_ENABLED 1 COMPASS QMC5883P I2C:0:0x2C false ROTATION_YAW_180 +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_NONE +# enable ADSB +define HAL_PERIPH_ENABLE_ADSB +define HAL_PERIPH_ADSB_PORT_DEFAULT -1 +define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600 +# enable baro +define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLE_DEFAULT 0 +BARO MS56XX I2C:0:0x76 +# enable rangefinder +define HAL_PERIPH_ENABLE_RANGEFINDER 1 +define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat deleted file mode 100644 index 7c8895bd3f..0000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat +++ /dev/null @@ -1,72 +0,0 @@ -# hw definition file for processing by chibios_pins.py - -# MCU class and specific type -MCU STM32L496 STM32L496xx - -FLASH_RESERVE_START_KB 0 -FLASH_BOOTLOADER_LOAD_KB 36 - -# reserve some space for params -APP_START_OFFSET_KB 4 - -# board ID for firmware load -APJ_BOARD_ID 1053 - -# setup build for a peripheral firmware -env AP_PERIPH 1 - -# crystal frequency -OSCILLATOR_HZ 12000000 - -# assume 256k flash part -FLASH_SIZE_KB 256 - -STDOUT_SERIAL SD2 -STDOUT_BAUDRATE 57600 - -# order of UARTs -SERIAL_ORDER OTG1 USART2 - -# a fault LED -PA13 LED_BOOTLOADER OUTPUT HIGH # blue -define HAL_LED_ON 0 - -# USART1 -PA2 USART2_TX USART2 SPEED_HIGH NODMA -PA3 USART2_RX USART2 SPEED_HIGH NODMA - -# USB -PA11 OTG_FS_DM OTG1 -PA12 OTG_FS_DP OTG1 - -define HAL_USE_SERIAL TRUE - -define STM32_SERIAL_USE_USART2 TRUE - -define HAL_NO_GPIO_IRQ - -define SERIAL_BUFFERS_SIZE 32 -define HAL_USE_EMPTY_IO TRUE -define PORT_INT_REQUIRED_STACK 64 - -define DMA_RESERVE_SIZE 0 - -MAIN_STACK 0x800 -PROCESS_STACK 0x800 - -define HAL_DISABLE_LOOP_DELAY - -# enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 - -# debugger support, disabled as PA13 used for LED -# PA13 JTMS-SWDIO SWD -# PA14 JTCK-SWCLK SWD - -# make bl baudrate match debug baudrate for easier debugging -define BOOTLOADER_BAUDRATE 57600 - -# use a small bootloader timeout -define HAL_BOOTLOADER_TIMEOUT 1000 - diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat deleted file mode 100644 index 807e790e30..0000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat +++ /dev/null @@ -1,143 +0,0 @@ -# hw definition file for processing by chibios_pins.py - -# MCU class and specific type -MCU STM32L496 STM32L496xx - -# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) -FLASH_RESERVE_START_KB 40 - -# store parameters in pages 18 and 19 -STORAGE_FLASH_PAGE 18 -define HAL_STORAGE_SIZE 800 - -# board ID for firmware load -APJ_BOARD_ID 1053 - -# setup build for a peripheral firmware -env AP_PERIPH 1 - -# enable watchdog - -# crystal frequency -OSCILLATOR_HZ 12000000 - -# assume the 256k flash part -FLASH_SIZE_KB 256 - -# order of UARTs -SERIAL_ORDER OTG1 USART2 USART3 UART4 - -define HAL_CAN_POOL_SIZE 6000 - -#STDOUT_SERIAL SD1 -#STDOUT_BAUDRATE 57600 - - -# PWM outputs -PA9 TIM1_CH2 TIM1 PWM(1) GPIO(50) -PA8 TIM1_CH1 TIM1 PWM(2) GPIO(51) -PC6 TIM3_CH1 TIM3 PWM(3) GPIO(52) # LED - -# USART2, ESC telem -PA2 USART2_TX USART2 SPEED_HIGH NODMA -PA3 USART2_RX USART2 SPEED_HIGH NODMA - -# USART3 -PC4 USART3_TX USART3 SPEED_HIGH NODMA -PC5 USART3_RX USART3 SPEED_HIGH NODMA - -# UART4 -PA0 UART4_TX UART4 SPEED_HIGH NODMA -PA1 UART4_RX UART4 SPEED_HIGH NODMA - -# USB -PA11 OTG_FS_DM OTG1 -PA12 OTG_FS_DP OTG1 - -# LED, active low -PA13 LED OUTPUT HIGH GPIO(1) - -# spi2 -PB10 SPI2_SCK SPI2 -PB14 SPI2_MISO SPI2 -PB15 SPI2_MOSI SPI2 - -# CS pins -PC8 BMI088_A_CS CS -PC9 BMI088_G_CS CS - -SPIDEV bmi088_g SPI2 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ -SPIDEV bmi088_a SPI2 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ - -# one I2C bus -PB6 I2C4_SCL I2C4 -PB7 I2C4_SDA I2C4 - -I2C_ORDER I2C4 - -# allow for reboot command for faster development -define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 - -# debugger support (disabled as conflicts with LED) -#PA13 JTMS-SWDIO SWD -#PA14 JTCK-SWCLK SWD - -define HAL_NO_GPIO_IRQ -define SERIAL_BUFFERS_SIZE 512 - -define DMA_RESERVE_SIZE 2048 - -# stack for fast interrupts -define PORT_INT_REQUIRED_STACK 64 - -# MAIN_STACK is stack for ISR handlers -MAIN_STACK 0x300 - -# PROCESS_STACK controls stack for main thread -PROCESS_STACK 0xA00 - -define HAL_DISABLE_LOOP_DELAY - -# enable CAN support -PB8 CAN1_RX CAN1 -PB9 CAN1_TX CAN1 - -# ADC inputs -define HAL_USE_ADC TRUE -define STM32_ADC_USE_ADC1 TRUE - -PA4 VSENSE1 ADC1 SCALE(1) -PA5 VSENSE2 ADC1 SCALE(1) -PA6 VSENSE3 ADC1 SCALE(1) -PB1 VSENSE4 ADC1 SCALE(1) - -define AP_STATS_ENABLED 1 - -define HAL_NO_GCS -define HAL_NO_MONITOR_THREAD - -define AP_PARAM_MAX_EMBEDDED_PARAM 512 - -define HAL_PERIPH_ENABLE_MAG -define HAL_PERIPH_ENABLE_BARO -define HAL_PERIPH_ENABLE_RC_OUT - -# enable ESC control -define HAL_SUPPORT_RCOUT_SERIAL 1 -define HAL_WITH_ESC_TELEM 1 - -# enable GPS -define HAL_PERIPH_ENABLE_GPS -define HAL_PERIPH_GPS_PORT_DEFAULT 2 -#define HAL_PERIPH_ENABLE_NOTIFY -#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY - -# default ADSB off by setting 0 baudrate -define HAL_PERIPH_ENABLE_ADSB -define HAL_PERIPH_ADSB_PORT_DEFAULT 3 -define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600 - -BARO MS56XX I2C:0:0x76 -COMPASS QMC5883P I2C:0:0x2C false ROTATION_YAW_180 - -define AP_COMPASS_QMC5883P_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm new file mode 100644 index 0000000000..d2cd1a60ce --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/defaults.parm @@ -0,0 +1,227 @@ +@include ../CarbonixCommon/defaults.parm +# Ottano-specific parameters +ARSPD_FBW_MAX,36 +ARSPD_FBW_MIN,23 +BATT_ARM_MAH,10000 +BATT_ARM_VOLT,24 +BATT_CAPACITY,30600 +BATT_CRT_MAH,7000 +BATT_CRT_VOLT,21 +BATT_FS_CRT_ACT,4 +BATT_FS_LOW_ACT,1 +BATT_FS_VOLTSRC,1 +BATT_LOW_MAH,10000 +BATT_LOW_VOLT,23 +BATT_MONITOR,10 +BATT_OPTIONS,64 +BATT_SUM_MASK,6 +BATT2_AMP_OFFSET,0.002314 +BATT2_AMP_PERVLT,29.86658 +BATT2_CAPACITY,0 +BATT2_CURR_PIN,51 +BATT2_MONITOR,28 +BATT2_VOLT_MULT,16.66666 +BATT2_VOLT_PIN,50 +BATT3_AMP_OFFSET,0.005901 +BATT3_AMP_PERVLT,30.09855 +BATT3_CAPACITY,0 +BATT3_CURR_PIN,52 +BATT3_MONITOR,28 +BATT3_VOLT_MULT,16.66666 +BATT3_VOLT_PIN,50 +BATT4_CAPACITY,0 +BATT4_MONITOR,9 +BATT5_MONITOR,8 +BATT6_MONITOR,8 +BRD_SAFETY_MASK,2032 +CAN_D1_UC_ESC_BM,9 +CAN_D1_UC_SRV_BM,1600 +CAN_D2_UC_ESC_BM,6 +CAN_D2_UC_SRV_BM,1600 +COMPASS_PRIO1_ID,70411 +COMPASS_PRIO2_ID,72963 +COMPASS_USE3,0 +EFI_COEF1,0.68 +EFI_FUEL_DENS,0.8364842 +EFI_THRLIN_COEF1,0.8364842 +EFI_THRLIN_COEF2,-0.02207897 +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 +GPS_POS2_Y,1.05 +ICE_ENABLE,1 +ICE_IDLE_RPM,2400 +ICE_IDLE_SLEW,2 +ICE_IGNITION_RLY,2 +ICE_OPTIONS,4 +ICE_RPM_CHAN,1 +ICE_START_CHAN,6 +ICE_START_DELAY,3 +ICE_STARTCHN_MIN,950 +ICE_STARTER_TIME,5 +INS_ACCEL_FILTER,10 +INS_GYRO_FILTER,22 +INS_HNTC2_ATT,60 +INS_HNTC2_BW,12 +INS_HNTC2_ENABLE,1 +INS_HNTC2_FREQ,35 +INS_HNTC2_MODE,2 +INS_HNTC2_OPTS,1 +INS_HNTC2_REF,1 +INS_HNTCH_ATT,60 +INS_HNTCH_BW,15 +INS_HNTCH_ENABLE,1 +INS_HNTCH_FREQ,60 +INS_HNTCH_HMNCS,3 +INS_HNTCH_MODE,3 +INS_HNTCH_OPTS,3 +INS_HNTCH_REF,1 +INS_LOG_BAT_MASK,5 +INS_POS1_X,0.82 +INS_POS2_X,0.82 +INS_POS3_X,0.82 +KFF_RDDRMIX,1 +LIM_ROLL_CD,3500 # Set to match NAVL1_LIM_BANK +NAVL1_LIM_BANK,35 # Set to match LIM_ROLL_CD +NAVL1_PERIOD,18 +PTCH_RATE_D,0.007605 +PTCH_RATE_FF,0.7402687 +PTCH_RATE_FLTD,11 +PTCH_RATE_FLTT,3.183099 +PTCH_RATE_I,0.7402687 +PTCH_RATE_IMAX,0.4 +PTCH_RATE_P,0.2194594 +PTCH_RATE_SMAX,110 +PTCH2SRV_RLL,1.05 +PTCH2SRV_RMAX_DN,45 +PTCH2SRV_RMAX_UP,75 +Q_A_ACCEL_P_MAX,8800 +Q_A_ACCEL_R_MAX,13000 +Q_A_ACCEL_Y_MAX,4000 +Q_A_ANG_YAW_P,2 +Q_A_RAT_PIT_D,0.015 +Q_A_RAT_PIT_FLTD,11 +Q_A_RAT_PIT_FLTE,8 +Q_A_RAT_PIT_FLTT,11 +Q_A_RAT_PIT_I,0.18 +Q_A_RAT_PIT_IMAX,0.4 +Q_A_RAT_PIT_P,0.18 +Q_A_RAT_PIT_SMAX,15 +Q_A_RAT_RLL_D,0.006 +Q_A_RAT_RLL_FLTD,11 +Q_A_RAT_RLL_FLTE,8 +Q_A_RAT_RLL_FLTT,11 +Q_A_RAT_RLL_I,0.3 +Q_A_RAT_RLL_P,0.3 +Q_A_RAT_RLL_SMAX,15 +Q_A_RAT_YAW_D,0.002 +Q_A_RAT_YAW_FLTD,11 +Q_A_RAT_YAW_FLTE,2 +Q_A_RAT_YAW_FLTT,11 +Q_A_RAT_YAW_I,0.25 +Q_A_RAT_YAW_IMAX,0.45 +Q_A_RAT_YAW_P,2.5 +Q_A_RAT_YAW_SMAX,10 +Q_A_RATE_P_MAX,45 +Q_A_RATE_R_MAX,55 +Q_A_RATE_Y_MAX,12 +Q_A_SLEW_YAW,1500 +Q_ACCEL_Z,100 +Q_ANGLE_MAX,1500 +Q_ASSIST_SPEED,18 +Q_FRAME_CLASS,1 +Q_FRAME_TYPE,1 +Q_LOIT_ACC_MAX,100 +Q_LOIT_ANG_MAX,10 +Q_LOIT_BRK_ACCEL,25 +Q_LOIT_BRK_JERK,175 +Q_LOIT_SPEED,300 +Q_M_BAT_VOLT_MAX,50.4 +Q_M_BAT_VOLT_MIN,39.6 +Q_M_SPIN_ARM,0.07 +Q_M_SPIN_MIN,0.1 +Q_M_THST_EXPO,0.582 +Q_M_THST_HOVER,0.3868718 +Q_M_YAW_HEADROOM,100 +Q_OPTIONS,147553 +Q_P_ACCZ_D,0.015 +Q_P_ACCZ_FLTD,6 +Q_P_ACCZ_FLTE,3 +Q_P_ACCZ_FLTT,6 +Q_P_ACCZ_I,0.82 +Q_P_ACCZ_P,0.41 +Q_P_ANGLE_MAX,10 +Q_P_JERK_XY,1.25 +Q_P_POSXY_P,0.85 +Q_P_POSZ_P,1.28 +Q_P_VELXY_D,0.2 +Q_P_VELXY_I,0.4 +Q_P_VELXY_P,0.65 +Q_P_VELZ_FLTD,7 +Q_P_VELZ_FLTE,4 +Q_P_VELZ_I,0.78 +Q_P_VELZ_IMAX,4 +Q_P_VELZ_P,4 +Q_PLT_Y_RATE,25 +Q_TRANS_DECEL,0.9 +Q_VFWD_GAIN,0.1 +Q_WP_ACCEL_Z,30 +Q_WP_JERK,0.7 +Q_WP_SPEED_DN,200 +Q_WP_SPEED_UP,220 +Q_WVANE_GAIN,1 +RELAY_PIN2,108 +RLL_RATE_D,0.001917198 +RLL_RATE_FF,0.7728607 +RLL_RATE_FLTD,11 +RLL_RATE_FLTT,3.183099 +RLL_RATE_I,0.7728607 +RLL_RATE_IMAX,0.4 +RLL_RATE_P,0.09429314 +RLL_RATE_SMAX,125 +RLL2SRV_RMAX,75 +RNGFND1_GNDCLEAR,27 +RNGFND1_POS_X,0.93 +RNGFND1_TYPE,24 +RPM1_TYPE,3 +SCALING_SPEED,24 +SERIAL1_BAUD,57 +SERIAL1_PROTOCOL,24 +SERIAL2_BAUD,115 +SERIAL3_BAUD,115 +SERIAL3_PROTOCOL,23 +SERIAL4_BAUD,57 +SERIAL4_PROTOCOL,2 +SERIAL5_PROTOCOL,28 +SERIAL6_BAUD,115 +SERIAL6_PROTOCOL,2 +SERVO5_MAX,1950 +SERVO5_MIN,980 +TECS_CLMB_MAX,4 +TECS_INTEG_GAIN,0.15 +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_TIME_CONST,4 +TECS_VERT_ACC,6 +THR_SLEWRATE,50 +TRIM_ARSPD_CM,2600 +TRIM_PITCH_CD,300 +TRIM_THROTTLE,60 +WP_LOITER_RAD,250 +WP_RADIUS,150 +YAW2SRV_DAMP,0.6 +YAW2SRV_IMAX,1000 +YAW2SRV_INT,1 +YAW2SRV_SLIP,3.5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/hwdef.dat new file mode 100644 index 0000000000..dcc2ae1b6c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/hwdef.dat @@ -0,0 +1 @@ +include ../CarbonixCommon/cubeorange.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/scripts/cx_built_in_test.lua b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/scripts/cx_built_in_test.lua new file mode 120000 index 0000000000..dbb50da048 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/scripts/cx_built_in_test.lua @@ -0,0 +1 @@ +../../CarbonixCommon/scripts/cx_built_in_test.lua \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/scripts/cx_led_driver.lua b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/scripts/cx_led_driver.lua new file mode 120000 index 0000000000..71087fb1e4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Ottano/scripts/cx_led_driver.lua @@ -0,0 +1 @@ +../../CarbonixCommon/scripts/cx_led_driver.lua \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm new file mode 100644 index 0000000000..f8ee18544c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/defaults.parm @@ -0,0 +1,188 @@ +@include ../CarbonixCommon/defaults.parm +# Volanti-specific parameters +ARSPD_FBW_MIN,20 # 20m/s is the minimum airspeed demanded in automatic throttle modes. Should be 20% above stall speed which is 16.5m/s at 16kg MTOW. +BRD_SAFETYENABLE,1 # On boot the Safety state is ON "SAFE". +COMPASS_PRIO1_ID,70403 # Compass from Drone CAN GPS 19 on CAN BUS 1 mounted left. +COMPASS_PRIO2_ID,72963 # Compass from Drone CAN GPS 29 on CAN BUS 1 mounted right. +# FFT_ENABLE,0 # Disable FFT as on lower Frequency it could create a major slew rate which could cause a crash. (Recommended by Tridge). +ARSPD_FBW_MAX,28 +BATT_CAPACITY,22000 +BATT_CRT_VOLT,44.4 +BATT_FS_LOW_ACT,1 +BATT_FS_VOLTSRC,1 +BATT_LOW_TIMER,3 +BATT_LOW_VOLT,44.8 +BATT_MONITOR,10 +BATT_OPTIONS,64 +BATT_SUM_MASK,6 +BATT2_AMP_OFFSET,0.002314 +BATT2_AMP_PERVLT,29.86658 +BATT2_CAPACITY,0 +BATT2_CURR_PIN,51 +BATT2_MONITOR,28 +BATT2_VOLT_MULT,16.66666 +BATT2_VOLT_PIN,50 +BATT3_AMP_OFFSET,0.005901 +BATT3_AMP_PERVLT,30.09855 +BATT3_CAPACITY,0 +BATT3_CURR_PIN,52 +BATT3_MONITOR,28 +BATT3_VOLT_MULT,16.66666 +BATT3_VOLT_PIN,50 +BATT4_CAPACITY,0 +BATT4_MONITOR,9 +BRD_SAFETY_MASK,16352 +CAN_D1_UC_ESC_BM,19 +CAN_D1_UC_SRV_BM,1824 +CAN_D2_UC_ESC_BM,12 +CAN_D2_UC_SRV_BM,1824 +COMPASS_USE3,0 +FWD_BAT_VOLT_MAX,50.4 +FWD_BAT_VOLT_MIN,42 +GPS_POS1_X,-0.12 +GPS_POS1_Y,-0.17 +GPS_POS1_Z,-0.06 +GPS_POS2_X,-0.12 +GPS_POS2_Y,0.17 +GPS_POS2_Z,-0.06 +INS_ACCEL_FILTER,6 +INS_FAST_SAMPLE,3 +INS_HNTCH_ATT,50 +INS_HNTCH_BW,60 +INS_HNTCH_ENABLE,1 +INS_HNTCH_FREQ,95 +INS_HNTCH_MODE,3 +INS_HNTCH_OPTS,3 +INS_HNTCH_REF,1 +INS_LOG_BAT_CNT,512 +INS_LOG_BAT_MASK,5 +INS_LOG_BAT_OPT,4 +INS_POS1_X,-0.21 +INS_POS1_Z,-0.03 +INS_POS2_X,-0.21 +INS_POS2_Z,-0.03 +INS_POS3_X,-0.21 +INS_POS3_Z,-0.03 +KFF_RDDRMIX,0.9 +LIM_ROLL_CD,4000 # Set to match NAVL1_LIM_BANK +NAVL1_LIM_BANK,40 # Set to match LIM_ROLL_CD +NAVL1_PERIOD,19 +PTCH_RATE_D,0.0029344 +PTCH_RATE_FF,0.36 +PTCH_RATE_FLTD,10 +PTCH_RATE_FLTT,3.183099 +PTCH_RATE_I,0.4009161 +PTCH_RATE_IMAX,0.4 +PTCH_RATE_P,0.09 +PTCH_RATE_SMAX,125 +PTCH2SRV_RLL,0.9 +PTCH2SRV_RMAX_DN,45 +PTCH2SRV_RMAX_UP,75 +Q_A_ACCEL_P_MAX,30000 +Q_A_ACCEL_R_MAX,30000 +Q_A_ACCEL_Y_MAX,4500 +Q_A_ANG_PIT_P,1.2 +Q_A_ANG_RLL_P,2 +Q_A_ANG_YAW_P,2.4 +Q_A_RAT_PIT_D,0.01 +Q_A_RAT_PIT_FLTE,7 +Q_A_RAT_PIT_FLTT,10 +Q_A_RAT_PIT_I,0.25 +Q_A_RAT_PIT_SMAX,10 +Q_A_RAT_RLL_D,0.007 +Q_A_RAT_RLL_FLTE,7 +Q_A_RAT_RLL_FLTT,10 +Q_A_RAT_RLL_I,0.34 +Q_A_RAT_RLL_P,0.3 +Q_A_RAT_RLL_SMAX,10 +Q_A_RAT_YAW_D,0.026 +Q_A_RAT_YAW_FLTE,2 +Q_A_RAT_YAW_FLTT,10 +Q_A_RAT_YAW_I,0.2 +Q_A_RAT_YAW_P,2 +Q_A_RAT_YAW_SMAX,10 +Q_A_RATE_P_MAX,60 +Q_A_RATE_R_MAX,60 +Q_A_RATE_Y_MAX,12 +Q_A_SLEW_YAW,1500 +Q_ACCEL_Z,200 +Q_ANGLE_MAX,1500 +Q_ASSIST_SPEED,18 +Q_FRAME_CLASS,1 +Q_FRAME_TYPE,1 +Q_LOIT_ACC_MAX,110 +Q_LOIT_ANG_MAX,10 +Q_LOIT_BRK_ACCEL,40 +Q_LOIT_BRK_DELAY,0.25 +Q_LOIT_BRK_JERK,130 +Q_LOIT_SPEED,300 +Q_M_BAT_VOLT_MAX,50.4 +Q_M_BAT_VOLT_MIN,39.6 +Q_M_SLEW_UP_TIME,0.05 +Q_M_SPIN_ARM,0.07 +Q_M_SPIN_MIN,0.1 +Q_M_THST_EXPO,0.52 +Q_M_THST_HOVER,0.4299014 +Q_M_YAW_HEADROOM,50 +Q_OPTIONS,147489 +Q_P_ACCZ_D,0.01 +Q_P_ACCZ_FLTD,8 +Q_P_ACCZ_FLTE,3 +Q_P_ACCZ_FLTT,8 +Q_P_ACCZ_I,0.76 +Q_P_ACCZ_P,0.38 +Q_P_ANGLE_MAX,10 +Q_P_JERK_XY,2.5 +Q_P_JERK_Z,6 +Q_P_POSXY_P,1.3 +Q_P_POSZ_P,1.3 +Q_P_VELXY_D,0.1 +Q_P_VELXY_FLTD,8 +Q_P_VELXY_I,0.5 +Q_P_VELXY_P,1 +Q_P_VELZ_FLTD,7 +Q_P_VELZ_I,0.8 +Q_P_VELZ_IMAX,4 +Q_P_VELZ_P,4.5 +Q_PLT_Y_RATE,12 +Q_TRANS_DECEL,0.8 +Q_VFWD_GAIN,0.05 +Q_WP_JERK,0.7 +Q_WP_SPEED_DN,120 +Q_WVANE_GAIN,3 +RLL_RATE_D,0.012262 +RLL_RATE_FF,0.27 +RLL_RATE_FLTD,10 +RLL_RATE_FLTT,3.183099 +RLL_RATE_I,0.3120202 +RLL_RATE_IMAX,0.4 +RLL_RATE_P,0.26 +RLL_RATE_SMAX,125 +RLL2SRV_RMAX,75 +RNGFND1_GNDCLEAR,20 +RNGFND1_POS_X,-0.12 +RNGFND1_POS_Z,0.05 +RNGFND1_TYPE,24 +SCALING_SPEED,21 +SERIAL2_BAUD,115 +SERIAL5_BAUD,115 +SERIAL5_PROTOCOL,2 +SERIAL6_BAUD,115 +SERIAL6_PROTOCOL,2 +TECS_CLMB_MAX,3.1 +TECS_PITCH_MAX,10 +TECS_PITCH_MIN,-10 +TECS_PTCH_DAMP,0.5 +TECS_PTCH_FF_V0,19 +TECS_RLL2THR,14 +TECS_SINK_MAX,4 +TECS_TIME_CONST,3 +TRIM_ARSPD_CM,2100 +TRIM_PITCH_CD,200 +TRIM_THROTTLE,60 # 60% Throttle is the target percentage in auto flight to maintain TRIM_ARSPD_CM. +WP_LOITER_RAD,250 +WP_RADIUS,75 +YAW2SRV_DAMP,1 +YAW2SRV_IMAX,1000 +YAW2SRV_INT,0.7 +YAW2SRV_SLIP,0.75 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/hwdef.dat new file mode 100644 index 0000000000..dcc2ae1b6c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/hwdef.dat @@ -0,0 +1 @@ +include ../CarbonixCommon/cubeorange.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/scripts/cx_built_in_test.lua b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/scripts/cx_built_in_test.lua new file mode 120000 index 0000000000..dbb50da048 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/scripts/cx_built_in_test.lua @@ -0,0 +1 @@ +../../CarbonixCommon/scripts/cx_built_in_test.lua \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/scripts/cx_led_driver.lua b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/scripts/cx_led_driver.lua new file mode 120000 index 0000000000..71087fb1e4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-Volanti/scripts/cx_led_driver.lua @@ -0,0 +1 @@ +../../CarbonixCommon/scripts/cx_led_driver.lua \ No newline at end of file