APM:Copter
mode_flip.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * Init and run calls for flip flight mode
5  * original implementation in 2010 by Jose Julio
6  * Adapted and updated for AC2 in 2011 by Jason Short
7  *
8  * Controls:
9  * CH7_OPT - CH12_OPT parameter must be set to "Flip" (AUXSW_FLIP) which is "2"
10  * Pilot switches to Stabilize, Acro or AltHold flight mode and puts ch7/ch8 switch to ON position
11  * Vehicle will Roll right by default but if roll or pitch stick is held slightly left, forward or back it will flip in that direction
12  * Vehicle should complete the roll within 2.5sec and will then return to the original flight mode it was in before flip was triggered
13  * Pilot may manually exit flip by switching off ch7/ch8 or by moving roll stick to >40deg left or right
14  *
15  * State machine approach:
16  * Flip_Start (while copter is leaning <45deg) : roll right at 400deg/sec, increase throttle
17  * Flip_Roll (while copter is between +45deg ~ -90) : roll right at 400deg/sec, reduce throttle
18  * Flip_Recover (while copter is between -90deg and original target angle) : use earth frame angle controller to return vehicle to original attitude
19  */
20 
21 #define FLIP_THR_INC 0.20f // throttle increase during Flip_Start stage (under 45deg lean angle)
22 #define FLIP_THR_DEC 0.24f // throttle decrease during Flip_Roll stage (between 45deg ~ -90deg roll)
23 #define FLIP_ROTATION_RATE 40000 // rotation rate request in centi-degrees / sec (i.e. 400 deg/sec)
24 #define FLIP_TIMEOUT_MS 2500 // timeout after 2.5sec. Vehicle will switch back to original flight mode
25 #define FLIP_RECOVERY_ANGLE 500 // consider successful recovery when roll is back within 5 degrees of original
26 
27 #define FLIP_ROLL_RIGHT 1 // used to set flip_dir
28 #define FLIP_ROLL_LEFT -1 // used to set flip_dir
29 
30 #define FLIP_PITCH_BACK 1 // used to set flip_dir
31 #define FLIP_PITCH_FORWARD -1 // used to set flip_dir
32 
33 // FIXME? these should be instance variables?
34 FlipState flip_state; // current state of flip
35 control_mode_t flip_orig_control_mode; // flight mode when flip was initated
36 uint32_t flip_start_time; // time since flip began
37 int8_t flip_roll_dir; // roll direction (-1 = roll left, 1 = roll right)
38 int8_t flip_pitch_dir; // pitch direction (-1 = pitch forward, 1 = pitch back)
39 
40 // flip_init - initialise flip controller
41 bool Copter::ModeFlip::init(bool ignore_checks)
42 {
43  // only allow flip from ACRO, Stabilize, AltHold or Drift flight modes
44  if (copter.control_mode != ACRO &&
45  copter.control_mode != STABILIZE &&
46  copter.control_mode != ALT_HOLD &&
47  copter.control_mode != FLOWHOLD) {
48  return false;
49  }
50 
51  // if in acro or stabilize ensure throttle is above zero
52  if (ap.throttle_zero && (copter.control_mode == ACRO || copter.control_mode == STABILIZE)) {
53  return false;
54  }
55 
56  // ensure roll input is less than 40deg
57  if (abs(channel_roll->get_control_in()) >= 4000) {
58  return false;
59  }
60 
61  // only allow flip when flying
62  if (!motors->armed() || ap.land_complete) {
63  return false;
64  }
65 
66  // capture original flight mode so that we can return to it after completion
67  flip_orig_control_mode = copter.control_mode;
68 
69  // initialise state
72 
74 
75  // choose direction based on pilot's roll and pitch sticks
76  if (channel_pitch->get_control_in() > 300) {
78  } else if (channel_pitch->get_control_in() < -300) {
80  } else if (channel_roll->get_control_in() >= 0) {
82  } else {
84  }
85 
86  // log start of flip
88 
89  // capture current attitude which will be used during the Flip_Recovery stage
90  float angle_max = copter.aparm.angle_max;
91  flip_orig_attitude.x = constrain_float(ahrs.roll_sensor, -angle_max, angle_max);
92  flip_orig_attitude.y = constrain_float(ahrs.pitch_sensor, -angle_max, angle_max);
94 
95  return true;
96 }
97 
98 // flip_run - runs the flip controller
99 // should be called at 100hz or more
101 {
102  float throttle_out;
103  float recovery_angle;
104 
105  // if pilot inputs roll > 40deg or timeout occurs abandon flip
106  if (!motors->armed() || (abs(channel_roll->get_control_in()) >= 4000) || (abs(channel_pitch->get_control_in()) >= 4000) || ((millis() - flip_start_time) > FLIP_TIMEOUT_MS)) {
108  }
109 
110  // get pilot's desired throttle
112 
113  // get corrected angle based on direction and axis of rotation
114  // we flip the sign of flip_angle to minimize the code repetition
115  int32_t flip_angle;
116 
117  if (flip_roll_dir != 0) {
118  flip_angle = ahrs.roll_sensor * flip_roll_dir;
119  } else {
120  flip_angle = ahrs.pitch_sensor * flip_pitch_dir;
121  }
122 
123  // state machine
124  switch (flip_state) {
125 
126  case Flip_Start:
127  // under 45 degrees request 400deg/sec roll or pitch
128  attitude_control->input_rate_bf_roll_pitch_yaw(FLIP_ROTATION_RATE * flip_roll_dir, FLIP_ROTATION_RATE * flip_pitch_dir, 0.0);
129 
130  // increase throttle
131  throttle_out += FLIP_THR_INC;
132 
133  // beyond 45deg lean angle move to next stage
134  if (flip_angle >= 4500) {
135  if (flip_roll_dir != 0) {
136  // we are rolling
138  } else {
139  // we are pitching
141  }
142  }
143  break;
144 
145  case Flip_Roll:
146  // between 45deg ~ -90deg request 400deg/sec roll
147  attitude_control->input_rate_bf_roll_pitch_yaw(FLIP_ROTATION_RATE * flip_roll_dir, 0.0, 0.0);
148  // decrease throttle
149  throttle_out = MAX(throttle_out - FLIP_THR_DEC, 0.0f);
150 
151  // beyond -90deg move on to recovery
152  if ((flip_angle < 4500) && (flip_angle > -9000)) {
154  }
155  break;
156 
157  case Flip_Pitch_A:
158  // between 45deg ~ -90deg request 400deg/sec pitch
159  attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, FLIP_ROTATION_RATE * flip_pitch_dir, 0.0);
160  // decrease throttle
161  throttle_out = MAX(throttle_out - FLIP_THR_DEC, 0.0f);
162 
163  // check roll for inversion
164  if ((labs(ahrs.roll_sensor) > 9000) && (flip_angle > 4500)) {
166  }
167  break;
168 
169  case Flip_Pitch_B:
170  // between 45deg ~ -90deg request 400deg/sec pitch
171  attitude_control->input_rate_bf_roll_pitch_yaw(0.0, FLIP_ROTATION_RATE * flip_pitch_dir, 0.0);
172  // decrease throttle
173  throttle_out = MAX(throttle_out - FLIP_THR_DEC, 0.0f);
174 
175  // check roll for inversion
176  if ((labs(ahrs.roll_sensor) < 9000) && (flip_angle > -4500)) {
178  }
179  break;
180 
181  case Flip_Recover:
182  // use originally captured earth-frame angle targets to recover
183  attitude_control->input_euler_angle_roll_pitch_yaw(flip_orig_attitude.x, flip_orig_attitude.y, flip_orig_attitude.z, false);
184 
185  // increase throttle to gain any lost altitude
186  throttle_out += FLIP_THR_INC;
187 
188  if (flip_roll_dir != 0) {
189  // we are rolling
190  recovery_angle = fabsf(flip_orig_attitude.x - (float)ahrs.roll_sensor);
191  } else {
192  // we are pitching
193  recovery_angle = fabsf(flip_orig_attitude.y - (float)ahrs.pitch_sensor);
194  }
195 
196  // check for successful recovery
197  if (fabsf(recovery_angle) <= FLIP_RECOVERY_ANGLE) {
198  // restore original flight mode
200  // this should never happen but just in case
202  }
203  // log successful completion
205  }
206  break;
207 
208  case Flip_Abandon:
209  // restore original flight mode
211  // this should never happen but just in case
213  }
214  // log abandoning flip
216  break;
217  }
218 
219  // set motors to full range
220  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
221 
222  // output pilot's throttle without angle boost
223  attitude_control->set_throttle_out(throttle_out, false, g.throttle_filt);
224 }
void run() override
Definition: mode_flip.cpp:100
bool init(bool ignore_checks) override
Definition: mode_flip.cpp:41
control_mode_t
Definition: defines.h:91
#define FLIP_RECOVERY_ANGLE
Definition: mode_flip.cpp:25
AP_Float throttle_filt
Definition: Parameters.h:386
#define DATA_FLIP_END
Definition: defines.h:347
void Log_Write_Event(uint8_t id)
Definition: mode.cpp:592
#define FLIP_PITCH_BACK
Definition: mode_flip.cpp:30
#define FLIP_ROLL_RIGHT
Definition: mode_flip.cpp:27
Vector3f flip_orig_attitude
Definition: Copter.h:654
int8_t flip_pitch_dir
Definition: mode_flip.cpp:38
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
int8_t flip_roll_dir
Definition: mode_flip.cpp:37
int32_t roll_sensor
#define FLIP_PITCH_FORWARD
Definition: mode_flip.cpp:31
int16_t get_control_in() const
Definition: defines.h:93
int32_t pitch_sensor
#define f(i)
uint32_t millis()
#define FLIP_ROLL_LEFT
Definition: mode_flip.cpp:28
FlipState flip_state
Definition: mode_flip.cpp:34
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
Definition: mode.cpp:563
DESIRED_THROTTLE_UNLIMITED
#define FLIP_THR_INC
Definition: mode_flip.cpp:21
RC_Channel *& channel_roll
Definition: Copter.h:125
#define ERROR_CODE_FLIP_ABANDONED
Definition: defines.h:434
#define ERROR_SUBSYSTEM_FLIP
Definition: defines.h:405
float constrain_float(const float amt, const float low, const float high)
MOTOR_CLASS *& motors
Definition: Copter.h:124
control_mode_t flip_orig_control_mode
Definition: mode_flip.cpp:35
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
uint32_t flip_start_time
Definition: mode_flip.cpp:36
#define DATA_FLIP_START
Definition: defines.h:346
#define FLIP_TIMEOUT_MS
Definition: mode_flip.cpp:24
AP_AHRS & ahrs
Definition: Copter.h:122
#define FLIP_ROTATION_RATE
Definition: mode_flip.cpp:23
FlipState
Definition: defines.h:259
int32_t yaw_sensor
Parameters & g
Definition: Copter.h:116
RC_Channel *& channel_throttle
Definition: Copter.h:127
RC_Channel *& channel_pitch
Definition: Copter.h:126
#define FLIP_THR_DEC
Definition: mode_flip.cpp:22