AP_Motors: support a minimum of 12 motors

this block could be removed if we made each backend dependent on having sAP_MOTORS_MAX_NUM_MOTORS high enough to support that frame.

However, not all frames have #ifdefs to support conditional compilation at this point.
This commit is contained in:
Peter Barker 2025-01-24 07:38:58 +11:00 committed by Peter Barker
parent afaed41d6e
commit 08bf42bf0a

View File

@ -54,8 +54,19 @@
#undef AP_MOTORS_MAX_NUM_MOTORS
#define AP_MOTORS_MAX_NUM_MOTORS NUM_SERVO_CHANNELS
#endif
// various Motors backends will not compile if we don't have 16 motors
// available (eg. AP_Motors6DOF). Until we stop compiling those
// backends in when there aren't enough motors to support those
// backends we will support a minimum of 12 motors, the limit before
// we moved to 32 motor support:
#if AP_MOTORS_MAX_NUM_MOTORS < 12
#undef AP_MOTORS_MAX_NUM_MOTORS
#define AP_MOTORS_MAX_NUM_MOTORS 12
#endif
#endif // defined (AP_MOTORS_MAX_NUM_MOTORS)
#ifndef AP_MOTORS_FRAME_DEFAULT_ENABLED
#define AP_MOTORS_FRAME_DEFAULT_ENABLED 1
#endif