APM:Copter
afs_copter.cpp
Go to the documentation of this file.
1 /*
2  copter specific AP_AdvancedFailsafe class
3  */
4 
5 #include "Copter.h"
6 
7 #if ADVANCED_FAILSAFE == ENABLED
8 
9 // Constructor
11  AP_AdvancedFailsafe(_mission, _gps)
12 {}
13 
14 
15 /*
16  setup radio_out values for all channels to termination values
17  */
19 {
22  } else {
23  // stop motors
24  copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
25  copter.motors->output();
26 
27  // disarm as well
28  copter.init_disarm_motors();
29 
30  // and set all aux channels
37  }
38 
40 }
41 
43 {
44  // setup failsafe for all aux channels
51 
52 #if FRAME_CONFIG != HELI_FRAME
53  // setup AP_Motors outputs for failsafe
54  uint16_t mask = copter.motors->get_motor_mask();
55  hal.rcout->set_failsafe_pwm(mask, copter.motors->get_pwm_output_min());
56 #endif
57 }
58 
59 /*
60  return an AFS_MODE for current control mode
61  */
63 {
64  switch (copter.control_mode) {
65  case AUTO:
66  case GUIDED:
67  case RTL:
68  case LAND:
70  default:
71  break;
72  }
74 }
75 
76 #endif // ADVANCED_FAILSAFE
Definition: defines.h:95
Definition: defines.h:96
Definition: defines.h:100
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
static void output_ch_all(void)
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
static void set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
AP_HAL::RCOutput * rcout
enum control_mode afs_mode(void)
AP_AdvancedFailsafe_Copter(AP_Mission &_mission, const AP_GPS &_gps)
Definition: defines.h:98