mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
battery: use set_pin() to allow pins to be changed at runtime
This commit is contained in:
parent
f541b2a081
commit
33d9ae23ff
@ -78,10 +78,12 @@ static void read_battery(void)
|
||||
|
||||
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
|
||||
static AP_AnalogSource_Arduino batt_volt_pin(g.battery_volt_pin);
|
||||
batt_volt_pin.set_pin(g.battery_volt_pin);
|
||||
battery_voltage1 = BATTERY_VOLTAGE(batt_volt_pin.read_average());
|
||||
}
|
||||
if(g.battery_monitoring == 4) {
|
||||
static AP_AnalogSource_Arduino batt_curr_pin(g.battery_curr_pin);
|
||||
batt_curr_pin.set_pin(g.battery_curr_pin);
|
||||
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)
|
||||
}
|
||||
|
@ -41,10 +41,14 @@ static void read_battery(void)
|
||||
|
||||
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
|
||||
static AP_AnalogSource_Arduino batt_volt_pin(g.battery_volt_pin);
|
||||
// this copes with changing the pin at runtime
|
||||
batt_volt_pin.set_pin(g.battery_volt_pin);
|
||||
battery_voltage1 = BATTERY_VOLTAGE(batt_volt_pin.read_average());
|
||||
}
|
||||
if(g.battery_monitoring == 4) {
|
||||
static AP_AnalogSource_Arduino batt_curr_pin(g.battery_curr_pin);
|
||||
// this copes with changing the pin at runtime
|
||||
batt_curr_pin.set_pin(g.battery_curr_pin);
|
||||
current_amps1 = CURRENT_AMPS(batt_curr_pin.read_average());
|
||||
current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours)
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user