2011-03-19 07:20:11 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-02-25 01:33:39 -04:00
|
|
|
// Sensors are not available in HIL_MODE_ATTITUDE
|
|
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
|
|
|
2011-02-24 01:56:59 -04:00
|
|
|
void ReadSCP1000(void) {}
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-02-24 01:56:59 -04:00
|
|
|
void init_barometer(void)
|
2010-12-19 12:40:33 -04:00
|
|
|
{
|
2011-02-25 01:33:39 -04:00
|
|
|
#if HIL_MODE == HIL_MODE_SENSORS
|
|
|
|
hil.update(); // look for inbound hil packets for initialization
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
// We take some readings...
|
|
|
|
for(int i = 0; i < 200; i++){
|
|
|
|
delay(25);
|
2011-02-25 01:33:39 -04:00
|
|
|
|
|
|
|
#if HIL_MODE == HIL_MODE_SENSORS
|
|
|
|
hil.update(); // look for inbound hil packets
|
|
|
|
#endif
|
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
// Get initial data from absolute pressure sensor
|
|
|
|
ground_pressure = read_baro_filtered();
|
2011-02-25 01:33:39 -04:00
|
|
|
ground_temperature = (ground_temperature * 9 + barometer.Temp) / 10;
|
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2011-06-16 14:03:26 -03:00
|
|
|
abs_pressure = ground_pressure;
|
|
|
|
ground_temperature = barometer.Temp;
|
2011-02-25 01:33:39 -04:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
//Serial.printf("abs_pressure %ld\n", ground_temperature);
|
|
|
|
//SendDebugln("barometer calibration complete.");
|
|
|
|
}
|
2010-12-19 12:40:33 -04:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
long read_baro_filtered(void)
|
|
|
|
{
|
|
|
|
long pressure = 0;
|
2011-02-25 01:33:39 -04:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
// get new data from absolute pressure sensor
|
|
|
|
barometer.Read();
|
|
|
|
|
|
|
|
// add new data into our filter
|
|
|
|
baro_filter[baro_filter_index] = barometer.Press;
|
|
|
|
baro_filter_index++;
|
|
|
|
|
|
|
|
// loop our filter
|
|
|
|
if(baro_filter_index == BARO_FILTER_SIZE)
|
|
|
|
baro_filter_index = 0;
|
|
|
|
|
|
|
|
// zero out our accumulator
|
|
|
|
|
|
|
|
// sum our filter
|
|
|
|
for(byte i = 0; i < BARO_FILTER_SIZE; i++){
|
|
|
|
pressure += baro_filter[i];
|
|
|
|
}
|
|
|
|
|
|
|
|
// average our sampels
|
|
|
|
return pressure /= BARO_FILTER_SIZE;
|
2011-02-25 01:33:39 -04:00
|
|
|
}
|
2011-02-24 01:56:59 -04:00
|
|
|
|
|
|
|
long read_barometer(void)
|
2011-02-21 00:30:56 -04:00
|
|
|
{
|
2010-12-19 12:40:33 -04:00
|
|
|
float x, scaling, temp;
|
2011-02-20 19:09:28 -04:00
|
|
|
|
2011-06-16 14:03:26 -03:00
|
|
|
abs_pressure = read_baro_filtered();
|
|
|
|
|
|
|
|
//Serial.printf("%ld, %ld, %ld, %ld\n", barometer.RawTemp, barometer.RawPress, barometer.Press, abs_pressure);
|
2011-02-20 19:09:28 -04:00
|
|
|
|
2011-02-18 23:59:58 -04:00
|
|
|
scaling = (float)ground_pressure / (float)abs_pressure;
|
2011-02-21 00:30:56 -04:00
|
|
|
temp = ((float)ground_temperature / 10.0f) + 273.15f;
|
2010-12-19 12:40:33 -04:00
|
|
|
x = log(scaling) * temp * 29271.267f;
|
2011-02-21 00:30:56 -04:00
|
|
|
return (x / 10);
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// in M/S * 100
|
|
|
|
void read_airspeed(void)
|
|
|
|
{
|
|
|
|
|
|
|
|
}
|
|
|
|
|
2011-02-25 01:33:39 -04:00
|
|
|
void zero_airspeed(void)
|
|
|
|
{
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2011-02-25 01:33:39 -04:00
|
|
|
}
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2011-02-25 01:33:39 -04:00
|
|
|
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
2011-02-24 01:56:59 -04:00
|
|
|
|
2010-12-19 12:40:33 -04:00
|
|
|
void read_battery(void)
|
|
|
|
{
|
|
|
|
battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9;
|
|
|
|
battery_voltage2 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN2)) * .1 + battery_voltage2 * .9;
|
|
|
|
battery_voltage3 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN3)) * .1 + battery_voltage3 * .9;
|
|
|
|
battery_voltage4 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN4)) * .1 + battery_voltage4 * .9;
|
2011-01-17 22:48:44 -04:00
|
|
|
|
2011-05-09 12:46:56 -03:00
|
|
|
if(g.battery_monitoring == 1)
|
2010-12-19 12:40:33 -04:00
|
|
|
battery_voltage = battery_voltage3; // set total battery voltage, for telemetry stream
|
2011-05-09 12:46:56 -03:00
|
|
|
if(g.battery_monitoring == 2)
|
|
|
|
battery_voltage = battery_voltage4;
|
|
|
|
if(g.battery_monitoring == 3 || g.battery_monitoring == 4)
|
|
|
|
battery_voltage = battery_voltage1;
|
|
|
|
if(g.battery_monitoring == 4) {
|
|
|
|
current_amps = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps * .9; //reads power sensor current pin
|
|
|
|
current_total += current_amps * (float)delta_ms_medium_loop * 0.000278;
|
|
|
|
}
|
2011-02-20 19:09:28 -04:00
|
|
|
|
2011-05-09 12:46:56 -03:00
|
|
|
#if BATTERY_EVENT == 1
|
|
|
|
if(battery_voltage < LOW_VOLTAGE) low_battery_event();
|
|
|
|
if(g.battery_monitoring == 4 && current_total > g.pack_capacity) low_battery_event();
|
2011-01-16 23:44:12 -04:00
|
|
|
#endif
|
2010-12-19 12:40:33 -04:00
|
|
|
}
|
2011-01-17 22:48:44 -04:00
|
|
|
|
|
|
|
//v: 10.9453, a: 17.4023, mah: 8.2
|