From 1685ff274d1116eab38f17d70b698cf752abbe8c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 11 Jul 2013 22:33:55 +0900 Subject: [PATCH] TradHeli: compile error fix related to new ACRO The motors_runup_complete must be a feature that Rob has implemented in his clone which has not yet reached master. We will need to restore these lost few trad-heli specific lines once Rob's changes make it to master. --- ArduCopter/Attitude.pde | 36 +++++++++--------------------------- 1 file changed, 9 insertions(+), 27 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index b217619df0..42ee2edc59 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -124,15 +124,9 @@ get_roll_rate_stabilized_bf(int32_t stick_angle) // don't let angle error grow too large angle_error = constrain_float(angle_error, - MAX_ROLL_OVERSHOOT, MAX_ROLL_OVERSHOOT); - #if FRAME_CONFIG == HELI_FRAME - if (!motors.motor_runup_complete) { - angle_error = 0; - } - #else - if (!motors.armed() || g.rc_3.servo_out == 0) { - angle_error = 0; - } - #endif // HELI_FRAME + if (!motors.armed() || g.rc_3.servo_out == 0) { + angle_error = 0; + } // set body frame targets for rate controller set_roll_rate_target(roll_axis + correction_rate, BODY_FRAME); @@ -180,15 +174,9 @@ get_pitch_rate_stabilized_bf(int32_t stick_angle) // don't let angle error grow too large angle_error = constrain_float(angle_error, - MAX_PITCH_OVERSHOOT, MAX_PITCH_OVERSHOOT); - #if FRAME_CONFIG == HELI_FRAME - if (!motors.motor_runup_complete) { - angle_error = 0; - } - #else - if (!motors.armed() || g.rc_3.servo_out == 0) { - angle_error = 0; - } - #endif // HELI_FRAME + if (!motors.armed() || g.rc_3.servo_out == 0) { + angle_error = 0; + } // set body frame targets for rate controller set_pitch_rate_target(pitch_axis + correction_rate, BODY_FRAME); @@ -236,15 +224,9 @@ get_yaw_rate_stabilized_bf(int32_t stick_angle) // don't let angle error grow too large angle_error = constrain_float(angle_error, - MAX_YAW_OVERSHOOT, MAX_YAW_OVERSHOOT); - #if FRAME_CONFIG == HELI_FRAME - if (!motors.motor_runup_complete) { - angle_error = 0; - } - #else - if (!motors.armed() || g.rc_3.servo_out == 0) { - angle_error = 0; - } - #endif // HELI_FRAME + if (!motors.armed() || g.rc_3.servo_out == 0) { + angle_error = 0; + } // set body frame targets for rate controller set_yaw_rate_target(nav_yaw + correction_rate, BODY_FRAME);