diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index 84bbbbddc4..783e953693 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -22,11 +22,15 @@ #include #include -#if !defined(NUM_SERVO_CHANNELS) && defined(HAL_BUILD_AP_PERIPH) && defined(HAL_PWM_COUNT) && (HAL_PWM_COUNT >= 1) +#ifndef NUM_SERVO_CHANNELS +#if defined(HAL_BUILD_AP_PERIPH) && defined(HAL_PWM_COUNT) #define NUM_SERVO_CHANNELS HAL_PWM_COUNT +#elif defined(HAL_BUILD_AP_PERIPH) + #define NUM_SERVO_CHANNELS 0 #else #define NUM_SERVO_CHANNELS 16 #endif +#endif class SRV_Channels; @@ -475,7 +479,11 @@ public: static AP_HAL::RCOutput::DshotEscType get_dshot_esc_type() { return AP_HAL::RCOutput::DshotEscType(_singleton->dshot_esc_type.get()); } static SRV_Channel *srv_channel(uint8_t i) { +#if NUM_SERVO_CHANNELS > 0 return i #include +#if NUM_SERVO_CHANNELS == 0 +#pragma GCC diagnostic ignored "-Wtype-limits" +#endif + extern const AP_HAL::HAL& hal; /// map a function to a servo channel and output it diff --git a/libraries/SRV_Channel/SRV_Channels.cpp b/libraries/SRV_Channel/SRV_Channels.cpp index 2caf570a08..1c83d78296 100644 --- a/libraries/SRV_Channel/SRV_Channels.cpp +++ b/libraries/SRV_Channel/SRV_Channels.cpp @@ -34,6 +34,10 @@ #include #endif +#if NUM_SERVO_CHANNELS == 0 +#pragma GCC diagnostic ignored "-Wtype-limits" +#endif + extern const AP_HAL::HAL& hal; SRV_Channel *SRV_Channels::channels;