1
0
Fork 0
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:
Nicholas Sherlock 2015-01-04 10:35:59 +13:00
commit 6c2ce5038c
12 changed files with 151 additions and 89 deletions

View file

@ -10,6 +10,7 @@ env:
- TARGET=PORT103R
- TARGET=SPARKY
- TARGET=STM32F3DISCOVERY
- TARGET=ALIENWIIF1
language: c
compiler: arm-none-eabi-gcc
before_install: sudo add-apt-repository -y ppa:terry.guo/gcc-arm-embedded && sudo apt-get update

View file

@ -35,7 +35,7 @@ SERIAL_DEVICE ?= /dev/ttyUSB0
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
OPBL_VALID_TARGETS = CC3D
@ -152,6 +152,12 @@ endif
TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
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) \
$(TARGET_DIR)
@ -252,6 +258,8 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
$(HIGHEND_SRC) \
$(COMMON_SRC)
ALIENWIIF1_SRC = $(NAZE_SRC)
EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
drivers/accgyro_adxl345.c \
drivers/accgyro_bma280.c \

View file

@ -118,4 +118,7 @@ https://travis-ci.org/cleanflight/cleanflight
[![Build Status](https://travis-ci.org/cleanflight/cleanflight.svg?branch=master)](https://travis-ci.org/cleanflight/cleanflight)
## Cleanflight Releases
https://github.com/cleanflight/cleanflight/releases

View file

@ -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.
* 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
## 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

View file

@ -141,7 +141,12 @@ void SetSysClock(bool overclock)
*RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16);
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;
#endif
switch (clocksrc) {
case SRC_HSE:
if (overclock) {

View file

@ -574,28 +574,37 @@ void activateConfig(void)
activateControlRateConfig();
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, &currentProfile->pidProfile);
useRcControlsConfig(
currentProfile->modeActivationConditions,
&masterConfig.escAndServoConfig,
&currentProfile->pidProfile
);
useGyroConfig(&masterConfig.gyroConfig);
#ifdef TELEMETRY
useTelemetryConfig(&masterConfig.telemetryConfig);
#endif
setPIDController(currentProfile->pidController);
#ifdef GPS
gpsUseProfile(&currentProfile->gpsProfile);
gpsUsePIDs(&currentProfile->pidProfile);
#endif
useFailsafeConfig(&currentProfile->failsafeConfig);
setAccelerationTrims(&masterConfig.accZero);
mixerUseConfigs(
currentProfile->servoConf,
&masterConfig.flight3DConfig,
&masterConfig.escAndServoConfig,
&currentProfile->mixerConfig,
&masterConfig.airplaneConfig,
&masterConfig.rxConfig,
&currentProfile->gimbalConfig
);
currentProfile->servoConf,
&masterConfig.flight3DConfig,
&masterConfig.escAndServoConfig,
&currentProfile->mixerConfig,
&masterConfig.airplaneConfig,
&masterConfig.rxConfig,
&currentProfile->gimbalConfig
);
imuRuntimeConfig.gyro_cmpf_factor = masterConfig.gyro_cmpf_factor;
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
@ -603,8 +612,18 @@ void activateConfig(void)
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
imuRuntimeConfig.small_angle = masterConfig.small_angle;
configureImu(&imuRuntimeConfig, &currentProfile->pidProfile, &currentProfile->accDeadband);
configureAltitudeHold(&currentProfile->pidProfile, &currentProfile->barometerConfig, &currentProfile->rcControlsConfig, &masterConfig.escAndServoConfig);
configureImu(
&imuRuntimeConfig,
&currentProfile->pidProfile,
&currentProfile->accDeadband
);
configureAltitudeHold(
&currentProfile->pidProfile,
&currentProfile->barometerConfig,
&currentProfile->rcControlsConfig,
&masterConfig.escAndServoConfig
);
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);

View file

@ -194,7 +194,8 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
UNUSED(controlRateConfig);
// **** 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++) {
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC
// observe max inclination

View file

