mirror of https://github.com/ArduPilot/ardupilot
Copter: always allocate a motors backend
this allows autotest to run, and gives a less confusing error to users when no FRAME_CLASS error is selected
This commit is contained in:
parent
7a3c4fd2ee
commit
3fe1a69a32
|
@ -542,6 +542,7 @@ void Copter::allocate_motors(void)
|
||||||
case AP_Motors::MOTOR_FRAME_Y6:
|
case AP_Motors::MOTOR_FRAME_Y6:
|
||||||
case AP_Motors::MOTOR_FRAME_OCTA:
|
case AP_Motors::MOTOR_FRAME_OCTA:
|
||||||
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
|
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
|
||||||
|
default:
|
||||||
motors = new AP_MotorsMatrix(MAIN_LOOP_RATE);
|
motors = new AP_MotorsMatrix(MAIN_LOOP_RATE);
|
||||||
break;
|
break;
|
||||||
case AP_Motors::MOTOR_FRAME_TRI:
|
case AP_Motors::MOTOR_FRAME_TRI:
|
||||||
|
@ -555,11 +556,10 @@ void Copter::allocate_motors(void)
|
||||||
break;
|
break;
|
||||||
#else // FRAME_CONFIG == HELI_FRAME
|
#else // FRAME_CONFIG == HELI_FRAME
|
||||||
case AP_Motors::MOTOR_FRAME_HELI:
|
case AP_Motors::MOTOR_FRAME_HELI:
|
||||||
|
default:
|
||||||
motors = new AP_MotorsHeli_Single(MAIN_LOOP_RATE);
|
motors = new AP_MotorsHeli_Single(MAIN_LOOP_RATE);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
if (motors == nullptr) {
|
if (motors == nullptr) {
|
||||||
AP_HAL::panic("Unable to allocate FRAME_CLASS=%u", (unsigned)g2.frame_class.get());
|
AP_HAL::panic("Unable to allocate FRAME_CLASS=%u", (unsigned)g2.frame_class.get());
|
||||||
|
|
Loading…
Reference in New Issue