APM:Copter
AP_State.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // ---------------------------------------------
5 {
6  // if no change, exit immediately
7  if( ap.auto_armed == b )
8  return;
9 
10  ap.auto_armed = b;
11  if(b){
13  }
14 }
15 
16 // ---------------------------------------------
23 {
24  if (ap.simple_mode != b) {
25  switch (b) {
26  case 0:
28  gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode off");
29  break;
30  case 1:
32  gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode on");
33  break;
34  case 2:
35  default:
36  // initialise super simple heading
39  gcs().send_text(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");
40  break;
41  }
42  ap.simple_mode = b;
43  }
44 }
45 
46 // ---------------------------------------------
48 {
49  // only act on changes
50  // -------------------
51  if(failsafe.radio != b) {
52 
53  // store the value so we don't trip the gate twice
54  // -----------------------------------------------
55  failsafe.radio = b;
56 
57  if (failsafe.radio == false) {
58  // We've regained radio contact
59  // ----------------------------
61  }else{
62  // We've lost radio contact
63  // ------------------------
65  }
66 
67  // update AP_Notify
69  }
70 }
71 
72 
73 // ---------------------------------------------
75 {
76  failsafe.gcs = b;
77 }
78 
79 // ---------------------------------------------
80 
82 {
83 #if FRAME_CONFIG == HELI_FRAME
84  // helicopters are always using motor interlock
85  ap.using_interlock = true;
86 #else
87  // check if we are using motor interlock control on an aux switch or are in throw mode
88  // which uses the interlock to stop motors while the copter is being thrown
90 #endif
91 }
92 
94 {
95  if(ap.motor_emergency_stop != b) {
96  ap.motor_emergency_stop = b;
97  }
98 
99  // Log new status
100  if (ap.motor_emergency_stop){
102  } else {
104  }
105 }
void failsafe_radio_off_event()
Definition: events.cpp:44
void set_auto_armed(bool b)
Definition: AP_State.cpp:4
struct _USB_OTG_GOTGCTL_TypeDef::@51 b
#define DATA_MOTORS_EMERGENCY_STOPPED
Definition: defines.h:374
GCS_Copter & gcs()
Definition: Copter.h:301
void set_simple_mode(uint8_t b)
Definition: AP_State.cpp:22
#define DATA_SET_SUPERSIMPLE_ON
Definition: defines.h:351
bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check)
Definition: switches.cpp:79
#define DATA_SET_SIMPLE_OFF
Definition: defines.h:350
void update_using_interlock()
Definition: AP_State.cpp:81
void Log_Write_Event(uint8_t id)
Definition: Log.cpp:200
void failsafe_radio_on_event()
Definition: events.cpp:7
void set_failsafe_radio(bool b)
Definition: AP_State.cpp:47
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void update_super_simple_bearing(bool force_update)
Definition: ArduCopter.cpp:532
#define DATA_SET_SIMPLE_ON
Definition: defines.h:349
#define DATA_MOTORS_EMERGENCY_STOP_CLEARED
Definition: defines.h:375
static struct notify_flags_and_values_type flags
struct Copter::@2 failsafe
#define DATA_AUTO_ARMED
Definition: defines.h:341
void set_failsafe_gcs(bool b)
Definition: AP_State.cpp:74
void set_motor_emergency_stop(bool b)
Definition: AP_State.cpp:93