@ -84,7 +84,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
#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_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},
@ -105,7 +105,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
{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_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}
@ -121,7 +121,7 @@ static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
#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_USART2, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
#if (SERIAL_PORT_COUNT > 2)
@ -548,9 +548,10 @@ serialPort_t *findSharedSerialPort(serialPortFunction_e functionToUse, uint16_t
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);
if (functionIndex == IDENTIFIER_NOT_FOUND) {
continue;

View file

@ -76,42 +76,18 @@ typedef enum {
#endif
} serialPortIndex_e;
#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
// serial port identifiers are now fixed, these values are used by MSP commands.
typedef enum {
SERIAL_PORT_USART1 = 0,
SERIAL_PORT_USART2,
SERIAL_PORT_USART3,
SERIAL_PORT_SOFTSERIAL1,
SERIAL_PORT_SOFTSERIAL2
SERIAL_PORT_USART4,
SERIAL_PORT_USB_VCP = 20,
SERIAL_PORT_SOFTSERIAL1 = 30,
SERIAL_PORT_SOFTSERIAL2,
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
} serialPortIdentifier_e;
#define SERIAL_PORT_IDENTIFIER_COUNT 5
#endif
#endif
// bitmask
typedef enum {
@ -128,6 +104,7 @@ typedef struct serialPortConstraint_s {
uint32_t maxBaudRate;
serialPortFeature_t feature;
} serialPortConstraint_t;
extern const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT];
typedef struct serialPortFunction_s {
serialPortIdentifier_e identifier;

View file

@ -98,7 +98,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
* API consumers should ALWAYS handle communication failures gracefully and attempt to continue
* 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
* 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 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
@ -154,21 +154,11 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define CAP_NAVCAP ((uint32_t)1 << 4)
#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_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
@ -206,6 +196,10 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_ADJUSTMENT_RANGES 52
#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)
//
@ -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
// 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.
#define MSP_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_CONFIG 67 //in message baseflight-specific settings save
// 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_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save
#define MSP_REBOOT 68 //in message reboot settings
// DEPRECATED - Use MSP_API_VERSION instead
#define MSP_BUILD_INFO 69 //out message build date as well as some space for future expansion
// DEPRECATED - Use MSP_BUILD_INFO instead
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
//
// Multwii original MSP commands
@ -657,35 +651,37 @@ static bool processOutCommand(uint8_t cmdMSP)
switch (cmdMSP) {
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(
1 + // protocol 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.
API_VERSION_LENGTH
);
serialize8(MSP_PROTOCOL_VERSION);
serialize8(API_VERSION_MAJOR);
serialize8(API_VERSION_MINOR);
break;
case MSP_FC_VARIANT:
headSerialReply(FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
for (i = 0; i < FLIGHT_CONTROLLER_IDENTIFIER_LENGTH; i++) {
serialize8(flightControllerIdentifier[i]);
}
break;
case MSP_FC_VERSION:
headSerialReply(FLIGHT_CONTROLLER_VERSION_LENGTH);
serialize8(FC_VERSION_MAJOR);
serialize8(FC_VERSION_MINOR);
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++) {
serialize8(boardIdentifier[i]);
}
@ -694,6 +690,14 @@ static bool processOutCommand(uint8_t cmdMSP)
#else
serialize16(0); // No other build targets currently have hardware revision detection.
#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++) {
serialize8(buildDate[i]);
@ -702,11 +706,9 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize8(buildTime[i]);
}
serialize8(GIT_SHORT_REVISION_LENGTH);
for (i = 0; i < GIT_SHORT_REVISION_LENGTH; i++) {
serialize8(shortGitRevision[i]);
}
serialize8(0); // No flight controller specific information to follow.
break;
// DEPRECATED - Use MSP_API_VERSION
@ -1052,7 +1054,7 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize8(masterConfig.rxConfig.rcmap[i]);
break;
case MSP_CONFIG:
case MSP_BF_CONFIG:
headSerialReply(1 + 4 + 1 + 2 + 2 + 2 + 2 + 2);
serialize8(masterConfig.mixerMode);
@ -1068,6 +1070,21 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(masterConfig.batteryConfig.currentMeterOffset);
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
case MSP_LED_COLORS:
headSerialReply(CONFIGURABLE_COLOR_COUNT * 4);
@ -1090,7 +1107,7 @@ static bool processOutCommand(uint8_t cmdMSP)
}
break;
#endif
case MSP_BUILD_INFO:
case MSP_BF_BUILD_INFO:
headSerialReply(11 + 4 + 4);
for (i = 0; i < 11; i++)
serialize8(buildDate[i]); // MMM DD YYYY as ascii, MMM = Jan/Feb... etc
@ -1368,7 +1385,7 @@ static bool processInCommand(void)
}
break;
case MSP_SET_CONFIG:
case MSP_SET_BF_CONFIG:
#ifdef USE_QUAD_MIXER_ONLY
read8(); // mixerMode ignored
@ -1389,6 +1406,24 @@ static bool processInCommand(void)
masterConfig.batteryConfig.currentMeterOffset = read16();
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
case MSP_SET_LED_COLORS:
for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {

View file

@ -17,7 +17,7 @@
#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_PIN Pin_3 // PB3 (LED)

View file

@ -16,7 +16,7 @@
*/
#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 MW_VERSION 231