boards: move default battery calibration defines to parameter defaults

This commit is contained in:
Daniel Agar
2022-01-08 15:10:52 -05:00
parent 78b3d22471
commit daa925137c
63 changed files with 141 additions and 190 deletions

View File

@@ -35,6 +35,6 @@ param set-default MC_YAWRATE_P 0.25
param set-default MC_YAWRATE_I 0.25
param set-default BAT1_V_DIV 12.27559
param set-default BAT1_A_PER_V 15.39103
param set-default BAT1_A_PER_V 15.391030303103
set MIXER quad_w

View File

@@ -0,0 +1,7 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303

View File

@@ -72,12 +72,6 @@
#define ADC_RC_RSSI_CHANNEL 11
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
/* Power supply control and monitoring GPIOs */
// #define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
// #define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)

View File

@@ -5,6 +5,8 @@
param set-default SYS_AUTOSTART 4061
param set-default BAT1_V_DIV 9.0
param set-default COM_ARM_SDCARD 0
param set-default SENS_EXT_I2C_PRB 0

View File

@@ -98,9 +98,6 @@
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
(1 << ADC1_SPARE_1_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V */
#define BOARD_BATTERY1_V_DIV (9.0f) /* measured with the provided PM board */
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)

View File

@@ -5,3 +5,5 @@
# system_power unavailable
param set-default CBRK_SUPPLY_CHK 894281
param set-default BAT1_V_DIV 10.13

View File

@@ -88,12 +88,6 @@
#define ADC_CHANNELS \
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (10.133333333f)
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)

View File

@@ -0,0 +1,6 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 11.0

View File

@@ -42,8 +42,6 @@
#define BOARD_OVERRIDE_UUID "BBBLUEID00000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_BBBLUE
#define BOARD_BATTERY1_V_DIV (11.0f)
#define BOARD_MAX_LEDS 4 // Number external of LED's this board has

View File

@@ -0,0 +1,8 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303

View File

@@ -42,9 +42,6 @@
#define BOARD_OVERRIDE_UUID "RPIID00000000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_RPI
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
#define BOARD_MAX_LEDS 1 // Number of external LED's this board has

View File

@@ -1,7 +1,13 @@
#!/bin/sh
#
# Holybro Durandal V1 specific board defaults
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 18.1
param set-default BAT2_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152
param set-default BAT2_A_PER_V 36.367515152
# Enable IMU thermal control
param set-default SENS_EN_THERMAL 1

View File

@@ -140,12 +140,6 @@
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
(1 << ADC1_3V3_IN_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)

View File

@@ -3,6 +3,9 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.9
param set-default BAT1_A_PER_V 17
# system_power unavailable
param set-default CBRK_SUPPLY_CHK 894281

View File

@@ -92,11 +92,6 @@
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
(1 << ADC_RSSI_IN_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (10.9f)
#define BOARD_BATTERY1_A_PER_V (17.f)
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 6

View File

@@ -3,5 +3,11 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 18.1
param set-default BAT2_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152
param set-default BAT2_A_PER_V 36.367515152
rgbled_pwm start
safety_button start

View File

@@ -173,12 +173,6 @@
(1 << ADC1_SPARE_1_CHANNEL))
#endif
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)

View File

@@ -0,0 +1,10 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 11
param set-default BAT1_A_PER_V 40
param set-default BAT2_V_DIV 11
param set-default BAT2_A_PER_V 40

View File

@@ -101,15 +101,6 @@
(1 << ADC_AIRSPEED_IN_CHANNEL) | \
(1 << ADC_RSSI_IN_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (40.0f)
#define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */
/* CAN Silence
*
* Silent mode control \ ESC Mux select

View File

@@ -1,4 +1,4 @@
#!/bin/sh
#
# ModalAI FC-v2 specific board defaults
# board specific defaults
#------------------------------------------------------------------------------

View File

@@ -171,12 +171,6 @@
#define SYSTEM_ADC_BASE STM32_ADC1_BASE
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)

View File

@@ -3,4 +3,7 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.1
param set-default BAT1_A_PER_V 17
safety_button start

View File

@@ -95,10 +95,6 @@
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_RC_RSSI_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V */
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)

View File

@@ -3,4 +3,7 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.1
param set-default BAT1_A_PER_V 17
safety_button start

View File

@@ -95,10 +95,6 @@
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_RC_RSSI_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V */
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)

View File

@@ -4,6 +4,6 @@
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.1
param set-default BAT1_A_PER_V 24
param set-default BAT1_A_PER_V 17
safety_button start

View File

@@ -4,6 +4,6 @@
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.1
param set-default BAT1_A_PER_V 24
param set-default BAT1_A_PER_V 17
safety_button start

View File

@@ -0,0 +1,7 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303

View File

