forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 18
/
sensors.pde
90 lines (75 loc) · 2.53 KB
/
sensors.pde
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// filter altitude from the barometer with a low pass filter
static LowPassFilterInt32 altitude_filter;
static void init_barometer(void)
{
gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer"));
barometer.calibrate();
// filter at 100ms sampling, with 0.7Hz cutoff frequency
altitude_filter.set_cutoff_frequency(0.1, 0.7);
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
}
// read the barometer and return the updated altitude in centimeters
// above the calibration altitude
static int32_t read_barometer(void)
{
barometer.read();
return altitude_filter.apply(barometer.get_altitude() * 100.0);
}
// in M/S * 100
static void read_airspeed(void)
{
airspeed.read();
calc_airspeed_errors();
}
static void zero_airspeed(void)
{
airspeed.calibrate();
gcs_send_text_P(SEVERITY_LOW,PSTR("zero airspeed calibrated"));
}
static void read_battery(void)
{
if(g.battery_monitoring == 0) {
battery.voltage = 0;
return;
}
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
// this copes with changing the pin at runtime
batt_volt_pin->set_pin(g.battery_volt_pin);
battery.voltage = BATTERY_VOLTAGE(batt_volt_pin);
}
if(g.battery_monitoring == 4) {
// this copes with changing the pin at runtime
batt_curr_pin->set_pin(g.battery_curr_pin);
battery.current_amps = CURRENT_AMPS(batt_curr_pin);
// .0002778 is 1/3600 (conversion to hours)
battery.current_total_mah += battery.current_amps * (float)delta_ms_medium_loop * 0.0002778;
}
if (battery.voltage != 0 &&
g.fs_batt_voltage > 0 &&
battery.voltage < g.fs_batt_voltage) {
low_battery_event();
}
if (g.battery_monitoring == 4 &&
g.fs_batt_mah > 0 &&
g.pack_capacity - battery.current_total_mah < g.fs_batt_mah) {
low_battery_event();
}
}
// read the receiver RSSI as an 8 bit number for MAVLink
// RC_CHANNELS_SCALED message
void read_receiver_rssi(void)
{
rssi_analog_source->set_pin(g.rssi_pin);
float ret = rssi_analog_source->voltage_average() * 50;
receiver_rssi = constrain_int16(ret, 0, 255);
}
/*
return current_loc.alt adjusted for ALT_OFFSET
This is useful during long flights to account for barometer changes
from the GCS, or to adjust the flying height of a long mission
*/
static int32_t adjusted_altitude_cm(void)
{
return current_loc.alt - (g.alt_offset*100);
}