diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 6b1cdcc112..18df44a760 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -110,7 +110,7 @@ static void read_battery(void) battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN_1)) * .1 + battery_voltage1 * .9; if(g.battery_monitoring == 4) { current_amps1 = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps1 * .9; //reads power sensor current pin - current_total1 += current_amps1 * 0.0002778; // .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) } #if BATTERY_EVENT == 1