forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
AP_State.cpp
51 lines (42 loc) · 1.17 KB
/
AP_State.cpp
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
#include "Blimp.h"
// ---------------------------------------------
void Blimp::set_auto_armed(bool b)
{
// if no change, exit immediately
if ( ap.auto_armed == b ) {
return;
}
ap.auto_armed = b;
if (b) {
AP::logger().Write_Event(LogEvent::AUTO_ARMED);
}
}
// ---------------------------------------------
void Blimp::set_failsafe_radio(bool b)
{
// only act on changes
// -------------------
if (failsafe.radio != b) {
// store the value so we don't trip the gate twice
// -----------------------------------------------
failsafe.radio = b;
if (failsafe.radio == false) {
// We've regained radio contact
// ----------------------------
failsafe_radio_off_event();
} else {
// We've lost radio contact
// ------------------------
failsafe_radio_on_event();
}
// update AP_Notify
AP_Notify::flags.failsafe_radio = b;
}
}
// ---------------------------------------------
void Blimp::set_failsafe_gcs(bool b)
{
failsafe.gcs = b;
// update AP_Notify
AP_Notify::flags.failsafe_gcs = b;
}