APM:Copter
takeoff.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // This file contains the high-level takeoff logic for Loiter, PosHold, AltHold, Sport modes.
4 // The take-off can be initiated from a GCS NAV_TAKEOFF command which includes a takeoff altitude
5 // A safe takeoff speed is calculated and used to calculate a time_ms
6 // the pos_control target is then slowly increased until time_ms expires
7 
8 // return true if this flight mode supports user takeoff
9 // must_nagivate is true if mode must also control horizontal position
10 bool Copter::current_mode_has_user_takeoff(bool must_navigate)
11 {
12  switch (control_mode) {
13  case GUIDED:
14  case LOITER:
15  case POSHOLD:
16  return true;
17  case ALT_HOLD:
18  case SPORT:
19  case FLOWHOLD:
20  return !must_navigate;
21  default:
22  return false;
23  }
24 }
25 
26 // initiate user takeoff - called when MAVLink TAKEOFF command is received
27 bool Copter::do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
28 {
29  if (motors->armed() && ap.land_complete && current_mode_has_user_takeoff(must_navigate) && takeoff_alt_cm > current_loc.alt) {
30 
31 #if FRAME_CONFIG == HELI_FRAME
32  // Helicopters should return false if MAVlink takeoff command is received while the rotor is not spinning
33  if (!motors->rotor_runup_complete()) {
34  return false;
35  }
36 #endif
37 
38  switch(control_mode) {
39 #if MODE_GUIDED_ENABLED == ENABLED
40  case GUIDED:
41  if (mode_guided.takeoff_start(takeoff_alt_cm)) {
42  set_auto_armed(true);
43  return true;
44  }
45  return false;
46 #endif
47  case LOITER:
48  case POSHOLD:
49  case ALT_HOLD:
50  case SPORT:
51  case FLOWHOLD:
52  set_auto_armed(true);
53  takeoff_timer_start(takeoff_alt_cm);
54  return true;
55  default:
56  return false;
57  }
58  }
59  return false;
60 }
61 
62 // start takeoff to specified altitude above home in centimeters
64 {
65  // calculate climb rate
66  float speed = MIN(wp_nav->get_speed_up(), MAX(g.pilot_speed_up*2.0f/3.0f, g.pilot_speed_up-50.0f));
67 
68  // sanity check speed and target
69  if (takeoff_state.running || speed <= 0.0f || alt_cm <= 0.0f) {
70  return;
71  }
72 
73  // initialise takeoff state
74  takeoff_state.running = true;
75  takeoff_state.max_speed = speed;
78 }
79 
80 // stop takeoff
82 {
83  takeoff_state.running = false;
85 }
86 
87 // returns pilot and takeoff climb rates
88 // pilot_climb_rate is both an input and an output
89 // takeoff_climb_rate is only an output
90 // has side-effect of turning takeoff off when timeout as expired
91 void Copter::takeoff_get_climb_rates(float& pilot_climb_rate, float& takeoff_climb_rate)
92 {
93  // return pilot_climb_rate if take-off inactive
94  if (!takeoff_state.running) {
95  takeoff_climb_rate = 0.0f;
96  return;
97  }
98 
99  // acceleration of 50cm/s/s
100  static const float takeoff_accel = 50.0f;
101  float takeoff_minspeed = MIN(50.0f,takeoff_state.max_speed);
102  float time_elapsed = (millis()-takeoff_state.start_ms)*1.0e-3f;
103  float speed = MIN(time_elapsed*takeoff_accel+takeoff_minspeed, takeoff_state.max_speed);
104 
105  float time_to_max_speed = (takeoff_state.max_speed-takeoff_minspeed)/takeoff_accel;
106  float height_gained;
107  if (time_elapsed <= time_to_max_speed) {
108  height_gained = 0.5f*takeoff_accel*sq(time_elapsed) + takeoff_minspeed*time_elapsed;
109  } else {
110  height_gained = 0.5f*takeoff_accel*sq(time_to_max_speed) + takeoff_minspeed*time_to_max_speed +
111  (time_elapsed-time_to_max_speed)*takeoff_state.max_speed;
112  }
113 
114  // check if the takeoff is over
115  if (height_gained >= takeoff_state.alt_delta) {
116  takeoff_stop();
117  }
118 
119  // if takeoff climb rate is zero return
120  if (speed <= 0.0f) {
121  takeoff_climb_rate = 0.0f;
122  return;
123  }
124 
125  // default take-off climb rate to maximum speed
126  takeoff_climb_rate = speed;
127 
128  // if pilot's commands descent
129  if (pilot_climb_rate < 0.0f) {
130  // if overall climb rate is still positive, move to take-off climb rate
131  if (takeoff_climb_rate + pilot_climb_rate > 0.0f) {
132  takeoff_climb_rate = takeoff_climb_rate + pilot_climb_rate;
133  pilot_climb_rate = 0;
134  } else {
135  // if overall is negative, move to pilot climb rate
136  pilot_climb_rate = pilot_climb_rate + takeoff_climb_rate;
137  takeoff_climb_rate = 0.0f;
138  }
139  } else { // pilot commands climb
140  // pilot climb rate is zero until it surpasses the take-off climb rate
141  if (pilot_climb_rate > takeoff_climb_rate) {
142  pilot_climb_rate = pilot_climb_rate - takeoff_climb_rate;
143  } else {
144  pilot_climb_rate = 0.0f;
145  }
146  }
147 }
148 
150 {
151  // start with our current altitude
153 
154  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock() || ap.land_complete) {
155  // we are not flying, add the wp_navalt_min
157  }
158 }
159 
160 
161 /*
162  call attitude controller for automatic takeoff, limiting roll/pitch
163  if below wp_navalt_min
164  */
165 void Copter::auto_takeoff_attitude_run(float target_yaw_rate)
166 {
167  float nav_roll, nav_pitch;
168 
170  // we haven't reached the takeoff navigation altitude yet
171  nav_roll = 0;
172  nav_pitch = 0;
173 #if FRAME_CONFIG == HELI_FRAME
174  // prevent hover roll starting till past specified altitude
175  hover_roll_trim_scalar_slew = 0;
176 #endif
177  // tell the position controller that we have limited roll/pitch demand to prevent integrator buildup
179  } else {
180  nav_roll = wp_nav->get_roll();
181  nav_pitch = wp_nav->get_pitch();
182  }
183 
184  // roll & pitch from waypoint controller, yaw rate from pilot
185  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(nav_roll, nav_pitch, target_yaw_rate);
186 }
void takeoff_stop()
Definition: takeoff.cpp:81
float auto_takeoff_no_nav_alt_cm
Definition: Copter.h:373
void set_auto_armed(bool b)
Definition: AP_State.cpp:4
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
float get_altitude() const
int32_t get_pitch() const
void takeoff_timer_start(float alt_cm)
Definition: takeoff.cpp:63
void takeoff_get_climb_rates(float &pilot_climb_rate, float &takeoff_climb_rate)
Definition: takeoff.cpp:91
ModeGuided mode_guided
Definition: Copter.h:984
AC_WPNav * wp_nav
Definition: Copter.h:494
int16_t alt_cm
Definition: Copter.h:242
void set_limit_accel_xy(void)
Definition: defines.h:96
AP_Int16 pilot_speed_up
Definition: Parameters.h:416
int32_t get_roll() const
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
Definition: defines.h:102
MOTOR_CLASS * motors
Definition: Copter.h:422
#define MIN(a, b)
void auto_takeoff_attitude_run(float target_yaw_rate)
Definition: takeoff.cpp:165
float takeoff_alt_cm
Definition: Copter.h:619
int32_t alt
#define f(i)
takeoff_state_t takeoff_state
Definition: Copter.h:370
uint32_t millis()
float get_speed_up() const
Location_Class current_loc
Definition: Copter.h:475
Definition: defines.h:97
bool do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
Definition: takeoff.cpp:27
Parameters g
Definition: Copter.h:208
bool current_mode_has_user_takeoff(bool must_navigate)
Definition: takeoff.cpp:10
void auto_takeoff_set_start_alt(void)
Definition: takeoff.cpp:149
bool takeoff_start(float final_alt_above_home)
Definition: mode_guided.cpp:54
AC_PosControl * pos_control
Definition: Copter.h:493
float sq(const T val)
ParametersG2 g2
Definition: Copter.h:209
control_mode_t control_mode
Definition: Copter.h:345
AP_Float wp_navalt_min
Definition: Parameters.h:501