mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 07:53:57 -04:00
AP_Periph: support 32 motors in a frame
This commit is contained in:
parent
405b067df6
commit
3b8d1d23dd
@ -25,7 +25,9 @@
|
||||
#define UAVCAN_ESC_MAX_VALUE 8191
|
||||
|
||||
#define SERVO_OUT_RCIN_MAX 32 // note that we allow for more than is in the enum
|
||||
#define SERVO_OUT_MOTOR_MAX 12 // SRV_Channel::k_motor1 ... SRV_Channel::k_motor8, SRV_Channel::k_motor9 ... SRV_Channel::k_motor12
|
||||
#ifndef SERVO_OUT_MOTOR_MAX
|
||||
#define SERVO_OUT_MOTOR_MAX 32 // SRV_Channel::k_motor1 ... SRV_Channel::k_motor8, SRV_Channel::k_motor9 ... SRV_Channel::k_motor12, SRV_Channel::k_motor13 ... SRV_Channel::k_motor32
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user