ACM : Attitude.pde added ap bitfield for failsafe bit

This commit is contained in:
Jason Short 2012-11-09 21:42:40 -08:00
parent a42c6bb609
commit 3c78c4a7a3

View File

@ -161,7 +161,7 @@ get_roll_rate_stabilized_ef(int32_t stick_angle)
angle_error = constrain(angle_error, -MAX_ROLL_OVERSHOOT, MAX_ROLL_OVERSHOOT);
}
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !failsafe)) {
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !ap.failsafe)) {
angle_error = 0;
}
@ -197,7 +197,7 @@ get_pitch_rate_stabilized_ef(int32_t stick_angle)
angle_error = constrain(angle_error, -MAX_PITCH_OVERSHOOT, MAX_PITCH_OVERSHOOT);
}
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !failsafe)) {
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !ap.failsafe)) {
angle_error = 0;
}
@ -228,7 +228,7 @@ get_yaw_rate_stabilized_ef(int32_t stick_angle)
// limit the maximum overshoot
angle_error = constrain(angle_error, -MAX_YAW_OVERSHOOT, MAX_YAW_OVERSHOOT);
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !failsafe)) {
if (motors.armed() == false || ((g.rc_3.control_in == 0) && !ap.failsafe)) {
angle_error = 0;
}