mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 06:45:16 +03:00
Merge remote-tracking branch 'upstream/master'
This commit is contained in:
commit
6c2ce5038c
12 changed files with 151 additions and 89 deletions
|
@ -10,6 +10,7 @@ env:
|
||||||
- TARGET=PORT103R
|
- TARGET=PORT103R
|
||||||
- TARGET=SPARKY
|
- TARGET=SPARKY
|
||||||
- TARGET=STM32F3DISCOVERY
|
- TARGET=STM32F3DISCOVERY
|
||||||
|
- TARGET=ALIENWIIF1
|
||||||
language: c
|
language: c
|
||||||
compiler: arm-none-eabi-gcc
|
compiler: arm-none-eabi-gcc
|
||||||
before_install: sudo add-apt-repository -y ppa:terry.guo/gcc-arm-embedded && sudo apt-get update
|
before_install: sudo add-apt-repository -y ppa:terry.guo/gcc-arm-embedded && sudo apt-get update
|
||||||
|
|
10
Makefile
10
Makefile
|
@ -35,7 +35,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0
|
||||||
|
|
||||||
FORKNAME = cleanflight
|
FORKNAME = cleanflight
|
||||||
|
|
||||||
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3 PORT103R SPARKY
|
VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU EUSTM32F103RC MASSIVEF3 PORT103R SPARKY ALIENWIIF1
|
||||||
|
|
||||||
# Valid targets for OP BootLoader support
|
# Valid targets for OP BootLoader support
|
||||||
OPBL_VALID_TARGETS = CC3D
|
OPBL_VALID_TARGETS = CC3D
|
||||||
|
@ -152,6 +152,12 @@ endif
|
||||||
TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
|
TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
|
||||||
TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
|
TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
|
||||||
|
|
||||||
|
ifeq ($(TARGET),ALIENWIIF1)
|
||||||
|
# ALIENWIIF1 is a VARIANT of NAZE
|
||||||
|
TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -DALIENWII32
|
||||||
|
TARGET_DIR = $(ROOT)/src/main/target/NAZE
|
||||||
|
endif
|
||||||
|
|
||||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
$(TARGET_DIR)
|
$(TARGET_DIR)
|
||||||
|
|
||||||
|
@ -252,6 +258,8 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
|
||||||
$(HIGHEND_SRC) \
|
$(HIGHEND_SRC) \
|
||||||
$(COMMON_SRC)
|
$(COMMON_SRC)
|
||||||
|
|
||||||
|
ALIENWIIF1_SRC = $(NAZE_SRC)
|
||||||
|
|
||||||
EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
|
EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
|
||||||
drivers/accgyro_adxl345.c \
|
drivers/accgyro_adxl345.c \
|
||||||
drivers/accgyro_bma280.c \
|
drivers/accgyro_bma280.c \
|
||||||
|
|
|
@ -118,4 +118,7 @@ https://travis-ci.org/cleanflight/cleanflight
|
||||||
|
|
||||||
[](https://travis-ci.org/cleanflight/cleanflight)
|
[](https://travis-ci.org/cleanflight/cleanflight)
|
||||||
|
|
||||||
|
## Cleanflight Releases
|
||||||
|
https://github.com/cleanflight/cleanflight/releases
|
||||||
|
|
||||||
|
|
||||||
|
|
12
docs/Gps.md
12
docs/Gps.md
|
@ -130,3 +130,15 @@ From the UBlox documentation:
|
||||||
* Pedestrian - Applications with low acceleration and speed, e.g. how a pedestrian would move. Low acceleration assumed. MAX Altitude [m]: 9000, MAX Velocity [m/s]: 30, MAX Vertical, Velocity [m/s]: 20, Sanity check type: Altitude and Velocity, Max Position Deviation: Small.
|
* Pedestrian - Applications with low acceleration and speed, e.g. how a pedestrian would move. Low acceleration assumed. MAX Altitude [m]: 9000, MAX Velocity [m/s]: 30, MAX Vertical, Velocity [m/s]: 20, Sanity check type: Altitude and Velocity, Max Position Deviation: Small.
|
||||||
* Portable - Applications with low acceleration, e.g. portable devices. Suitable for most situations. MAX Altitude [m]: 12000, MAX Velocity [m/s]: 310, MAX Vertical Velocity [m/s]: 50, Sanity check type: Altitude and Velocity, Max Position Deviation: Medium.
|
* Portable - Applications with low acceleration, e.g. portable devices. Suitable for most situations. MAX Altitude [m]: 12000, MAX Velocity [m/s]: 310, MAX Vertical Velocity [m/s]: 50, Sanity check type: Altitude and Velocity, Max Position Deviation: Medium.
|
||||||
* Airborne < 1G - Used for applications with a higher dynamic range and vertical acceleration than a passenger car. No 2D position fixes supported. MAX Altitude [m]: 50000, MAX Velocity [m/s]: 100, MAX Vertical Velocity [m/s]: 100, Sanity check type: Altitude, Max Position Deviation: Large
|
* Airborne < 1G - Used for applications with a higher dynamic range and vertical acceleration than a passenger car. No 2D position fixes supported. MAX Altitude [m]: 50000, MAX Velocity [m/s]: 100, MAX Vertical Velocity [m/s]: 100, Sanity check type: Altitude, Max Position Deviation: Large
|
||||||
|
|
||||||
|
## Hardware
|
||||||
|
|
||||||
|
There are many GPS receivers available on the market, people have reported success with the following receivers:
|
||||||
|
|
||||||
|
Ublox Neo-7M GPS with Compass and Pedestal Mount
|
||||||
|
http://www.hobbyking.com/hobbyking/store/__55558__Ublox_Neo_7M_GPS_with_Compass_and_Pedestal_Mount.html
|
||||||
|
|
||||||
|
RY825AI 18Hz UART USB interface GPS Glonass BeiDou QZSS antenna module flash
|
||||||
|
http://www.ebay.com/itm/RY825AI-18Hz-UART-USB-interface-GPS-Glonass-BeiDou-QZSS-antenna-module-flash/181566850426
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -141,7 +141,12 @@ void SetSysClock(bool overclock)
|
||||||
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
|
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
|
||||||
GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET);
|
GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET);
|
||||||
|
|
||||||
|
#if defined(CJMCU)
|
||||||
|
// On CJMCU new revision boards (Late 2014) bit 15 of GPIOC->IDR is '1'.
|
||||||
|
RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL9;
|
||||||
|
#else
|
||||||
RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9;
|
RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9;
|
||||||
|
#endif
|
||||||
switch (clocksrc) {
|
switch (clocksrc) {
|
||||||
case SRC_HSE:
|
case SRC_HSE:
|
||||||
if (overclock) {
|
if (overclock) {
|
||||||
|
|
|
@ -574,19 +574,28 @@ void activateConfig(void)
|
||||||
|
|
||||||
activateControlRateConfig();
|
activateControlRateConfig();
|
||||||
|
|
||||||
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile);
|
useRcControlsConfig(
|
||||||
|
currentProfile->modeActivationConditions,
|
||||||
|
&masterConfig.escAndServoConfig,
|
||||||
|
¤tProfile->pidProfile
|
||||||
|
);
|
||||||
|
|
||||||
useGyroConfig(&masterConfig.gyroConfig);
|
useGyroConfig(&masterConfig.gyroConfig);
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
useTelemetryConfig(&masterConfig.telemetryConfig);
|
useTelemetryConfig(&masterConfig.telemetryConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
setPIDController(currentProfile->pidController);
|
setPIDController(currentProfile->pidController);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
gpsUseProfile(¤tProfile->gpsProfile);
|
gpsUseProfile(¤tProfile->gpsProfile);
|
||||||
gpsUsePIDs(¤tProfile->pidProfile);
|
gpsUsePIDs(¤tProfile->pidProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
useFailsafeConfig(¤tProfile->failsafeConfig);
|
useFailsafeConfig(¤tProfile->failsafeConfig);
|
||||||
setAccelerationTrims(&masterConfig.accZero);
|
setAccelerationTrims(&masterConfig.accZero);
|
||||||
|
|
||||||
mixerUseConfigs(
|
mixerUseConfigs(
|
||||||
currentProfile->servoConf,
|
currentProfile->servoConf,
|
||||||
&masterConfig.flight3DConfig,
|
&masterConfig.flight3DConfig,
|
||||||
|
@ -603,8 +612,18 @@ void activateConfig(void)
|
||||||
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
|
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
|
||||||
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
||||||
|
|
||||||
configureImu(&imuRuntimeConfig, ¤tProfile->pidProfile, ¤tProfile->accDeadband);
|
configureImu(
|
||||||
configureAltitudeHold(¤tProfile->pidProfile, ¤tProfile->barometerConfig, ¤tProfile->rcControlsConfig, &masterConfig.escAndServoConfig);
|
&imuRuntimeConfig,
|
||||||
|
¤tProfile->pidProfile,
|
||||||
|
¤tProfile->accDeadband
|
||||||
|
);
|
||||||
|
|
||||||
|
configureAltitudeHold(
|
||||||
|
¤tProfile->pidProfile,
|
||||||
|
¤tProfile->barometerConfig,
|
||||||
|
¤tProfile->rcControlsConfig,
|
||||||
|
&masterConfig.escAndServoConfig
|
||||||
|
);
|
||||||
|
|
||||||
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
|
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
|
||||||
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);
|
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);
|
||||||
|
|
|
@ -194,7 +194,8 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
||||||
UNUSED(controlRateConfig);
|
UNUSED(controlRateConfig);
|
||||||
|
|
||||||
// **** PITCH & ROLL & YAW PID ****
|
// **** PITCH & ROLL & YAW PID ****
|
||||||
prop = max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])); // range [0;500]
|
prop = min(max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])), 500); // range [0;500]
|
||||||
|
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC
|
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC
|
||||||
// observe max inclination
|
// observe max inclination
|
||||||
|
|
|
@ -84,7 +84,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||||
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
|
{SERIAL_PORT_USB_VCP, 9600, 115200, SPF_NONE },
|
||||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
|
@ -105,7 +105,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||||
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||||
};
|
};
|
||||||
|
|
||||||
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
{SERIAL_PORT_USART3, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART3, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||||
|
@ -121,7 +121,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
{SERIAL_PORT_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
|
||||||
#if (SERIAL_PORT_COUNT > 2)
|
#if (SERIAL_PORT_COUNT > 2)
|
||||||
|
@ -548,9 +548,10 @@ serialPort_t *findSharedSerialPort(serialPortFunction_e functionToUse, uint16_t
|
||||||
|
|
||||||
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
|
void applySerialConfigToPortFunctions(serialConfig_t *serialConfig)
|
||||||
{
|
{
|
||||||
uint32_t portIndex = 0, serialPortIdentifier;
|
uint32_t portIndex = 0, serialPortIdentifier, constraintIndex;
|
||||||
|
|
||||||
for (serialPortIdentifier = 0; serialPortIdentifier < SERIAL_PORT_IDENTIFIER_COUNT && portIndex < SERIAL_PORT_COUNT; serialPortIdentifier++) {
|
for (constraintIndex = 0; constraintIndex < SERIAL_PORT_COUNT && portIndex < SERIAL_PORT_COUNT; constraintIndex++) {
|
||||||
|
serialPortIdentifier = serialPortConstraints[constraintIndex].identifier;
|
||||||
uint32_t functionIndex = lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier);
|
uint32_t functionIndex = lookupSerialPortFunctionIndexByIdentifier(serialPortIdentifier);
|
||||||
if (functionIndex == IDENTIFIER_NOT_FOUND) {
|
if (functionIndex == IDENTIFIER_NOT_FOUND) {
|
||||||
continue;
|
continue;
|
||||||
|
|
|
@ -76,42 +76,18 @@ typedef enum {
|
||||||
#endif
|
#endif
|
||||||
} serialPortIndex_e;
|
} serialPortIndex_e;
|
||||||
|
|
||||||
|
// serial port identifiers are now fixed, these values are used by MSP commands.
|
||||||
#ifdef STM32F303xC
|
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
SERIAL_PORT_USB_VCP = 0,
|
|
||||||
SERIAL_PORT_USART1,
|
|
||||||
SERIAL_PORT_USART2,
|
|
||||||
SERIAL_PORT_USART3,
|
|
||||||
SERIAL_PORT_USART4
|
|
||||||
} serialPortIdentifier_e;
|
|
||||||
|
|
||||||
#define SERIAL_PORT_IDENTIFIER_COUNT 5
|
|
||||||
#else
|
|
||||||
|
|
||||||
#ifdef CC3D
|
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
SERIAL_PORT_USART1 = 0,
|
|
||||||
SERIAL_PORT_USART3,
|
|
||||||
SERIAL_PORT_SOFTSERIAL1,
|
|
||||||
} serialPortIdentifier_e;
|
|
||||||
|
|
||||||
#define SERIAL_PORT_IDENTIFIER_COUNT 3
|
|
||||||
#else
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
SERIAL_PORT_USART1 = 0,
|
SERIAL_PORT_USART1 = 0,
|
||||||
SERIAL_PORT_USART2,
|
SERIAL_PORT_USART2,
|
||||||
SERIAL_PORT_USART3,
|
SERIAL_PORT_USART3,
|
||||||
SERIAL_PORT_SOFTSERIAL1,
|
SERIAL_PORT_USART4,
|
||||||
SERIAL_PORT_SOFTSERIAL2
|
SERIAL_PORT_USB_VCP = 20,
|
||||||
|
SERIAL_PORT_SOFTSERIAL1 = 30,
|
||||||
|
SERIAL_PORT_SOFTSERIAL2,
|
||||||
|
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
|
||||||
} serialPortIdentifier_e;
|
} serialPortIdentifier_e;
|
||||||
|
|
||||||
#define SERIAL_PORT_IDENTIFIER_COUNT 5
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// bitmask
|
// bitmask
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -128,6 +104,7 @@ typedef struct serialPortConstraint_s {
|
||||||
uint32_t maxBaudRate;
|
uint32_t maxBaudRate;
|
||||||
serialPortFeature_t feature;
|
serialPortFeature_t feature;
|
||||||
} serialPortConstraint_t;
|
} serialPortConstraint_t;
|
||||||
|
extern const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT];
|
||||||
|
|
||||||
typedef struct serialPortFunction_s {
|
typedef struct serialPortFunction_s {
|
||||||
serialPortIdentifier_e identifier;
|
serialPortIdentifier_e identifier;
|
||||||
|
|
|
@ -98,7 +98,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
||||||
* API consumers should ALWAYS handle communication failures gracefully and attempt to continue
|
* API consumers should ALWAYS handle communication failures gracefully and attempt to continue
|
||||||
* without the information if possible. Clients MAY log/display a suitable message.
|
* without the information if possible. Clients MAY log/display a suitable message.
|
||||||
*
|
*
|
||||||
* API clients should NOT attempt any communication if they can't handle the API MAJOR VERSION.
|
* API clients should NOT attempt any communication if they can't handle the returned API MAJOR VERSION.
|
||||||
*
|
*
|
||||||
* API clients SHOULD attempt communication if the API MINOR VERSION has increased from the time
|
* API clients SHOULD attempt communication if the API MINOR VERSION has increased from the time
|
||||||
* the API client was written and handle command failures gracefully. Clients MAY disable
|
* the API client was written and handle command failures gracefully. Clients MAY disable
|
||||||
|
@ -121,7 +121,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
||||||
#define MSP_PROTOCOL_VERSION 0
|
#define MSP_PROTOCOL_VERSION 0
|
||||||
|
|
||||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||||
#define API_VERSION_MINOR 0 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
#define API_VERSION_MINOR 1 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||||
|
|
||||||
#define API_VERSION_LENGTH 2
|
#define API_VERSION_LENGTH 2
|
||||||
|
|
||||||
|
@ -154,21 +154,11 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
||||||
#define CAP_NAVCAP ((uint32_t)1 << 4)
|
#define CAP_NAVCAP ((uint32_t)1 << 4)
|
||||||
#define CAP_EXTAUX ((uint32_t)1 << 5)
|
#define CAP_EXTAUX ((uint32_t)1 << 5)
|
||||||
|
|
||||||
/**
|
|
||||||
* Returns MSP protocol version
|
|
||||||
* API version
|
|
||||||
* Flight Controller Identifier
|
|
||||||
* Flight Controller build version (major, minor, patchlevel)
|
|
||||||
* Board Identifier
|
|
||||||
* Board Hardware Revision
|
|
||||||
* Build Date - "MMM DD YYYY" MMM = Jan/Feb/...
|
|
||||||
* Build Time - "HH:MM:SS"
|
|
||||||
* SCM reference length
|
|
||||||
* SCM reference (git revision, svn commit id)
|
|
||||||
* Additional FC information length
|
|
||||||
* Additional FC information (as decided by the FC, for FC specific tools to use as required)
|
|
||||||
**/
|
|
||||||
#define MSP_API_VERSION 1 //out message
|
#define MSP_API_VERSION 1 //out message
|
||||||
|
#define MSP_FC_VARIANT 2 //out message
|
||||||
|
#define MSP_FC_VERSION 3 //out message
|
||||||
|
#define MSP_BOARD_INFO 4 //out message
|
||||||
|
#define MSP_BUILD_INFO 5 //out message
|
||||||
|
|
||||||
//
|
//
|
||||||
// MSP commands for Cleanflight original features
|
// MSP commands for Cleanflight original features
|
||||||
|
@ -206,6 +196,10 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
||||||
#define MSP_ADJUSTMENT_RANGES 52
|
#define MSP_ADJUSTMENT_RANGES 52
|
||||||
#define MSP_SET_ADJUSTMENT_RANGE 53
|
#define MSP_SET_ADJUSTMENT_RANGE 53
|
||||||
|
|
||||||
|
// private - only to be used by the configurator, the commands are likely to change
|
||||||
|
#define MSP_CF_SERIAL_CONFIG 54
|
||||||
|
#define MSP_SET_CF_SERIAL_CONFIG 55
|
||||||
|
|
||||||
//
|
//
|
||||||
// Baseflight MSP commands (if enabled they exist in Cleanflight)
|
// Baseflight MSP commands (if enabled they exist in Cleanflight)
|
||||||
//
|
//
|
||||||
|
@ -213,14 +207,14 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
||||||
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
|
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
|
||||||
|
|
||||||
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
|
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
|
||||||
// DEPRECATED - DO NOT USE "MSP_CONFIG" and MSP_SET_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
|
// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
|
||||||
#define MSP_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
|
#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
|
||||||
#define MSP_SET_CONFIG 67 //in message baseflight-specific settings save
|
#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save
|
||||||
|
|
||||||
#define MSP_REBOOT 68 //in message reboot settings
|
#define MSP_REBOOT 68 //in message reboot settings
|
||||||
|
|
||||||
// DEPRECATED - Use MSP_API_VERSION instead
|
// DEPRECATED - Use MSP_BUILD_INFO instead
|
||||||
#define MSP_BUILD_INFO 69 //out message build date as well as some space for future expansion
|
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
|
||||||
|
|
||||||
//
|
//
|
||||||
// Multwii original MSP commands
|
// Multwii original MSP commands
|
||||||
|
@ -657,35 +651,37 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
|
|
||||||
switch (cmdMSP) {
|
switch (cmdMSP) {
|
||||||
case MSP_API_VERSION:
|
case MSP_API_VERSION:
|
||||||
// the components of this command are in an order such that future changes could be made to it without breaking clients.
|
|
||||||
// i.e. most important first.
|
|
||||||
headSerialReply(
|
headSerialReply(
|
||||||
1 + // protocol version length
|
1 + // protocol version length
|
||||||
API_VERSION_LENGTH +
|
API_VERSION_LENGTH
|
||||||
FLIGHT_CONTROLLER_IDENTIFIER_LENGTH +
|
|
||||||
FLIGHT_CONTROLLER_VERSION_LENGTH +
|
|
||||||
BOARD_IDENTIFIER_LENGTH +
|
|
||||||
BOARD_HARDWARE_REVISION_LENGTH +
|
|
||||||
BUILD_DATE_LENGTH +
|
|
||||||
BUILD_TIME_LENGTH +
|
|
||||||
1 + // scm reference length
|
|
||||||
GIT_SHORT_REVISION_LENGTH +
|
|
||||||
1 // additional FC specific length
|
|
||||||
// no addition FC specific data yet.
|
|
||||||
);
|
);
|
||||||
serialize8(MSP_PROTOCOL_VERSION);
|
serialize8(MSP_PROTOCOL_VERSION);
|
||||||
|
|
||||||
serialize8(API_VERSION_MAJOR);
|
serialize8(API_VERSION_MAJOR);
|
||||||
serialize8(API_VERSION_MINOR);
|
serialize8(API_VERSION_MINOR);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSP_FC_VARIANT:
|
||||||
|
headSerialReply(FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
|
||||||
|
|
||||||
for (i = 0; i < FLIGHT_CONTROLLER_IDENTIFIER_LENGTH; i++) {
|
for (i = 0; i < FLIGHT_CONTROLLER_IDENTIFIER_LENGTH; i++) {
|
||||||
serialize8(flightControllerIdentifier[i]);
|
serialize8(flightControllerIdentifier[i]);
|
||||||
}
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSP_FC_VERSION:
|
||||||
|
headSerialReply(FLIGHT_CONTROLLER_VERSION_LENGTH);
|
||||||
|
|
||||||
serialize8(FC_VERSION_MAJOR);
|
serialize8(FC_VERSION_MAJOR);
|
||||||
serialize8(FC_VERSION_MINOR);
|
serialize8(FC_VERSION_MINOR);
|
||||||
serialize8(FC_VERSION_PATCH_LEVEL);
|
serialize8(FC_VERSION_PATCH_LEVEL);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSP_BOARD_INFO:
|
||||||
|
headSerialReply(
|
||||||
|
BOARD_IDENTIFIER_LENGTH +
|
||||||
|
BOARD_HARDWARE_REVISION_LENGTH
|
||||||
|
);
|
||||||
for (i = 0; i < BOARD_IDENTIFIER_LENGTH; i++) {
|
for (i = 0; i < BOARD_IDENTIFIER_LENGTH; i++) {
|
||||||
serialize8(boardIdentifier[i]);
|
serialize8(boardIdentifier[i]);
|
||||||
}
|
}
|
||||||
|
@ -694,6 +690,14 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
#else
|
#else
|
||||||
serialize16(0); // No other build targets currently have hardware revision detection.
|
serialize16(0); // No other build targets currently have hardware revision detection.
|
||||||
#endif
|
#endif
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSP_BUILD_INFO:
|
||||||
|
headSerialReply(
|
||||||
|
BUILD_DATE_LENGTH +
|
||||||
|
BUILD_TIME_LENGTH +
|
||||||
|
GIT_SHORT_REVISION_LENGTH
|
||||||
|
);
|
||||||
|
|
||||||
for (i = 0; i < BUILD_DATE_LENGTH; i++) {
|
for (i = 0; i < BUILD_DATE_LENGTH; i++) {
|
||||||
serialize8(buildDate[i]);
|
serialize8(buildDate[i]);
|
||||||
|
@ -702,11 +706,9 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
serialize8(buildTime[i]);
|
serialize8(buildTime[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
serialize8(GIT_SHORT_REVISION_LENGTH);
|
|
||||||
for (i = 0; i < GIT_SHORT_REVISION_LENGTH; i++) {
|
for (i = 0; i < GIT_SHORT_REVISION_LENGTH; i++) {
|
||||||
serialize8(shortGitRevision[i]);
|
serialize8(shortGitRevision[i]);
|
||||||
}
|
}
|
||||||
serialize8(0); // No flight controller specific information to follow.
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
// DEPRECATED - Use MSP_API_VERSION
|
// DEPRECATED - Use MSP_API_VERSION
|
||||||
|
@ -1052,7 +1054,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
serialize8(masterConfig.rxConfig.rcmap[i]);
|
serialize8(masterConfig.rxConfig.rcmap[i]);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_CONFIG:
|
case MSP_BF_CONFIG:
|
||||||
headSerialReply(1 + 4 + 1 + 2 + 2 + 2 + 2 + 2);
|
headSerialReply(1 + 4 + 1 + 2 + 2 + 2 + 2 + 2);
|
||||||
serialize8(masterConfig.mixerMode);
|
serialize8(masterConfig.mixerMode);
|
||||||
|
|
||||||
|
@ -1068,6 +1070,21 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
serialize16(masterConfig.batteryConfig.currentMeterOffset);
|
serialize16(masterConfig.batteryConfig.currentMeterOffset);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSP_CF_SERIAL_CONFIG:
|
||||||
|
headSerialReply(
|
||||||
|
((sizeof(uint8_t) * 2) * SERIAL_PORT_COUNT) +
|
||||||
|
(sizeof(uint32_t) * 4)
|
||||||
|
);
|
||||||
|
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||||
|
serialize8(serialPortConstraints[i].identifier);
|
||||||
|
serialize8(masterConfig.serialConfig.serial_port_scenario[i]);
|
||||||
|
}
|
||||||
|
serialize32(masterConfig.serialConfig.msp_baudrate);
|
||||||
|
serialize32(masterConfig.serialConfig.cli_baudrate);
|
||||||
|
serialize32(masterConfig.serialConfig.gps_baudrate);
|
||||||
|
serialize32(masterConfig.serialConfig.gps_passthrough_baudrate);
|
||||||
|
break;
|
||||||
|
|
||||||
#ifdef LED_STRIP
|
#ifdef LED_STRIP
|
||||||
case MSP_LED_COLORS:
|
case MSP_LED_COLORS:
|
||||||
headSerialReply(CONFIGURABLE_COLOR_COUNT * 4);
|
headSerialReply(CONFIGURABLE_COLOR_COUNT * 4);
|
||||||
|
@ -1090,7 +1107,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
case MSP_BUILD_INFO:
|
case MSP_BF_BUILD_INFO:
|
||||||
headSerialReply(11 + 4 + 4);
|
headSerialReply(11 + 4 + 4);
|
||||||
for (i = 0; i < 11; i++)
|
for (i = 0; i < 11; i++)
|
||||||
serialize8(buildDate[i]); // MMM DD YYYY as ascii, MMM = Jan/Feb... etc
|
serialize8(buildDate[i]); // MMM DD YYYY as ascii, MMM = Jan/Feb... etc
|
||||||
|
@ -1368,7 +1385,7 @@ static bool processInCommand(void)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SET_CONFIG:
|
case MSP_SET_BF_CONFIG:
|
||||||
|
|
||||||
#ifdef USE_QUAD_MIXER_ONLY
|
#ifdef USE_QUAD_MIXER_ONLY
|
||||||
read8(); // mixerMode ignored
|
read8(); // mixerMode ignored
|
||||||
|
@ -1389,6 +1406,24 @@ static bool processInCommand(void)
|
||||||
masterConfig.batteryConfig.currentMeterOffset = read16();
|
masterConfig.batteryConfig.currentMeterOffset = read16();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSP_SET_CF_SERIAL_CONFIG:
|
||||||
|
{
|
||||||
|
uint8_t baudRateSize = (sizeof(uint32_t) * 4);
|
||||||
|
uint8_t serialPortCount = currentPort->dataSize - baudRateSize;
|
||||||
|
if (serialPortCount != SERIAL_PORT_COUNT) {
|
||||||
|
headSerialError(0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||||
|
masterConfig.serialConfig.serial_port_scenario[i] = read8();
|
||||||
|
}
|
||||||
|
masterConfig.serialConfig.msp_baudrate = read32();
|
||||||
|
masterConfig.serialConfig.cli_baudrate = read32();
|
||||||
|
masterConfig.serialConfig.gps_baudrate = read32();
|
||||||
|
masterConfig.serialConfig.gps_passthrough_baudrate = read32();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
#ifdef LED_STRIP
|
#ifdef LED_STRIP
|
||||||
case MSP_SET_LED_COLORS:
|
case MSP_SET_LED_COLORS:
|
||||||
for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
|
for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "AFNA" // AFroNAze - NAZE might be considerd misleading on Naze clones like the flip32.
|
#define TARGET_BOARD_IDENTIFIER "AFNA" // AFroNAze - NAZE might be considered misleading on Naze clones like the flip32.
|
||||||
|
|
||||||
#define LED0_GPIO GPIOB
|
#define LED0_GPIO GPIOB
|
||||||
#define LED0_PIN Pin_3 // PB3 (LED)
|
#define LED0_PIN Pin_3 // PB3 (LED)
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define FC_VERSION_MAJOR 1 // increment when a major release is made (big new feature, etc)
|
#define FC_VERSION_MAJOR 1 // increment when a major release is made (big new feature, etc)
|
||||||
#define FC_VERSION_MINOR 0 // increment when a minor release is made (small new feature, change etc)
|
#define FC_VERSION_MINOR 4 // increment when a minor release is made (small new feature, change etc)
|
||||||
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
|
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
|
||||||
|
|
||||||
#define MW_VERSION 231
|
#define MW_VERSION 231
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue