From afaed41d6ed3327f2e6ce02aea597bc3c2187570 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 23 Jan 2025 19:10:48 +1100 Subject: [PATCH] AP_Motors: clamp max-num-motors to num-servo-channels --- libraries/AP_Motors/AP_Motors_Class.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 775d073db3..58f45a7301 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -6,6 +6,7 @@ #include #include #include +#include // offsets for motors in motor_out and _motor_filtered arrays #define AP_MOTORS_MOT_1 0U @@ -47,6 +48,12 @@ #else #define AP_MOTORS_MAX_NUM_MOTORS 12 #endif + +// doesn't make sense to have more motors than servo channels, so clamp: +#if NUM_SERVO_CHANNELS < AP_MOTORS_MAX_NUM_MOTORS +#undef AP_MOTORS_MAX_NUM_MOTORS +#define AP_MOTORS_MAX_NUM_MOTORS NUM_SERVO_CHANNELS +#endif #endif #ifndef AP_MOTORS_FRAME_DEFAULT_ENABLED