mirror of https://github.com/ArduPilot/ardupilot
hwdef: updated KakuteH7 battery scale defaults
thanks to Vincent at Holybro
This commit is contained in:
parent
7ad1886667
commit
05ec2be62b
|
@ -78,8 +78,8 @@ PA8 VBUS INPUT
|
||||||
# define default battery setup
|
# define default battery setup
|
||||||
define HAL_BATT_VOLT_PIN 10
|
define HAL_BATT_VOLT_PIN 10
|
||||||
define HAL_BATT_CURR_PIN 11
|
define HAL_BATT_CURR_PIN 11
|
||||||
define HAL_BATT_VOLT_SCALE 10.1
|
define HAL_BATT_VOLT_SCALE 11.0
|
||||||
define HAL_BATT_CURR_SCALE 17.0
|
define HAL_BATT_CURR_SCALE 59.5
|
||||||
|
|
||||||
PC5 RSSI_ADC ADC1
|
PC5 RSSI_ADC ADC1
|
||||||
define BOARD_RSSI_ANA_PIN 8
|
define BOARD_RSSI_ANA_PIN 8
|
||||||
|
|
Loading…
Reference in New Issue