AP_HAL_ChibiOS: update relay parameter names

This commit is contained in:
Iampete1 2024-06-12 12:51:25 +01:00 committed by Randy Mackay
parent 2216f64c30
commit 18d13986ff
15 changed files with 31 additions and 30 deletions

View File

@ -1,7 +1,7 @@
# setup for LEDs on chan9
SERVO9_FUNCTION 120
# Default VTX power to on
RELAY_DEFAULT 1
RELAY2_DEFAULT 1
# UART1 for DJI Goggles
SERIAL1_PROTOCOL 33

View File

@ -52,7 +52,7 @@ The KakuteH7 v2 supports OSD using OSD_TYPE 1 (MAX7456 driver).
## VTX Support
The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect
this to a peripheral requiring 5v. The 9v supply is controlled by RELAY_PIN2 and is on by default. It can be configured to be operated by an RC switch by selecting the function RELAY2.
this to a peripheral requiring 5v. The 9v supply is controlled by RELAY2_PIN and is on by default. It can be configured to be operated by an RC switch by selecting the function RELAY2.
## PWM Output

View File

@ -1,7 +1,7 @@
# setup for LEDs on chan9
SERVO9_FUNCTION 120
# Default VTX power to on
RELAY_DEFAULT 1
RELAY2_DEFAULT 1
# UART1 for DJI Goggles
SERIAL1_PROTOCOL 33
# UART3 for VTX

View File

@ -1,7 +1,7 @@
# setup for LEDs on chan9
SERVO7_FUNCTION 120
# Default VTX power to on
RELAY_DEFAULT 1
RELAY2_DEFAULT 1
# UART1 is RX input
SERIAL1_PROTOCOL 23
# UART2 is GPS

View File

@ -1,5 +1,5 @@
# setup for LEDs on chan9
SERVO9_FUNCTION 120
# Default VTX power to on
RELAY_DEFAULT 1
RELAY2_DEFAULT 1

View File

@ -132,10 +132,10 @@ PE10 UART7_CTS UART7
PE9 UART7_RTS UART7
# telem1-UART7 RTS and CTS as GPIO in alternative configs
PE10 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(2) # Cts7 pin as GPIO 1 (set RELAY_PINx = 1 to use it)
PE9 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(2) # Rts7 pin as GPIO 2 (set RELAY_PINx = 2 to use it)
PE10 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(3) # Cts7 pin as GPIO 1 (set RELAY_PINx = 1 to use it)
PE9 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(3) # Rts7 pin as GPIO 2 (set RELAY_PINx = 2 to use it)
PE10 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(2) # Cts7 pin as GPIO 1 (set RELAYx_PIN = 1 to use it)
PE9 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(2) # Rts7 pin as GPIO 2 (set RELAYx_PIN = 2 to use it)
PE10 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(3) # Cts7 pin as GPIO 1 (set RELAYx_PIN = 1 to use it)
PE9 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(3) # Rts7 pin as GPIO 2 (set RELAYx_PIN = 2 to use it)
# alternative configs:
# 1: bidirectional receiver protocol on RX6 pin

View File

@ -12,12 +12,12 @@ BATT2_VOLT_MULT 20.000
BATT2_AMP_PERVLT 60.000
# setup the parameter for the two Relays GPIO others for reserve
RELAY_PIN 1
RELAY_PIN2 2
RELAY_PIN3 3
RELAY_PIN4 4
RELAY_PIN5 5
RELAY_PIN6 6
RELAY1_PIN 1
RELAY2_PIN 2
RELAY3_PIN 3
RELAY4_PIN 4
RELAY5_PIN 5
RELAY6_PIN 6
# Disable the safety switch by default
BRD_SAFETY_DEFLT 0

View File

@ -16,5 +16,5 @@ BATT2_VOLT_MULT 20.000
BATT2_AMP_PERVLT 17.000
# setup the parameter for the two Relays GPIO others for reserve
RELAY_PIN 1
RELAY_PIN2 2
RELAY1_PIN 1
RELAY2_PIN 2

View File

@ -5,5 +5,5 @@ BRD_HEAT_TARG 45
SERIAL2_BAUD 921600
# setup the parameter for the two Relays GPIO others for reserve
RELAY_PIN 1
RELAY_PIN2 2
RELAY1_PIN 1
RELAY2_PIN 2

View File

@ -13,4 +13,4 @@ SERIAL2_PROTOCOL 5
SERIAL4_PROTOCOL 16
# 9V regulator switch, ON on boot
RELAY_DEFAULT 1
RELAY2_DEFAULT 1

View File

@ -52,7 +52,7 @@ The SDMODEL SDH7 V2 supports OSD using OSD_TYPE 1 (MAX7456 driver).The defaults
## VTX Support
The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect
this to a peripheral requiring 5v. The 9v supply is controlled by RELAY_PIN2 set to GPIO 81 and is on by default. It can be configured to be operated by an RC switch by selecting the function RELAY2.
this to a peripheral requiring 5v. The 9v supply is controlled by RELAY2_PIN set to GPIO 81 and is on by default. It can be configured to be operated by an RC switch by selecting the function RELAY2.
## Camera Control

View File

@ -2,7 +2,8 @@
SERVO9_FUNCTION 120
NTF_LED_LEN 1
# Default VTX power to on
RELAY_DEFAULT 1
RELAY2_DEFAULT 1
RELAY3_DEFAULT 1
SERIAL3_PROTOCOL 16
RSSI_TYPE 3

View File

@ -146,8 +146,6 @@ RC4_MAX,1900
RC4_MIN,1100
RC6_OPTION,5
RC_PROTOCOLS,0
RELAY_PIN,-1
RELAY_PIN2,-1
RTL_ALT,1500
SCHED_LOOP_RATE,800
SERIAL1_BAUD,921

View File

@ -24,9 +24,10 @@ TMODE_FLAGS 63
TMODE_TMIN 0.9
# LEDs. pin0 is green, pin1 is red
RELAY_PIN 0
RELAY_PIN2 1
RELAY_DEFAULT 1
RELAY1_PIN 0
RELAY2_PIN 1
RELAY1_DEFAULT 1
RELAY2_DEFAULT 1
AHRS_ORIENTATION 2
COMPASS_EXTERNAL 1

View File

@ -22,9 +22,10 @@ TMODE_FLAGS 23
TMODE_TMIN 0.9
# LEDs. pin54 is green, pin55 is red
RELAY_PIN 54
RELAY_PIN2 55
RELAY_DEFAULT 1
RELAY1_PIN 54
RELAY2_PIN 55
RELAY1_DEFAULT 1
RELAY2_DEFAULT 1
# Set to GPIO so they are used as RELAY
SERVO5_FUNCTION -1
SERVO6_FUNCTION -1