AP_Radio: tidy AP_Radio includes

This commit is contained in:
Peter Barker 2024-02-01 16:45:16 +11:00 committed by Peter Barker
parent 0d26118b12
commit 49b4a74641
12 changed files with 87 additions and 37 deletions

View File

@ -1,6 +1,8 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_Radio_config.h"
#if HAL_RCINPUT_WITH_AP_RADIO
#if AP_RADIO_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "AP_Radio.h"
#include "AP_Radio_backend.h"
@ -151,40 +153,36 @@ AP_Radio::AP_Radio(void)
bool AP_Radio::init(void)
{
switch (radio_type) {
#if (not defined AP_RADIO_CYRF6936 || AP_RADIO_CYRF6936)
#if AP_RADIO_CYRF6936_ENABLED
case RADIO_TYPE_CYRF6936:
driver = new AP_Radio_cypress(*this);
break;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#if (not defined AP_RADIO_CC2500 || AP_RADIO_CC2500)
#if AP_RADIO_CC2500_ENABLED
case RADIO_TYPE_CC2500:
driver = new AP_Radio_cc2500(*this);
break;
#endif
#endif
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
#if (not defined AP_RADIO_BK2425 || AP_RADIO_BK2425)
#if AP_RADIO_BK2425_ENABLED
case RADIO_TYPE_BK2425:
driver = new AP_Radio_beken(*this);
break;
#endif
#endif
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
case RADIO_TYPE_AUTO:
// auto-detect between cc2500 and beken radios
#if (not defined AP_RADIO_CC2500 || AP_RADIO_CC2500)
#if AP_RADIO_CC2500_ENABLED
if (AP_Radio_cc2500::probe()) {
driver = new AP_Radio_cc2500(*this);
}
#endif
#if (not defined AP_RADIO_BK2425 || AP_RADIO_BK2425)
#if AP_RADIO_BK2425_ENABLED
if (driver == nullptr) {
driver = new AP_Radio_beken(*this);
}
#endif
break;
#endif
#endif // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
default:
break;
}
@ -301,5 +299,4 @@ void AP_Radio::change_txmode(void)
}
}
#endif // HAL_RCINPUT_WITH_AP_RADIO
#endif // AP_RADIO_ENABLED

View File

@ -14,6 +14,10 @@
*/
#pragma once
#include "AP_Radio_config.h"
#if AP_RADIO_ENABLED
/*
* base class for direct attached radios
*/
@ -128,3 +132,5 @@ private:
static AP_Radio *_singleton;
};
#endif // AP_RADIO_ENABLED

View File

@ -16,6 +16,10 @@
* backend class for direct attached radios
*/
#include "AP_Radio_config.h"
#if AP_RADIO_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "AP_Radio_backend.h"
@ -27,3 +31,5 @@ AP_Radio_backend::AP_Radio_backend(AP_Radio &_radio) :
AP_Radio_backend::~AP_Radio_backend(void)
{
}
#endif // AP_RADIO_ENABLED

View File

@ -14,6 +14,10 @@
*/
#pragma once
#include "AP_Radio_config.h"
#if AP_RADIO_ENABLED
/*
* backend class for direct attached radios
*/
@ -156,3 +160,5 @@ protected:
AP_Radio &radio;
};
#endif // AP_RADIO_ENABLED

View File

@ -1,3 +1,7 @@
#include "AP_Radio_config.h"
#if AP_RADIO_BK2425_ENABLED
/*
driver for Beken_2425 radio
*/
@ -5,8 +9,6 @@
//#pragma GCC optimize("O0")
#if defined(HAL_RCINPUT_WITH_AP_RADIO) && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
#include <AP_Math/AP_Math.h>
#include "AP_Radio_bk2425.h"
#include <utility>
@ -1421,7 +1423,4 @@ void SyncAdaptive::Miss(uint8_t channel)
}
}
#endif // HAL_RCINPUT_WITH_AP_RADIO
#endif // AP_RADIO_BK2425_ENABLED

View File

@ -20,9 +20,12 @@
With thanks to cleanflight and betaflight projects
*/
#include "AP_Radio_config.h"
#if AP_RADIO_BK2425_ENABLED
#include "AP_Radio_backend.h"
#if defined(HAL_RCINPUT_WITH_AP_RADIO) && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
#include "hal.h"
#include "telem_structure.h"
#include "driver_bk2425.h"
@ -258,4 +261,4 @@ private:
uint8_t myDroneId[4]; // CRC of the flight boards UUID, to inform the tx
};
#endif // HAL_RCINPUT_WITH_AP_RADIO
#endif // AP_RADIO_BK2425_ENABLED

View File

@ -20,8 +20,12 @@
With thanks to cleanflight and betaflight projects
*/
#include "AP_Radio_config.h"
#if AP_RADIO_CC2500_ENABLED
#include "AP_Radio_backend.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include "hal.h"
#include "telem_structure.h"
#include "driver_cc2500.h"
@ -226,5 +230,4 @@ private:
};
#endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#endif // AP_RADIO_CC2500_ENABLED

View File

@ -0,0 +1,23 @@
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef AP_RADIO_ENABLED
#define AP_RADIO_ENABLED HAL_RCINPUT_WITH_AP_RADIO
#endif
#ifndef AP_RADIO_BACKEND_DEFAULT_ENABLED
#define AP_RADIO_BACKEND_DEFAULT_ENABLED AP_RADIO_ENABLED
#endif
#ifndef AP_RADIO_CC2500_ENABLED
#define AP_RADIO_CC2500_ENABLED AP_RADIO_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_RADIO_CYRF6936_ENABLED
#define AP_RADIO_CYRF6936_ENABLED AP_RADIO_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_RADIO_BK2425_ENABLED
#define AP_RADIO_BK2425_ENABLED AP_RADIO_BACKEND_DEFAULT_ENABLED
#endif

View File

@ -1,6 +1,8 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_Radio_config.h"
#if HAL_RCINPUT_WITH_AP_RADIO
#if AP_RADIO_CYRF6936_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include "AP_Radio_cypress.h"
@ -1681,5 +1683,4 @@ void AP_Radio_cypress::handle_data_packet(mavlink_channel_t chan, const mavlink_
}
}
#endif // HAL_RCINPUT_WITH_AP_RADIO
#endif // AP_RADIO_CYRF6936_ENABLED

View File

@ -14,7 +14,9 @@
*/
#pragma once
#if HAL_RCINPUT_WITH_AP_RADIO
#include "AP_Radio_config.h"
#if AP_RADIO_CYRF6936_ENABLED
/*
AP_Radio implementation for Cypress 2.4GHz radio.
@ -279,4 +281,4 @@ private:
void setup_timeout(uint32_t timeout_ms);
};
#endif
#endif // AP_RADIO_CYRPRESS_ENABLED

View File

@ -1,11 +1,13 @@
#include "AP_Radio_config.h"
#if AP_RADIO_BK2425_ENABLED
// --------------------------------------------------------------------
// low level driver for the beken radio on SPI
// --------------------------------------------------------------------
#include "driver_bk2425.h"
#if defined(HAL_RCINPUT_WITH_AP_RADIO) && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
#include <utility>
#include <AP_HAL_ChibiOS/AP_HAL_ChibiOS.h>
using namespace ChibiOS;
@ -722,4 +724,4 @@ void Radio_Beken::DumpRegisters(void)
SetRBank(0);
}
#endif // HAL_RCINPUT_WITH_AP_RADIO
#endif // AP_RADIO_BK2425_ENABLED

View File

@ -6,9 +6,11 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#include "AP_Radio_config.h"
#if defined(HAL_RCINPUT_WITH_AP_RADIO) && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
#if AP_RADIO_BK2425_ENABLED
#include <AP_HAL/AP_HAL.h>
#define SUPPORT_BK_DEBUG_PINS 0 // 0=UART6 is for GPS, 1=UART6 is debug gpio
#define TX_SPEED 250u // Default transmit speed in kilobits per second.
@ -414,4 +416,4 @@ private:
BkRadioMode bkMode;
};
#endif
#endif // AP_RADIO_BK2425_ENABLED