diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat
index 2dbe30e939..8093067f66 100644
--- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat
+++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat
@@ -43,6 +43,19 @@ PC9  TIM8_CH4 TIM8 PWM(8) GPIO(57)
 PB11 VTX_PWR OUTPUT HIGH GPIO(81)
 define RELAY2_PIN_DEFAULT 81
 
+define HAL_BATT_MONITOR_DEFAULT 4
+
+# second battery sensor on second ESC connector
+PA1 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
+PC4 BATT2_CURRENT_SENS ADC1 SCALE(1)
+
+# second battery setup (note external current sensor required)
+define HAL_BATT2_VOLT_PIN 17
+define HAL_BATT2_CURR_PIN 4
+define HAL_BATT2_VOLT_SCALE 11.0
+define HAL_BATT2_CURR_SCALE 59.5
+define HAL_BATT2_MONITOR_DEFAULT 4
+
 SPIDEV dataflash SPI1 DEVID1 SDCARD_CS      MODE3 104*MHZ 104*MHZ
 SPIDEV bmi270    SPI4 DEVID1 ICM20689_CS    MODE3  1*MHZ  10*MHZ # Clock is 100Mhz so highest clock <= 10Mhz is 100Mhz/16
 
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat
index f0bbdf1f65..74c9949e33 100644
--- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat
+++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat
@@ -75,13 +75,6 @@ define HAL_BATT_CURR_SCALE 40.0
 PB0 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
 PB1 BATT2_CURRENT_SENS ADC1 SCALE(1)
 
-define HAL_BATT2_MONITOR_DEFAULT  0
-define HAL_BATT2_VOLT_PIN 15
-define HAL_BATT2_VOLT_SCALE 21.0
-define HAL_BATT2_CURR_PIN 16
-define HAL_BATT2_CURR_SCALE 40.0
-
-
 # -------------------- Buzzer+NeoPixels --------------d------
 define HAL_PERIPH_ENABLE_RC_OUT
 define HAL_PERIPH_ENABLE_NOTIFY
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat
index 1592b42147..22285cf8eb 100644
--- a/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat
+++ b/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat
@@ -212,10 +212,6 @@ PC1 SCALED_V3V3 ADC1 SCALE(2)
 # setup scaling defaults
 define HAL_BATT_VOLT_SCALE 18.0
 define HAL_BATT_CURR_SCALE 24.0
-define HAL_BATT_VOLT_PIN 0
-define HAL_BATT_CURR_PIN 1
-define HAL_BATT2_VOLT_PIN 2
-define HAL_BATT2_CURR_PIN 3
 
 # CAN bus
 PI9  CAN1_RX CAN1
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat
index 00b363a8d7..cc5358dd18 100644
--- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat
+++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat
@@ -198,14 +198,17 @@ PB1 BATT2_VOLTAGE_SENS ADC1 SCALE(2)
 PC4 VDD_5V_SENS ADC1 SCALE(2)
 PC5 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(12)
 
+define HAL_BATT_MONITOR 4
 define HAL_BATT_VOLT_PIN 13
 define HAL_BATT_CURR_PIN 12
+define HAL_BATT_VOLT_SCALE 20
+define HAL_BATT_CURR_SCALE 61
+# not enabled by default
+# define HAL_BATT2_MONITOR 4
 define HAL_BATT2_VOLT_PIN 9
 define HAL_BATT2_CURR_PIN 8
-define HAL_BATT_VOLT_SCALE 20
-define HAL_BATT_CURR_SCALE 17
 define HAL_BATT2_VOLT_SCALE 20
-define HAL_BATT2_CURR_SCALE 17
+define HAL_BATT2_CURR_SCALE 61
 
 
 define HAL_HAVE_IMU_HEATER 1
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm
index 65b893da7c..7e5dd045aa 100644
--- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm
+++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm
@@ -4,17 +4,6 @@ BRD_HEAT_TARG 45
 # setup serial2 port defaults for ESP8266
 SERIAL2_BAUD 921600
 
-# setup the parameter for the ADC power module
-BATT_MONITOR 4
-BATT_VOLT_PIN 16
-BATT_CURR_PIN 17
-BATT_VOLT_MULT 20.000
-BATT_AMP_PERVLT 17.000
-BATT2_VOLT_PIN 10
-BATT2_CURR_PIN 11
-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
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat
index dfca39149e..e992a954fb 100644
--- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat
+++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat
@@ -134,6 +134,18 @@ PC4 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(12)
 PC5 PRESSURE_SENS ADC1 SCALE(2)
 PB1 RSSI_IN ADC1 SCALE(2)
 
+# setup the parameter for the ADC power module
+define HAL_BATT_MONITOR 4
+define HAL_BATT_VOLT_PIN 16
+define HAL_BATT_CURR_PIN 17
+define HAL_BATT_VOLT_SCALE 20.000
+define HAL_BATT_CURR_SCALE 61.000
+# not enabled by default
+# define HAL_BATT2_MONITOR 4
+define HAL_BATT2_VOLT_PIN 10
+define HAL_BATT2_CURR_PIN 11
+define HAL_BATT2_VOLT_SCALE 20.000
+define HAL_BATT2_CURR_SCALE 61.000
 
 # CAN bus
 PD0  CAN1_RX CAN1