@@ -0,0 +1,7 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303

View File

@@ -3,5 +3,8 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303
rgbled_pwm start
safety_button start

View File

@@ -249,12 +249,6 @@ __END_DECLS
/* PTB6 ADC1_SE12 */ ADC1_GPIO(12), \
/* PTB7 ADC1_SE13 */ ADC1_GPIO(13)
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
/* User GPIOs
*
*/

View File

@@ -3,6 +3,9 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303
rgbled_pwm start
safety_button start

View File

@@ -253,12 +253,6 @@ __END_DECLS
/* PTB6 ADC1_SE12 */ ADC1_GPIO(12), \
/* PTB7 ADC1_SE13 */ ADC1_GPIO(13)
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
/* User GPIOs
*
*/

View File

@@ -3,5 +3,8 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.1097
param set-default BAT1_A_PER_V 15.391030303
rgbled_pwm start
safety_button start

View File

@@ -179,11 +179,6 @@
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
(1 << ADC1_SPARE_1_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V */
#define BOARD_BATTERY1_V_DIV (10.1097f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)

View File

@@ -3,6 +3,9 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 11.12
param set-default BAT1_A_PER_V 31
# system_power unavailable
param set-default CBRK_SUPPLY_CHK 894281

View File

@@ -74,11 +74,6 @@
#define ADC_BATTERY_CURRENT_CHANNEL 11
#define ADC_RC_RSSI_CHANNEL 0
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (11.12f)
#define BOARD_BATTERY1_A_PER_V (31.f)
/* User GPIOs
*
* GPIO0-5 are the PWM servo outputs.

View File

@@ -0,0 +1,8 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303

View File

@@ -108,12 +108,6 @@
#define ADC_5V_RAIL_SENSE 4
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
/* Power supply control and monitoring GPIOs */
#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)

View File

@@ -0,0 +1,7 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.177939394
param set-default BAT1_A_PER_V 15.391030303

View File

@@ -108,12 +108,6 @@
#define ADC_5V_RAIL_SENSE 4
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
/* Power supply control and monitoring GPIOs */
#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)

View File

@@ -3,26 +3,7 @@
# board specific defaults
#------------------------------------------------------------------------------
# start MAVLink on Wifi (ESP8266 port). Except for the TealOne airframe.
if ! param compare SYS_AUTOSTART 4250
then
param set-default MAV_2_CONFIG 301
param set-default MAV_2_RATE 20000
param set-default SER_WIFI_BAUD 921600
fi
if param compare SER_WIFI_BAUD 1
then
# Transitional support: The Wifi port has not been configured by the user,
# configure it for MAVLink via the ESP8266 Wifi module. Except for the TealOne airframe.
if ! param compare SYS_AUTOSTART 4250
then
param set-default MAV_2_CONFIG 301
param set-default MAV_2_RATE 20000
param set-default SER_WIFI_BAUD 921600
fi
fi
param set-default BAT1_V_DIV 13.653333333
param set-default BAT1_A_PER_V 36.367515152
safety_button start

View File

@@ -83,11 +83,6 @@
#define ADC_5V_RAIL_SENSE 4
#define ADC_RC_RSSI_CHANNEL 11
/* Define Battery 1 Voltage Divider and A per V. */
#define BOARD_BATTERY1_V_DIV (13.653333333f)
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* Power supply control and monitoring GPIOs. */
#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
#define GPIO_VDD_USB_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0)

View File

@@ -3,6 +3,12 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 6.490196078
param set-default BAT2_V_DIV 6.490196078
param set-default BAT1_A_PER_V 26.4
param set-default BAT2_A_PER_V 26.4
# Multi-EKF
param set-default EKF2_MULTI_IMU 2
param set-default SENS_IMU_MODE 0

View File

@@ -112,18 +112,6 @@
(1 << ADC_5V_RAIL_SENSE) | \
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | (1 << ADC_BATTERY2_CURRENT_CHANNEL)
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (6.490196078f)
#define BOARD_BATTERY1_A_PER_V (26.4f)
/* Define Battery 2 Voltage Divider and A per V
*/
#define BOARD_BATTERY2_V_DIV (6.490196078f)
#define BOARD_BATTERY2_A_PER_V (26.4f)
/* Define LTC4417 UV set by resistors on the board that are different than FMUv2 3.7V */
#define BOARD_VALID_UV (4.01f)

View File

@@ -3,6 +3,11 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 18.1
param set-default BAT2_V_DIV 18.1
param set-default BAT1_A_PER_V 36.367515152
param set-default BAT2_A_PER_V 36.367515152
if ver hwtypecmp V550 V560
then

View File

@@ -173,18 +173,10 @@
(1 << ADC1_SPARE_1_CHANNEL))
#endif
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING
#define GPIO_HW_REV_DRIVE /* PH14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN14)

View File

@@ -164,18 +164,10 @@
#define SYSTEM_ADC_BASE STM32_ADC1_BASE
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)

View File

@@ -202,18 +202,10 @@
#define SYSTEM_ADC_BASE STM32_ADC1_BASE
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)

View File

@@ -42,9 +42,6 @@
#define BOARD_OVERRIDE_UUID "SIMULATIONID0000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_SITL
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
#define BOARD_HAS_POWER_CONTROL 1
#define PX4_NUMBER_I2C_BUSES 1

View File

@@ -3,6 +3,9 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 13.653333333
param set-default BAT1_A_PER_V 36.367515152
# system_power unavailable
param set-default CBRK_SUPPLY_CHK 894281

View File

@@ -65,10 +65,6 @@
#define ADC_BATTERY_CURRENT_CHANNEL 2 // Corresponding GPIO 28. Used in init.c for disabling GPIO_IE
#define ADC_RC_RSSI_CHANNEL 0
/* Define Battery 1 Voltage Divider and A per V. */
#define BOARD_BATTERY1_V_DIV (13.653333333f)
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* High-resolution timer */
#define HRT_TIMER 1
#define HRT_TIMER_CHANNEL 1

View File

@@ -0,0 +1,7 @@
#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
# 1K + 4.7K
param set-default BAT1_V_DIV 5.7

View File

@@ -56,7 +56,6 @@
#define ADC_BATTERY_CURRENT_CHANNEL -1
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 2
#define BOARD_BATTERY1_V_DIV 5.7f // 1K + 4.7K
#define ADC_DP_V_DIV 1.0f
#define BOARD_ADC_OPEN_CIRCUIT_V 5.3f // Powered from USB

View File

@@ -3,6 +3,9 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.9
param set-default BAT1_A_PER_V 17
# system_power unavailable
param set-default CBRK_SUPPLY_CHK 894281

View File

@@ -88,11 +88,6 @@
#define ADC_CHANNELS (1 << 4) | (1 << 10) | (1 << 11)
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (10.9f)
#define BOARD_BATTERY1_A_PER_V (17.f)
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 8

View File

@@ -3,5 +3,8 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default BAT1_V_DIV 10.14
param set-default BAT1_A_PER_V 18.18
# don't probe external I2C
param set-default SENS_EXT_I2C_PRB 0

View File

@@ -83,10 +83,6 @@
#define ADC_5V_RAIL_SENSE 4
#define ADC_RC_RSSI_CHANNEL 11
/* Define Battery 1 Voltage Divider and A per V. */
#define BOARD_BATTERY1_V_DIV (10.14f)
#define BOARD_BATTERY1_A_PER_V (18.18f)
/* Power supply control and monitoring GPIOs. */
#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
#define GPIO_VDD_USB_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0)

View File

@@ -8,6 +8,9 @@ param import
# system_power not implemented
param set CBRK_SUPPLY_CHK 894281
param set-default BAT1_V_DIV 5.7
# broadcast to LAN
# always keep current config
param set SYS_AUTOCONFIG 0

View File

@@ -8,6 +8,9 @@ param import
# system_power not implemented
param set CBRK_SUPPLY_CHK 894281
param set-default BAT1_V_DIV 5.7
# broadcast to LAN
# always keep current config
param set SYS_AUTOCONFIG 0

View File

@@ -8,6 +8,8 @@
param select eeprom/parameters
param import
param set BAT1_V_DIV 10.177939394
param set BAT1_A_PER_V 15.391030303
param set CBRK_SUPPLY_CHK 894281
param set SYS_AUTOSTART 4001
param set MAV_TYPE 2

View File

@@ -8,6 +8,8 @@
param select eeprom/parameters
param import
param set BAT1_V_DIV 10.177939394
param set BAT1_A_PER_V 15.391030303
param set CBRK_SUPPLY_CHK 894281
param set SYS_AUTOSTART 2100
param set MAV_TYPE 1

View File

@@ -126,17 +126,5 @@ AnalogBattery::updateParams()
param_get(_analog_param_handles.i_channel, &_analog_params.i_channel);
param_get(_analog_param_handles.v_offs_cur, &_analog_params.v_offs_cur);
if (_analog_params.v_div < 0.0f) {
/* apply scaling according to defaults if set to default */
_analog_params.v_div = BOARD_BATTERY1_V_DIV;
param_set_no_notification(_analog_param_handles.v_div, &_analog_params.v_div);
}
if (_analog_params.a_per_v < 0.0f) {
/* apply scaling according to defaults if set to default */
_analog_params.a_per_v = BOARD_BATTERY1_A_PER_V;
param_set_no_notification(_analog_param_handles.a_per_v, &_analog_params.a_per_v);
}
Battery::updateParams();
}