Copter: update_thr_cruise removed from control_stabilize

This commit is contained in:
Randy Mackay 2014-02-03 14:06:29 +09:00 committed by Andrew Tridgell
parent 223c6fd4de
commit aedb4136de
2 changed files with 0 additions and 6 deletions

View File

@ -61,7 +61,4 @@ static void stabilize_run()
control_roll = angle_target.x;
control_pitch = angle_target.y;
control_yaw = angle_target.z;
// update estimate of throttle cruise
update_throttle_cruise(pilot_throttle_scaled);
}

View File

@ -47,9 +47,6 @@ static void heli_stabilize_run()
control_roll = angle_target.x;
control_pitch = angle_target.y;
control_yaw = angle_target.z;
// update estimate of throttle cruise
update_throttle_cruise(motors.get_collective_out());
}
#endif //HELI_FRAME