mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Removed some target dependencies, and added makefile target 'check-target-independence' to find dependencies.
This commit is contained in:
parent
50ff0ddadb
commit
ede204aa81
11 changed files with 28 additions and 20 deletions
11
Makefile
11
Makefile
|
@ -473,6 +473,17 @@ targets:
|
||||||
test junittest:
|
test junittest:
|
||||||
$(V0) cd src/test && $(MAKE) $@
|
$(V0) cd src/test && $(MAKE) $@
|
||||||
|
|
||||||
|
|
||||||
|
check-target-independence:
|
||||||
|
$(V1)for test_target in $(VALID_TARGETS); do \
|
||||||
|
FOUND=$$(grep -rP "\W$${test_target}\W" src/main/ | grep -vP "(\/\/)|(\/\*).*\W$${test_target}\W" | grep -vP "^src/main/target"); \
|
||||||
|
if [ "$${FOUND}" != "" ]; then \
|
||||||
|
echo "Target dependencies found:"; \
|
||||||
|
echo "$${FOUND}"; \
|
||||||
|
exit 1; \
|
||||||
|
fi; \
|
||||||
|
done
|
||||||
|
|
||||||
# rebuild everything when makefile changes
|
# rebuild everything when makefile changes
|
||||||
$(TARGET_OBJS) : Makefile
|
$(TARGET_OBJS) : Makefile
|
||||||
|
|
||||||
|
|
|
@ -91,6 +91,6 @@ uint16_t adcInternalReadVrefint(void);
|
||||||
uint16_t adcInternalReadTempsensor(void);
|
uint16_t adcInternalReadTempsensor(void);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef SITL
|
#if !defined(SIMULATOR_BUILD)
|
||||||
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance);
|
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -74,7 +74,7 @@ void systemInit(void)
|
||||||
|
|
||||||
SetSysClock(false);
|
SetSysClock(false);
|
||||||
|
|
||||||
#ifdef CC3D
|
#if defined(OPBL)
|
||||||
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
|
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
|
||||||
extern void *isr_vector_table_base;
|
extern void *isr_vector_table_base;
|
||||||
|
|
||||||
|
|
|
@ -774,7 +774,7 @@ void timerInit(void)
|
||||||
{
|
{
|
||||||
memset(timerConfig, 0, sizeof (timerConfig));
|
memset(timerConfig, 0, sizeof (timerConfig));
|
||||||
|
|
||||||
#ifdef CC3D
|
#if defined(PARTIAL_REMAP_TIM3)
|
||||||
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
|
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -437,7 +437,7 @@ void init(void)
|
||||||
beeperInit(beeperDevConfig());
|
beeperInit(beeperDevConfig());
|
||||||
#endif
|
#endif
|
||||||
/* temp until PGs are implemented. */
|
/* temp until PGs are implemented. */
|
||||||
#if defined(USE_INVERTER) && !defined(SITL)
|
#if defined(USE_INVERTER) && !defined(SIMULATOR_BUILD)
|
||||||
initInverters(serialPinConfig());
|
initInverters(serialPinConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -782,10 +782,6 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CJMCU
|
|
||||||
LED2_ON;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_RCDEVICE
|
#ifdef USE_RCDEVICE
|
||||||
rcdeviceInit();
|
rcdeviceInit();
|
||||||
#endif // USE_RCDEVICE
|
#endif // USE_RCDEVICE
|
||||||
|
|
|
@ -238,12 +238,12 @@ FAST_CODE NOINLINE void processRcCommand(void)
|
||||||
|
|
||||||
if (isRXDataNew || updatedChannel) {
|
if (isRXDataNew || updatedChannel) {
|
||||||
const uint8_t maxUpdatedAxis = isRXDataNew ? FD_YAW : MIN(updatedChannel, FD_YAW); // throttle channel doesn't require rate calculation
|
const uint8_t maxUpdatedAxis = isRXDataNew ? FD_YAW : MIN(updatedChannel, FD_YAW); // throttle channel doesn't require rate calculation
|
||||||
#if defined(SITL)
|
#if defined(SIMULATOR_BUILD)
|
||||||
#pragma GCC diagnostic push
|
#pragma GCC diagnostic push
|
||||||
#pragma GCC diagnostic ignored "-Wunsafe-loop-optimizations"
|
#pragma GCC diagnostic ignored "-Wunsafe-loop-optimizations"
|
||||||
#endif
|
#endif
|
||||||
for (int axis = FD_ROLL; axis <= maxUpdatedAxis; axis++) {
|
for (int axis = FD_ROLL; axis <= maxUpdatedAxis; axis++) {
|
||||||
#if defined(SITL)
|
#if defined(SIMULATOR_BUILD)
|
||||||
#pragma GCC diagnostic pop
|
#pragma GCC diagnostic pop
|
||||||
#endif
|
#endif
|
||||||
calculateSetpointRate(axis);
|
calculateSetpointRate(axis);
|
||||||
|
|
|
@ -41,7 +41,7 @@
|
||||||
#include "drivers/serial_softserial.h"
|
#include "drivers/serial_softserial.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SITL
|
#if defined(SIMULATOR_BUILD)
|
||||||
#include "drivers/serial_tcp.h"
|
#include "drivers/serial_tcp.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -377,8 +377,8 @@ serialPort_t *openSerialPort(
|
||||||
#ifdef USE_UART8
|
#ifdef USE_UART8
|
||||||
case SERIAL_PORT_USART8:
|
case SERIAL_PORT_USART8:
|
||||||
#endif
|
#endif
|
||||||
#ifdef SITL
|
#if defined(SIMULATOR_BUILD)
|
||||||
// SITL emulates serial ports over TCP
|
// emulate serial ports over TCP
|
||||||
serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
|
serialPort = serTcpOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
|
||||||
#else
|
#else
|
||||||
serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
|
serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, rxCallbackData, baudRate, mode, options);
|
||||||
|
@ -446,7 +446,7 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef SITL
|
#if !defined(SIMULATOR_BUILD)
|
||||||
else if (serialPortUsageList[index].identifier <= SERIAL_PORT_USART8) {
|
else if (serialPortUsageList[index].identifier <= SERIAL_PORT_USART8) {
|
||||||
int resourceIndex = SERIAL_PORT_IDENTIFIER_TO_INDEX(serialPortUsageList[index].identifier);
|
int resourceIndex = SERIAL_PORT_IDENTIFIER_TO_INDEX(serialPortUsageList[index].identifier);
|
||||||
if (!(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
|
if (!(serialPinConfig()->ioTagTx[resourceIndex] || serialPinConfig()->ioTagRx[resourceIndex])) {
|
||||||
|
|
|
@ -185,7 +185,7 @@ void init(void)
|
||||||
busSwitchInit();
|
busSwitchInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_UART) && !defined(SITL)
|
#if defined(USE_UART) && !defined(SIMULATOR_BUILD)
|
||||||
uartPinConfigure(serialPinConfig());
|
uartPinConfigure(serialPinConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#define NOINLINE __attribute__((noinline))
|
#define NOINLINE __attribute__((noinline))
|
||||||
|
|
||||||
#if !defined(UNIT_TEST) && !defined(SITL) && !(USBD_DEBUG_LEVEL > 0)
|
#if !defined(UNIT_TEST) && !defined(SIMULATOR_BUILD) && !(USBD_DEBUG_LEVEL > 0)
|
||||||
#pragma GCC poison sprintf snprintf
|
#pragma GCC poison sprintf snprintf
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -98,7 +98,7 @@
|
||||||
#define STM32F1
|
#define STM32F1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif defined(SITL)
|
#elif defined(SIMULATOR_BUILD)
|
||||||
|
|
||||||
// Nop
|
// Nop
|
||||||
|
|
||||||
|
|
|
@ -115,8 +115,7 @@ void pgResetFn_compassConfig(compassConfig_t *compassConfig)
|
||||||
static int16_t magADCRaw[XYZ_AXIS_COUNT];
|
static int16_t magADCRaw[XYZ_AXIS_COUNT];
|
||||||
static uint8_t magInit = 0;
|
static uint8_t magInit = 0;
|
||||||
|
|
||||||
#if !defined(SITL)
|
#if !defined(SIMULATOR_BUILD)
|
||||||
|
|
||||||
bool compassDetect(magDev_t *dev)
|
bool compassDetect(magDev_t *dev)
|
||||||
{
|
{
|
||||||
magSensor_e magHardware = MAG_NONE;
|
magSensor_e magHardware = MAG_NONE;
|
||||||
|
@ -257,7 +256,7 @@ bool compassDetect(magDev_t *dev)
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif // !SITL
|
#endif // !SIMULATOR_BUILD
|
||||||
|
|
||||||
bool compassInit(void)
|
bool compassInit(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -131,5 +131,7 @@
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC ( BIT(14) )
|
#define TARGET_IO_PORTC ( BIT(14) )
|
||||||
|
|
||||||
|
#define PARTIAL_REMAP_TIM3
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 12
|
#define USABLE_TIMER_CHANNEL_COUNT 12
|
||||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue