forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
AP_State.cpp
91 lines (80 loc) · 2.47 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
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
91
#include "Copter.h"
// ---------------------------------------------
void Copter::set_auto_armed(bool b)
{
// if no change, exit immediately
if( ap.auto_armed == b )
return;
ap.auto_armed = b;
if(b){
Log_Write_Event(DATA_AUTO_ARMED);
}
}
// ---------------------------------------------
/**
* Set Simple mode
*
* @param [in] b 0:false or disabled, 1:true or SIMPLE, 2:SUPERSIMPLE
*/
void Copter::set_simple_mode(uint8_t b)
{
if (ap.simple_mode != b) {
switch (b) {
case 0:
Log_Write_Event(DATA_SET_SIMPLE_OFF);
gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode off");
break;
case 1:
Log_Write_Event(DATA_SET_SIMPLE_ON);
gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode on");
break;
case 2:
default:
// initialise super simple heading
update_super_simple_bearing(true);
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON);
gcs().send_text(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");
break;
}
ap.simple_mode = b;
}
}
// ---------------------------------------------
void Copter::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 Copter::set_failsafe_gcs(bool b)
{
failsafe.gcs = b;
}
// ---------------------------------------------
void Copter::update_using_interlock()
{
#if FRAME_CONFIG == HELI_FRAME
// helicopters are always using motor interlock
ap.using_interlock = true;
#else
// check if we are using motor interlock control on an aux switch or are in throw mode
// which uses the interlock to stop motors while the copter is being thrown
ap.using_interlock = rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) != nullptr;
#endif
}