mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 08:15:30 +03:00
CJMCU - Allow various features to be compiled out to support.
This commit is contained in:
parent
fc93be394f
commit
125f6d1450
16 changed files with 84 additions and 9 deletions
10
Makefile
10
Makefile
|
@ -146,9 +146,11 @@ COMMON_SRC = build_config.c \
|
|||
io/statusindicator.c \
|
||||
rx/rx.c \
|
||||
rx/pwm.c \
|
||||
rx/msp.c \
|
||||
sensors/acceleration.c \
|
||||
sensors/battery.c \
|
||||
sensors/boardalignment.c \
|
||||
sensors/acceleration.c \
|
||||
sensors/compass.c \
|
||||
sensors/gyro.c \
|
||||
sensors/initialisation.c \
|
||||
$(CMSIS_SRC) \
|
||||
|
@ -157,7 +159,6 @@ COMMON_SRC = build_config.c \
|
|||
HIGHEND_SRC = io/gps.c \
|
||||
io/gps_conversion.c \
|
||||
io/ledstrip.c \
|
||||
rx/msp.c \
|
||||
rx/sbus.c \
|
||||
rx/sumd.c \
|
||||
rx/spektrum.c \
|
||||
|
@ -166,8 +167,7 @@ HIGHEND_SRC = io/gps.c \
|
|||
telemetry/hott.c \
|
||||
telemetry/msp.c \
|
||||
sensors/sonar.c \
|
||||
sensors/barometer.c \
|
||||
sensors/compass.c
|
||||
sensors/barometer.c
|
||||
|
||||
NAZE_SRC = startup_stm32f10x_md_gcc.S \
|
||||
drivers/accgyro_adxl345.c \
|
||||
|
@ -228,9 +228,11 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
|
|||
CJMCU_SRC = startup_stm32f10x_md_gcc.S \
|
||||
drivers/adc.c \
|
||||
drivers/adc_stm32f10x.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/bus_i2c_stm32f10x.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/light_led_stm32f10x.c \
|
||||
drivers/pwm_mapping.c \
|
||||
drivers/pwm_output.c \
|
||||
drivers/pwm_rssi.c \
|
||||
|
|
|
@ -383,7 +383,9 @@ void activateConfig(void)
|
|||
generateThrottleCurve(¤tProfile.controlRateConfig, &masterConfig.escAndServoConfig);
|
||||
|
||||
useGyroConfig(&masterConfig.gyroConfig);
|
||||
#ifdef TELEMETRY
|
||||
useTelemetryConfig(&masterConfig.telemetryConfig);
|
||||
#endif
|
||||
setPIDController(currentProfile.pidController);
|
||||
#ifdef GPS
|
||||
gpsUseProfile(¤tProfile.gpsProfile);
|
||||
|
|
|
@ -350,13 +350,17 @@ functionConstraint_t *getConfiguredFunctionConstraint(serialPortFunction_e funct
|
|||
configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
|
||||
break;
|
||||
|
||||
#ifdef TELEMETRY
|
||||
case FUNCTION_TELEMETRY:
|
||||
configuredFunctionConstraint.minBaudRate = getTelemetryProviderBaudRate();
|
||||
configuredFunctionConstraint.maxBaudRate = configuredFunctionConstraint.minBaudRate;
|
||||
break;
|
||||
#endif
|
||||
#ifdef SERIAL_RX
|
||||
case FUNCTION_SERIAL_RX:
|
||||
updateSerialRxFunctionConstraint(&configuredFunctionConstraint);
|
||||
break;
|
||||
#endif
|
||||
case FUNCTION_GPS:
|
||||
configuredFunctionConstraint.maxBaudRate = serialConfig->gps_baudrate;
|
||||
break;
|
||||
|
@ -501,6 +505,7 @@ serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbac
|
|||
case SERIAL_PORT_USART2:
|
||||
serialPort = uartOpen(USART2, callback, baudRate, mode, inversion);
|
||||
break;
|
||||
#ifdef SOFT_SERIAL
|
||||
case SERIAL_PORT_SOFTSERIAL1:
|
||||
serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, inversion);
|
||||
serialSetMode(serialPort, mode);
|
||||
|
@ -509,6 +514,9 @@ serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbac
|
|||
serialPort = openSoftSerial(SOFTSERIAL2, callback, baudRate, inversion);
|
||||
serialSetMode(serialPort, mode);
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (!serialPort) {
|
||||
|
|
|
@ -232,13 +232,17 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef LED_STRIP
|
||||
if (feature(FEATURE_LED_STRIP)) {
|
||||
ws2811LedStripInit();
|
||||
ledStripInit();
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef TELEMETRY
|
||||
if (feature(FEATURE_TELEMETRY))
|
||||
initTelemetry();
|
||||
#endif
|
||||
|
||||
previousTime = micros();
|
||||
|
||||
|
|
|
@ -263,7 +263,9 @@ void annexCode(void)
|
|||
updateWarningLed(currentTime);
|
||||
}
|
||||
|
||||
#ifdef TELEMETRY
|
||||
checkTelemetryState();
|
||||
#endif
|
||||
|
||||
#ifdef LEDRING
|
||||
if (feature(FEATURE_LED_RING)) {
|
||||
|
@ -642,11 +644,15 @@ void loop(void)
|
|||
writeMotors();
|
||||
}
|
||||
|
||||
#ifdef TELEMETRY
|
||||
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
||||
handleTelemetry();
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef LED_STRIP
|
||||
if (feature(FEATURE_LED_STRIP)) {
|
||||
updateLedStrip();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -79,6 +79,7 @@ void useRxConfig(rxConfig_t *rxConfigToUse)
|
|||
rxConfig = rxConfigToUse;
|
||||
}
|
||||
|
||||
#ifdef SERIAL_RX
|
||||
void updateSerialRxFunctionConstraint(functionConstraint_t *functionConstraintToUpdate)
|
||||
{
|
||||
switch (rxConfig->serialrx_provider) {
|
||||
|
@ -94,6 +95,7 @@ void updateSerialRxFunctionConstraint(functionConstraint_t *functionConstraintTo
|
|||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void rxInit(rxConfig_t *rxConfig, failsafe_t *initialFailsafe)
|
||||
{
|
||||
|
@ -106,9 +108,11 @@ void rxInit(rxConfig_t *rxConfig, failsafe_t *initialFailsafe)
|
|||
|
||||
failsafe = initialFailsafe;
|
||||
|
||||
#ifdef SERIAL_RX
|
||||
if (feature(FEATURE_RX_SERIAL)) {
|
||||
serialRxInit(rxConfig);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||
|
@ -119,6 +123,7 @@ void rxInit(rxConfig_t *rxConfig, failsafe_t *initialFailsafe)
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef SERIAL_RX
|
||||
void serialRxInit(rxConfig_t *rxConfig)
|
||||
{
|
||||
bool enabled = false;
|
||||
|
@ -154,6 +159,7 @@ bool isSerialRxFrameComplete(rxConfig_t *rxConfig)
|
|||
}
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
uint8_t calculateChannelRemapping(uint8_t *channelMap, uint8_t channelMapEntryCount, uint8_t channelToRemap)
|
||||
{
|
||||
|
@ -171,10 +177,12 @@ void updateRx(void)
|
|||
{
|
||||
rcDataReceived = false;
|
||||
|
||||
#ifdef SERIAL_RX
|
||||
// calculate rc stuff from serial-based receivers (spek/sbus)
|
||||
if (feature(FEATURE_RX_SERIAL)) {
|
||||
rcDataReceived = isSerialRxFrameComplete(rxConfig);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
rcDataReceived = rxMspFrameComplete();
|
||||
|
|
|
@ -28,3 +28,9 @@
|
|||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
|
|
|
@ -39,6 +39,11 @@
|
|||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define GPS
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
|
|
|
@ -40,10 +40,15 @@
|
|||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define GPS
|
||||
|
||||
// #define SOFT_I2C // enable to test software i2c
|
||||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
|
|
|
@ -29,6 +29,11 @@
|
|||
|
||||
#define GYRO
|
||||
#define ACC
|
||||
#define GPS
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
|
|
|
@ -39,10 +39,15 @@
|
|||
#define BARO
|
||||
#define GYRO
|
||||
#define MAG
|
||||
#define GPS
|
||||
|
||||
// #define SOFT_I2C // enable to test software i2c
|
||||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
|
|
|
@ -41,6 +41,11 @@
|
|||
#define BEEPER
|
||||
#define LED0
|
||||
#define LED1
|
||||
#define GPS
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
|
|
|
@ -24,6 +24,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef TELEMETRY
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
||||
|
@ -383,3 +385,4 @@ void handleFrSkyTelemetry(void)
|
|||
uint32_t getFrSkyTelemetryProviderBaudRate(void) {
|
||||
return FRSKY_BAUDRATE;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -58,6 +58,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef TELEMETRY
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
@ -446,3 +448,4 @@ void handleHoTTTelemetry(void)
|
|||
uint32_t getHoTTTelemetryProviderBaudRate(void) {
|
||||
return HOTT_BAUDRATE;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -25,6 +25,10 @@
|
|||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef TELEMETRY
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "io/serial_msp.h"
|
||||
|
@ -37,3 +41,4 @@ void handleMSPTelemetry(void)
|
|||
{
|
||||
sendMspTelemetry();
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef TELEMETRY
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/serial.h"
|
||||
|
@ -186,3 +188,4 @@ void handleTelemetry(void)
|
|||
handleMSPTelemetry();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue