AP_Vehicle: Added method to takeoff for use by external control
[ardupilot.git] / ArduCopter / mode_stabilize.cpp
blob301bf991f4dac36dabdace1e5f7aa448c156dc84
1 #include "Copter.h"
3 /*
4 * Init and run calls for stabilize flight mode
5 */
7 // stabilize_run - runs the main stabilize controller
8 // should be called at 100hz or more
9 void ModeStabilize::run()
11 // apply simple mode transform to pilot inputs
12 update_simple_mode();
14 // convert pilot input to lean angles
15 float target_roll, target_pitch;
16 get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
18 // get pilot's desired yaw rate
19 float target_yaw_rate = get_pilot_desired_yaw_rate();
21 if (!motors->armed()) {
22 // Motors should be Stopped
23 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
24 } else if (copter.ap.throttle_zero
25 || (copter.air_mode == AirMode::AIRMODE_ENABLED && motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN)) {
26 // throttle_zero is never true in air mode, but the motors should be allowed to go through ground idle
27 // in order to facilitate the spoolup block
29 // Attempting to Land
30 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
31 } else {
32 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
35 float pilot_desired_throttle = get_pilot_desired_throttle();
37 switch (motors->get_spool_state()) {
38 case AP_Motors::SpoolState::SHUT_DOWN:
39 // Motors Stopped
40 attitude_control->reset_yaw_target_and_rate();
41 attitude_control->reset_rate_controller_I_terms();
42 pilot_desired_throttle = 0.0f;
43 break;
45 case AP_Motors::SpoolState::GROUND_IDLE:
46 // Landed
47 attitude_control->reset_yaw_target_and_rate();
48 attitude_control->reset_rate_controller_I_terms_smoothly();
49 pilot_desired_throttle = 0.0f;
50 break;
52 case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
53 // clear landing flag above zero throttle
54 if (!motors->limit.throttle_lower) {
55 set_land_complete(false);
57 break;
59 case AP_Motors::SpoolState::SPOOLING_UP:
60 case AP_Motors::SpoolState::SPOOLING_DOWN:
61 // do nothing
62 break;
65 // call attitude controller
66 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
68 // output pilot's throttle
69 attitude_control->set_throttle_out(pilot_desired_throttle, true, g.throttle_filt);