diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index a0d1db2ae0..42d580dfd9 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -29,7 +29,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] PROGMEM = { // @DisplayName: Voltage Multiplier // @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick on APM2 or Pixhawk, this should be set to 10.1. For the PX4 using the PX4IO power supply this should be set to 1. // @User: Advanced - AP_GROUPINFO("BATT_VOLT_MULT", 3, AP_BattMonitor, _volt_multiplier, AP_BATT_VOLTDIVIDER_DEFAULT), + AP_GROUPINFO("VOLT_MULT", 3, AP_BattMonitor, _volt_multiplier, AP_BATT_VOLTDIVIDER_DEFAULT), // @Param: BATT_APM_PERVOLT // @DisplayName: Apms per volt diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index a88302fc11..5312ceec65 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -23,7 +23,7 @@ #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 # define AP_BATT_VOLT_PIN 13 // APM2.5/2.6 with 3dr power module # define AP_BATT_CURR_PIN 12 - # define AP_BATT_VOLTDIVIDER_DEFAULT 10.0 + # define AP_BATT_VOLTDIVIDER_DEFAULT 10.1 # define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 0 #elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE // Flymaple board pin 20 is connected to the external battery supply @@ -37,17 +37,17 @@ #elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 # define AP_BATT_VOLT_PIN 2 # define AP_BATT_CURR_PIN 3 - # define AP_BATT_VOLTDIVIDER_DEFAULT 10.0 + # define AP_BATT_VOLTDIVIDER_DEFAULT 10.1 # define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17 #elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL - # define AP_BATT_VOLT_PIN 1 - # define AP_BATT_CURR_PIN 2 - # define AP_BATT_VOLTDIVIDER_DEFAULT 10.0 - # define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 0 + # define AP_BATT_VOLT_PIN 13 + # define AP_BATT_CURR_PIN 12 + # define AP_BATT_VOLTDIVIDER_DEFAULT 10.1 + # define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 17 #else # define AP_BATT_VOLT_PIN -1 # define AP_BATT_CURR_PIN -1 - # define AP_BATT_VOLTDIVIDER_DEFAULT 10.0 + # define AP_BATT_VOLTDIVIDER_DEFAULT 10.1 # define AP_BATT_CURR_AMP_PERVOLT_DEFAULT 0 #endif