diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index ba83e14f16..bb73cc09ca 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -695,8 +695,8 @@ bool QuadPlane::setup(void) tilt.tilt_mask.set(0); } rotation = ROTATION_PITCH_90; - motors = new AP_MotorsMatrixTS(plane.scheduler.get_loop_rate_hz(), rc_speed); - motors_var_info = AP_MotorsMatrixTS::var_info; + motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz(), rc_speed); + motors_var_info = AP_MotorsMatrix::var_info; } const static char *strUnableToAllocate = "Unable to allocate";