AP_MotorsHeli_Single: remove roll_scalar, pitch_scalar

This commit is contained in:
Randy Mackay 2016-02-03 14:34:01 +09:00
parent 756236af35
commit 27fed39671
1 changed files with 0 additions and 4 deletions

View File

@ -240,10 +240,6 @@ void AP_MotorsHeli_Single::calculate_scalars()
// calculate collective mid point as a number from 0 to 1000
_collective_mid_pwm = ((float)(_collective_mid-_collective_min))/((float)(_collective_max-_collective_min))*1000.0f;
// determine roll, pitch and collective input scaling
_roll_scaler = (float)_cyclic_max/4500.0f;
_pitch_scaler = (float)_cyclic_max/4500.0f;
// calculate factors based on swash type and servo position
calculate_roll_pitch_collective_factors();