AP_Vehicle: Added method to takeoff for use by external control
[ardupilot.git] / ArduCopter / standby.cpp
blobd7c3562491a8bd29f094af99797bb42c18ceaf22
1 #include "Copter.h"
3 // Run standby functions at approximately 100 Hz to limit maximum variable build up
4 //
5 // When standby is active:
6 // all I terms are continually reset
7 // heading error is reset to zero
8 // position errors are reset to zero
9 // crash_check is disabled
10 // thrust_loss_check is disabled
11 // parachute_check is disabled
12 // hover throttle learn is disabled
13 // and landing detection is disabled.
14 void Copter::standby_update()
16 if (!standby_active) {
17 return;
20 attitude_control->reset_rate_controller_I_terms();
21 attitude_control->reset_yaw_target_and_rate();
22 pos_control->standby_xyz_reset();