mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter: small comment fixes related to battery monitoring
This commit is contained in:
parent
775489d658
commit
240b0b43fd
@ -116,16 +116,16 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
GSCALAR(tilt_comp, "TILT", TILT_COMPENSATION),
|
GSCALAR(tilt_comp, "TILT", TILT_COMPENSATION),
|
||||||
|
|
||||||
// @Param: BATT_VOLT_PIN
|
// @Param: BATT_VOLT_PIN
|
||||||
// @DisplayName: Battery Voltage sending pin
|
// @DisplayName: Battery Voltage sensing pin
|
||||||
// @Description: Setting this to 0 ~ 11 will enable battery voltage sending on pins A0 ~ A11. Current will be measured on this pin + 1
|
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13.
|
||||||
// @Values: 99:Disabled, 0:A0, 1:A1, 10:A13
|
// @Values: 99:Disabled, 0:A0, 1:A1, 13:A13
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(battery_volt_pin, "BATT_VOLT_PIN", BATTERY_VOLT_PIN),
|
GSCALAR(battery_volt_pin, "BATT_VOLT_PIN", BATTERY_VOLT_PIN),
|
||||||
|
|
||||||
// @Param: BATT_CURR_PIN
|
// @Param: BATT_CURR_PIN
|
||||||
// @DisplayName: Battery Voltage sending pin
|
// @DisplayName: Battery Current sensing pin
|
||||||
// @Description: Setting this to 0 ~ 11 will enable battery voltage sending on pins A0 ~ A11. Current will be measured on this pin + 1
|
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13.
|
||||||
// @Values: 99:Disabled, 0:A0, 1:A1, 10:A12
|
// @Values: 99:Disabled, 1:A1, 2:A2, 12:A12
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(battery_curr_pin, "BATT_CURR_PIN", BATTERY_CURR_PIN),
|
GSCALAR(battery_curr_pin, "BATT_CURR_PIN", BATTERY_CURR_PIN),
|
||||||
|
|
||||||
|
@ -81,7 +81,7 @@ static void read_battery(void)
|
|||||||
battery_voltage1 = BATTERY_VOLTAGE(batt_volt_pin.read_average());
|
battery_voltage1 = BATTERY_VOLTAGE(batt_volt_pin.read_average());
|
||||||
}
|
}
|
||||||
if(g.battery_monitoring == 4) {
|
if(g.battery_monitoring == 4) {
|
||||||
static AP_AnalogSource_Arduino batt_curr_pin(g.battery_curr_pin); // current is always read from one pin higher than battery voltage
|
static AP_AnalogSource_Arduino batt_curr_pin(g.battery_curr_pin);
|
||||||
current_amps1 = CURRENT_AMPS(batt_curr_pin.read_average());
|
current_amps1 = CURRENT_AMPS(batt_curr_pin.read_average());
|
||||||
current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours)
|
current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours)
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user