AP_ESC_Telem: Use SRV_Channel_config to extract the number of expected channels available

Removes duplication of definitions of available channels

Co-authored-by: Simon Maddison <81274690+Sypaq-MadMan@users.noreply.github.com>
This commit is contained in:
James O'Shannessy 2022-11-29 20:47:28 +11:00 committed by Peter Barker
parent cd76aa3cff
commit dec9f486ed
2 changed files with 4 additions and 7 deletions

View File

@ -3,17 +3,13 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <AP_TemperatureSensor/AP_TemperatureSensor_config.h>
#include <SRV_Channel/SRV_Channel_config.h>
#include "AP_ESC_Telem_Backend.h"
#if HAL_WITH_ESC_TELEM
#ifdef NUM_SERVO_CHANNELS
#define ESC_TELEM_MAX_ESCS NUM_SERVO_CHANNELS
#elif !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024
#define ESC_TELEM_MAX_ESCS 32
#else
#define ESC_TELEM_MAX_ESCS 16
#endif
#define ESC_TELEM_MAX_ESCS NUM_SERVO_CHANNELS
static_assert(ESC_TELEM_MAX_ESCS > 0, "Cannot have 0 ESC telemetry instances");
#define ESC_TELEM_DATA_TIMEOUT_MS 5000UL
#define ESC_RPM_DATA_TIMEOUT_US 1000000UL

View File

@ -1,6 +1,7 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <SRV_Channel/SRV_Channel_config.h>
#if defined(NUM_SERVO_CHANNELS) && NUM_SERVO_CHANNELS == 0
#define HAL_WITH_ESC_TELEM 0