|
|
|
@ -15,7 +15,7 @@ static LowPassFilterInt32 altitude_filter(0.3);
@@ -15,7 +15,7 @@ static LowPassFilterInt32 altitude_filter(0.3);
|
|
|
|
|
// above the calibration altitude |
|
|
|
|
static int32_t read_barometer(void) |
|
|
|
|
{ |
|
|
|
|
barometer.read(); |
|
|
|
|
barometer.read(); |
|
|
|
|
return altitude_filter.apply(barometer.get_altitude() * 100.0); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -23,7 +23,7 @@ static int32_t read_barometer(void)
@@ -23,7 +23,7 @@ static int32_t read_barometer(void)
|
|
|
|
|
static void read_airspeed(void) |
|
|
|
|
{ |
|
|
|
|
airspeed.read(); |
|
|
|
|
calc_airspeed_errors(); |
|
|
|
|
calc_airspeed_errors(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void zero_airspeed(void) |
|
|
|
@ -34,24 +34,24 @@ static void zero_airspeed(void)
@@ -34,24 +34,24 @@ static void zero_airspeed(void)
|
|
|
|
|
|
|
|
|
|
static void read_battery(void) |
|
|
|
|
{ |
|
|
|
|
if(g.battery_monitoring == 0) { |
|
|
|
|
battery_voltage1 = 0; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) { |
|
|
|
|
if(g.battery_monitoring == 0) { |
|
|
|
|
battery_voltage1 = 0; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) { |
|
|
|
|
static AP_AnalogSource_Arduino bat_pin(BATTERY_PIN_1); |
|
|
|
|
battery_voltage1 = BATTERY_VOLTAGE(bat_pin.read_average()); |
|
|
|
|
battery_voltage1 = BATTERY_VOLTAGE(bat_pin.read_average()); |
|
|
|
|
} |
|
|
|
|
if(g.battery_monitoring == 4) { |
|
|
|
|
if(g.battery_monitoring == 4) { |
|
|
|
|
static AP_AnalogSource_Arduino current_pin(CURRENT_PIN_1); |
|
|
|
|
current_amps1 = CURRENT_AMPS(current_pin.read_average()); |
|
|
|
|
current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours) |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if BATTERY_EVENT == ENABLED |
|
|
|
|
if(battery_voltage1 < LOW_VOLTAGE) low_battery_event(); |
|
|
|
|
if(g.battery_monitoring == 4 && current_total1 > g.pack_capacity) low_battery_event(); |
|
|
|
|
#endif |
|
|
|
|
current_amps1 = CURRENT_AMPS(current_pin.read_average()); |
|
|
|
|
current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours) |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if BATTERY_EVENT == ENABLED |
|
|
|
|
if(battery_voltage1 < LOW_VOLTAGE) low_battery_event(); |
|
|
|
|
if(g.battery_monitoring == 4 && current_total1 > g.pack_capacity) low_battery_event(); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|