Copter: fixed var table loading for heli single parms

we were not loading parameters such as the swash angle
This commit is contained in:
Andrew Tridgell 2017-03-14 22:13:01 +11:00 committed by Randy Mackay
parent 132979b12f
commit 54b852ebfe
1 changed files with 1 additions and 1 deletions

View File

@ -572,7 +572,7 @@ void Copter::allocate_motors(void)
case AP_Motors::MOTOR_FRAME_HELI:
default:
motors = new AP_MotorsHeli_Single(MAIN_LOOP_RATE);
var_info = AP_MotorsHeli::var_info;
var_info = AP_MotorsHeli_Single::var_info;
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
break;
#endif