mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
SRV_Channel: allow build with no channels
needed for AP_Periph when using LED driver only
This commit is contained in:
parent
1a81b10d27
commit
11e4b62438
@ -22,11 +22,15 @@
|
||||
#include <AP_SBusOut/AP_SBusOut.h>
|
||||
#include <AP_BLHeli/AP_BLHeli.h>
|
||||
|
||||
#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<NUM_SERVO_CHANNELS?&channels[i]:nullptr;
|
||||
#else
|
||||
return nullptr;
|
||||
#endif
|
||||
}
|
||||
|
||||
// SERVO* parameters
|
||||
|
@ -21,6 +21,10 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
|
||||
#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
|
||||
|
@ -34,6 +34,10 @@
|
||||
#include <AP_PiccoloCAN/AP_PiccoloCAN.h>
|
||||
#endif
|
||||
|
||||
#if NUM_SERVO_CHANNELS == 0
|
||||
#pragma GCC diagnostic ignored "-Wtype-limits"
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
SRV_Channel *SRV_Channels::channels;
|
||||
|
Loading…
Reference in New Issue
Block a user