AP_MotorsHeli: output_min uses new move_actuators in -1 to +1 range

This commit is contained in:
Randy Mackay 2016-02-02 21:31:44 +09:00
parent 1197a439af
commit a18722a2fc
1 changed files with 1 additions and 1 deletions

View File

@ -186,7 +186,7 @@ void AP_MotorsHeli::Init()
void AP_MotorsHeli::output_min()
{
// move swash to mid
move_actuators(0,0,500,0);
move_actuators(0.0f,0.0f,0.5f,0.0f);
update_motor_control(ROTOR_CONTROL_STOP);