mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 09:33:59 -03:00
AP_Motors: limit nax-motors to 12 unless scripting enabled
we only allow configuration of more complicated frames with scripting at the moment
This commit is contained in:
parent
9f5c095688
commit
dfe0a559d3
@ -42,7 +42,11 @@
|
||||
#define AP_MOTORS_MOT_32 31U
|
||||
|
||||
#ifndef AP_MOTORS_MAX_NUM_MOTORS
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#define AP_MOTORS_MAX_NUM_MOTORS 32
|
||||
#else
|
||||
#define AP_MOTORS_MAX_NUM_MOTORS 12
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef AP_MOTORS_FRAME_DEFAULT_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user