Copter: guided takeoff checks auto-armed status

This resolves an edge case in which the vehicle could takeoff with auto-armed false
This commit is contained in:
Randy Mackay 2015-10-20 15:40:24 +09:00
parent 25c5c167f7
commit 38476b9204

View File

@ -192,6 +192,18 @@ void Copter::guided_run()
// called by guided_run at 100hz or more // called by guided_run at 100hz or more
void Copter::guided_takeoff_run() void Copter::guided_takeoff_run()
{ {
// if not auto armed or motors not enabled set throttle to zero and exit immediately
if (!ap.auto_armed || !motors.get_interlock()) {
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
attitude_control.set_throttle_out(0,false,g.throttle_filt);
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif
return;
}
// process pilot's yaw input // process pilot's yaw input
float target_yaw_rate = 0; float target_yaw_rate = 0;
if (!failsafe.radio) { if (!failsafe.radio) {