diff --git a/ArduCopter/heli_control_acro.cpp b/ArduCopter/heli_control_acro.cpp index 4200a181ce..535c7bdf73 100644 --- a/ArduCopter/heli_control_acro.cpp +++ b/ArduCopter/heli_control_acro.cpp @@ -27,7 +27,7 @@ bool Copter::heli_acro_init(bool ignore_checks) void Copter::heli_acro_run() { float target_roll, target_pitch, target_yaw; - int16_t pilot_throttle_scaled; + float pilot_throttle_scaled; // Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because // we may be in autorotation flight. These should be reset only when transitioning from disarmed diff --git a/ArduCopter/heli_control_stabilize.cpp b/ArduCopter/heli_control_stabilize.cpp index 3f3c0ed166..9936036512 100644 --- a/ArduCopter/heli_control_stabilize.cpp +++ b/ArduCopter/heli_control_stabilize.cpp @@ -26,7 +26,7 @@ void Copter::heli_stabilize_run() { float target_roll, target_pitch; float target_yaw_rate; - int16_t pilot_throttle_scaled; + float pilot_throttle_scaled; // Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because // we may be in autorotation flight. These should be reset only when transitioning from disarmed