mirror of https://github.com/ArduPilot/ardupilot
AP_Battery: fixed parameter name and default voltage ratio
also setup SITL with right pins
This commit is contained in:
parent
c7df0eaf2a
commit
366d73124a
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
Loading…
Reference in New Issue