AP_Motors: clamp max-num-motors to num-servo-channels

This commit is contained in:
Peter Barker 2025-01-23 19:10:48 +11:00 committed by Peter Barker
parent dfe0a559d3
commit afaed41d6e

View File

@ -6,6 +6,7 @@
#include <Filter/DerivativeFilter.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Logger/AP_Logger_config.h>
#include <SRV_Channel/SRV_Channel_config.h>
// 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