1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

Merge branch 'master' into xbus_jr01

Conflicts:
	src/main/io/serial.c
This commit is contained in:
Stefan Grufman 2015-01-03 17:23:21 +01:00
commit bf3aca8240
29 changed files with 1961 additions and 1712 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)
@ -251,6 +257,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

@ -0,0 +1,24 @@
# Board - AlienWii32
The AlienWii32 is actually in prototype stage only a few samples exist. There is some more field testing ongoing. The information below is preliminary and will be updated as needed.
Here are the hardware specifications:
- STM32F103CBT6 MCU
- MPU6050 accelerometer/gyro sensor unit
- 8x 4.2A brushed ESCs, integrated, to run the strongest micro motors
- extra-wide traces on the PCB, for maximum power throughput
- USB port, integrated
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100 or Lemon RX)
- alternatively PPM receiver connection (i.e. Deltang Rx31)
- ground and 3.3V for the receiver
- hardware bind plug for easy binding
- motor connections are at the corners for a clean look with reduced wiring
- dimensions: 29x33mm
- direct operation from an single cell lipoly battery
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset).
Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different.
The pin layout is very similar as the NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The AlienWii32 firmware will be built with TARGET=NAZE and OPTIONS="AlienWii32". The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with an small Quadcopter. An preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienWii32. The mixer can be activated with "mixer custom" in the CLI. To use the AlienWii32 in an Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the Cleanflight configurator.

View file

@ -37,7 +37,7 @@ When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but two
| Pin | Identifier | Function | Notes |
| --- | ---------- | -------------- | -------------------------------- |
| 7 | 5 | SOFTSERIAL1 TX | Enable `feature SOFTSERIAL` |
| 8 | 6 | SOFTSERIAL1 RX | |
| 9 | 7 | SOFTSERIAL2 TX | |
| 10 | 8 | SOFTSERIAL2 RX | |
| 7 | 5 | SOFTSERIAL1 RX | Enable `feature SOFTSERIAL`|
| 8 | 6 | SOFTSERIAL1 TX | |
| 9 | 7 | SOFTSERIAL2 RX | |
| 10 | 8 | SOFTSERIAL2 TX | |

View file

@ -23,6 +23,7 @@ Tested with revision 1 board.
* Sonar
* Display (via Flex port)
* Softserial - though having 3 hardware serial ports makes it a little redundant.
* Airplane PWM mappings.
# Flashing

View file

@ -22,9 +22,15 @@ The failsafe system attempts to detect when your receiver looses signal. It the
The failsafe is activated when:
Either:
a) no valid channel data from the RX via Serial RX.
b) the first 4 Parallel PWM/PPM channels do not have valid signals.
And:
c) the failsafe guard time specified by `failsafe_delay` has elapsed.
## Configuration
There are a few settings for it, as below.
Failsafe delays are configured in 0.1 second steps.

49
docs/Spektrum bind.md Normal file
View file

@ -0,0 +1,49 @@
# Spektrum bind support
Spektrum bind with hardware bind plug support.
The Spektrum bind code is actually enabled for the NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY, CC3D targets.
## Configure the bind code
The following parameters can be used to enable and configure this in the related target.h file:
SPEKTRUM_BIND Enables the Spektrum bind code
BIND_PORT GPIOA Defines the port for the bind pin
BIND_PIN Pin_3 Defines the bind pin (the satellite receiver is connected to)
This is to activate the hardware bind plug feature
HARDWARE_BIND_PLUG Enables the hardware bind plug feature
BINDPLUG_PORT GPIOB Defines the port for the hardware bind plug
BINDPLUG_PIN Pin_5 Defines the hardware bind plug pin
## Hardware
The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during building of the firmware. BINDPLUG_PORT and BINDPLUG_PIN also need to be defined (please see above). This is done automatically if the AlienWii32 firmware is build. The hardware bind plug is expected between the defined bind pin and ground.
## Function
The bind code will actually work for NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY targets (USART2) and CC3D target (USART3, flex port). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
If the hardware bind plug is configured the bind mode will only be activated if the plug is set during the firmware start-up. The value of the spektrum_sat_bind parameter will be permanently preserved. The bind plug should be always removed for normal flying.
If no hardware bind plug is used the spektrum_sat_bind parameter will trigger the bind process during the next hardware reset and will be automatically reset to "0" after this.
Please refer to the satellite receiver documentation for more details of the specific receiver in bind mode. Usually the bind mode will be indicated with some flashing LEDs.
## Table with spektrum_sat_bind parameter value
| Value | Receiver mode | Notes |
| ----- | ---------------| -------------------|
| 3 | DSM2 1024/22ms | |
| 5 | DSM2 2048/11ms | default AlienWii32 |
| 7 | DSMX 22ms | |
| 9 | DSMX 11ms | |
More detailed information regarding the satellite binding process can be found here:
http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
### Supported Hardware
NAZE, NAZE32PRO, CJMCU, SPARKY, EUSTM32F103RC, CC3D targets (AlienWii32 with hardware bind plug)

View file

@ -352,6 +352,7 @@ static void resetConf(void)
masterConfig.retarded_arm = 0;
masterConfig.disarm_kill_switch = 1;
masterConfig.auto_disarm_delay = 5;
masterConfig.small_angle = 25;
masterConfig.airplaneConfig.flaps_speed = 0;
@ -444,6 +445,71 @@ static void resetConf(void)
applyDefaultLedStripConfig(masterConfig.ledConfigs);
#endif
// alternative defaults AlienWii32 (activate via OPTIONS="ALIENWII32" during make for NAZE target)
#ifdef ALIENWII32
featureSet(FEATURE_RX_SERIAL);
featureSet(FEATURE_MOTOR_STOP);
featureSet(FEATURE_FAILSAFE);
masterConfig.serialConfig.serial_port_scenario[1] = lookupScenarioIndex(SCENARIO_SERIAL_RX_ONLY);
masterConfig.rxConfig.serialrx_provider = 1;
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.escAndServoConfig.minthrottle = 1000;
masterConfig.escAndServoConfig.maxthrottle = 2000;
masterConfig.motor_pwm_rate = 32000;
currentControlRateProfile->rcRate8 = 130;
currentControlRateProfile->rollPitchRate = 20;
currentControlRateProfile->yawRate = 60;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
// { 1.0f, -0.5f, 1.0f, -1.0f }, // REAR_R
masterConfig.customMixer[0].throttle = 1.0f;
masterConfig.customMixer[0].roll = -0.5f;
masterConfig.customMixer[0].pitch = 1.0f;
masterConfig.customMixer[0].yaw = -1.0f;
// { 1.0f, -0.5f, -1.0f, 1.0f }, // FRONT_R
masterConfig.customMixer[1].throttle = 1.0f;
masterConfig.customMixer[1].roll = -0.5f;
masterConfig.customMixer[1].pitch = -1.0f;
masterConfig.customMixer[1].yaw = 1.0f;
// { 1.0f, 0.5f, 1.0f, 1.0f }, // REAR_L
masterConfig.customMixer[2].throttle = 1.0f;
masterConfig.customMixer[2].roll = 0.5f;
masterConfig.customMixer[2].pitch = 1.0f;
masterConfig.customMixer[2].yaw = 1.0f;
// { 1.0f, 0.5f, -1.0f, -1.0f }, // FRONT_L
masterConfig.customMixer[3].throttle = 1.0f;
masterConfig.customMixer[3].roll = 0.5f;
masterConfig.customMixer[3].pitch = -1.0f;
masterConfig.customMixer[3].yaw = -1.0f;
// { 1.0f, -1.0f, -0.5f, -1.0f }, // MIDFRONT_R
masterConfig.customMixer[4].throttle = 1.0f;
masterConfig.customMixer[4].roll = -1.0f;
masterConfig.customMixer[4].pitch = -0.5f;
masterConfig.customMixer[4].yaw = -1.0f;
// { 1.0f, 1.0f, -0.5f, 1.0f }, // MIDFRONT_L
masterConfig.customMixer[5].throttle = 1.0f;
masterConfig.customMixer[5].roll = 1.0f;
masterConfig.customMixer[5].pitch = -0.5f;
masterConfig.customMixer[5].yaw = 1.0f;
// { 1.0f, -1.0f, 0.5f, 1.0f }, // MIDREAR_R
masterConfig.customMixer[6].throttle = 1.0f;
masterConfig.customMixer[6].roll = -1.0f;
masterConfig.customMixer[6].pitch = 0.5f;
masterConfig.customMixer[6].yaw = 1.0f;
// { 1.0f, 1.0f, 0.5f, -1.0f }, // MIDREAR_L
masterConfig.customMixer[7].throttle = 1.0f;
masterConfig.customMixer[7].roll = 1.0f;
masterConfig.customMixer[7].pitch = 0.5f;
masterConfig.customMixer[7].yaw = -1.0f;
#endif
// copy first profile into remaining profile
for (i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));

View file

@ -63,6 +63,7 @@ typedef struct master_t {
uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
uint8_t small_angle;
airplaneConfig_t airplaneConfig;

View file

@ -297,7 +297,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
// this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ]
if (init->airplane)
i = 2; // switch to air hardware config
if (init->usePPM)
if (init->usePPM || init->useSerialRx)
i++; // next index is for PPM
setup = hardwareMaps[i];

View file

@ -39,6 +39,7 @@
typedef struct drv_pwm_config_t {
bool useParallelPWM;
bool usePPM;
bool useSerialRx;
bool useRSSIADC;
bool useCurrentMeterADC;
#ifdef STM32F10X

View file

@ -189,7 +189,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

@ -573,7 +573,7 @@ void applyLedWarningLayer(uint8_t updateNow)
if (feature(FEATURE_VBAT) && calculateBatteryState() != BATTERY_OK) {
warningFlags |= WARNING_FLAG_LOW_BATTERY;
}
if (failsafe->vTable->hasTimerElapsed()) {
if (feature(FEATURE_FAILSAFE) && failsafe->vTable->hasTimerElapsed()) {
warningFlags |= WARNING_FLAG_FAILSAFE;
}
if (!ARMING_FLAG(ARMED) && !ARMING_FLAG(OK_TO_ARM)) {

View file

@ -57,6 +57,11 @@ int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+
uint32_t rcModeActivationMask; // one bit per mode defined in boxId_e
bool isUsingSticksForArming(void)
{
return isUsingSticksToArm;
}
bool areSticksInApModePosition(uint16_t ap_mode)
{
return abs(rcCommand[ROLL]) < ap_mode && abs(rcCommand[PITCH]) < ap_mode;
@ -519,6 +524,8 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
escAndServoConfig = escAndServoConfigToUse;
pidProfile = pidProfileToUse;
isUsingSticksToArm = true;
for (index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[index];
if (modeActivationCondition->modeId == BOXARM && IS_RANGE_USABLE(&modeActivationCondition->range)) {

View file

@ -213,3 +213,4 @@ void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmen
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig);
bool isUsingSticksForArming(void);

View file

@ -81,7 +81,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},
@ -102,7 +102,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}
@ -118,7 +118,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, 250000, SPF_NONE | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
{SERIAL_PORT_USART2, 9600, 250000, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_BIDIR_MODE},
#if (SERIAL_PORT_COUNT > 2)
@ -544,9 +544,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

@ -73,42 +73,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 {
@ -125,6 +101,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

@ -236,6 +236,7 @@ const clivalue_t valueTable[] = {
{ "retarded_arm", VAR_UINT8 | MASTER_VALUE, &masterConfig.retarded_arm, 0, 1 },
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, 0, 60 },
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
{ "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },

View file

@ -80,6 +80,8 @@ extern uint16_t cycleTime; // FIXME dependency on mw.c
extern uint16_t rssi; // FIXME dependency on mw.c
extern int16_t debug[4]; // FIXME dependency on mw.c
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
/**
* MSP Guidelines, emphasis is used to clarify.
*
@ -96,7 +98,7 @@ extern int16_t debug[4]; // FIXME dependency on mw.c
* 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
@ -119,7 +121,7 @@ extern int16_t debug[4]; // FIXME dependency on mw.c
#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
@ -152,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
@ -204,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)
//
@ -211,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
@ -655,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]);
}
@ -692,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]);
@ -700,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
@ -760,7 +764,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_RAW_IMU:
headSerialReply(18);
// Retarded hack until multiwiidorks start using real units for sensor data
// Hack due to choice of units for sensor data in multiwii
if (acc_1G > 1024) {
for (i = 0; i < 3; i++)
serialize16(accSmooth[i] / 8);
@ -1050,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);
@ -1066,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);
@ -1088,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
@ -1172,6 +1191,8 @@ static bool processInCommand(void)
mac->auxChannelIndex = read8();
mac->range.startStep = read8();
mac->range.endStep = read8();
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, &currentProfile->pidProfile);
} else {
headSerialError(0);
}
@ -1364,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
@ -1385,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++) {
@ -1469,6 +1508,7 @@ static void mspProcessPort(void)
tailSerialReply();
}
currentPort->c_state = IDLE;
break; // process one command so as not to block.
}
}
}

View file

@ -290,6 +290,7 @@ void init(void)
pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP);
pwm_params.usePPM = feature(FEATURE_RX_PPM);
pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
pwm_params.useSerialRx = feature(FEATURE_RX_SERIAL);
pwm_params.useServos = isMixerUsingServos();
pwm_params.extraServos = currentProfile->gimbalConfig.gimbal_flags & GIMBAL_FORWARDAUX;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;

View file

@ -91,6 +91,7 @@ uint16_t cycleTime = 0; // this is the number in micro second to achieve
int16_t headFreeModeHold;
int16_t telemTemperature1; // gyro sensor temperature
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
extern uint8_t dynP8[3], dynI8[3], dynD8[3];
extern failsafe_t *failsafe;
@ -326,6 +327,8 @@ void mwArm(void)
}
}
#endif
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
return;
}
}
@ -493,6 +496,21 @@ void processRx(void)
resetErrorAngle();
resetErrorGyro();
}
// When armed and motors aren't spinning, disarm board after delay so users without buzzer won't lose fingers.
// mixTable constrains motor commands, so checking throttleStatus is enough
if (
ARMING_FLAG(ARMED)
&& feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING)
&& masterConfig.auto_disarm_delay != 0
&& isUsingSticksForArming()
) {
if (throttleStatus == THROTTLE_LOW) {
if ((int32_t)(disarmAt - millis()) < 0) // delay is over
mwDisarm();
} else {
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // extend delay
}
}
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, masterConfig.retarded_arm, masterConfig.disarm_kill_switch);

View file

@ -35,9 +35,14 @@
#include "rx/rx.h"
#include "rx/sbus.h"
#define DEBUG_SBUS_PACKETS
#define SBUS_MAX_CHANNEL 16
#define SBUS_FRAME_SIZE 25
#define SBUS_SYNCBYTE 0x0F
#define SBUS_FRAME_BEGIN_BYTE 0x0F
#define SBUS_FRAME_END_BYTE 0x00
#define SBUS_BAUDRATE 100000
@ -48,6 +53,7 @@ static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
static serialPort_t *sBusPort;
static uint32_t sbusSignalLostEventCount = 0;
void sbusUpdateSerialRxFunctionConstraint(functionConstraint_t *functionConstraint)
{
@ -71,7 +77,14 @@ bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa
return sBusPort != NULL;
}
struct sbus_dat {
#define SBUS_FLAG_RESERVED_1 (1 << 0)
#define SBUS_FLAG_RESERVED_2 (1 << 1)
#define SBUS_FLAG_SIGNAL_LOSS (1 << 2)
#define SBUS_FLAG_FAILSAFE_ACTIVE (1 << 3)
struct sbusFrame_s {
uint8_t syncByte;
// 176 bits of data (11 bits per channel * 16 channels) = 22 bytes.
unsigned int chan0 : 11;
unsigned int chan1 : 11;
unsigned int chan2 : 11;
@ -88,39 +101,53 @@ struct sbus_dat {
unsigned int chan13 : 11;
unsigned int chan14 : 11;
unsigned int chan15 : 11;
uint8_t flags;
uint8_t endByte;
} __attribute__ ((__packed__));
typedef union {
uint8_t in[SBUS_FRAME_SIZE];
struct sbus_dat msg;
} sbus_msg;
uint8_t bytes[SBUS_FRAME_SIZE];
struct sbusFrame_s frame;
} sbusFrame_t;
static sbus_msg sbus;
static sbusFrame_t sbusFrame;
// Receive ISR callback
static void sbusDataReceive(uint16_t c)
{
uint32_t sbusTime;
static uint32_t sbusTimeLast;
static uint8_t sbusFramePosition;
#ifdef DEBUG_SBUS_PACKETS
static uint8_t sbusUnusedFrameCount = 0;
#endif
sbusTime = micros();
if ((sbusTime - sbusTimeLast) > 2500) // sbus2 fast timing
static uint8_t sbusFramePosition = 0;
static uint32_t sbusTimeoutAt = 0;
uint32_t now = millis();
if ((int32_t)(sbusTimeoutAt - now) < 0) {
sbusFramePosition = 0;
sbusTimeLast = sbusTime;
}
sbusTimeoutAt = now + 2500;
if (sbusFramePosition == 0 && c != SBUS_SYNCBYTE)
sbusFrame.bytes[sbusFramePosition] = (uint8_t)c;
if (sbusFramePosition == 0 && c != SBUS_FRAME_BEGIN_BYTE) {
return;
}
sbusFrameDone = false; // lazy main loop didnt fetch the stuff
if (sbusFramePosition != 0)
sbus.in[sbusFramePosition - 1] = (uint8_t)c;
sbusFramePosition++;
if (sbusFramePosition == SBUS_FRAME_SIZE - 1) {
if (sbusFramePosition == SBUS_FRAME_SIZE) {
if (sbusFrame.frame.endByte == SBUS_FRAME_END_BYTE) {
sbusFrameDone = true;
}
sbusFramePosition = 0;
} else {
sbusFramePosition++;
#ifdef DEBUG_SBUS_PACKETS
if (sbusFrameDone) {
sbusUnusedFrameCount++;
}
#endif
sbusFrameDone = false;
}
}
@ -130,26 +157,32 @@ bool sbusFrameComplete(void)
return false;
}
sbusFrameDone = false;
if ((sbus.in[SBUS_FRAME_SIZE - 3] >> 3) & 0x0001) {
if (sbusFrame.frame.flags & SBUS_FLAG_SIGNAL_LOSS) {
// internal failsafe enabled and rx failsafe flag set
sbusSignalLostEventCount++;
}
if (sbusFrame.frame.flags & SBUS_FLAG_FAILSAFE_ACTIVE) {
// internal failsafe enabled and rx failsafe flag set
return false;
}
sbusChannelData[0] = sbus.msg.chan0;
sbusChannelData[1] = sbus.msg.chan1;
sbusChannelData[2] = sbus.msg.chan2;
sbusChannelData[3] = sbus.msg.chan3;
sbusChannelData[4] = sbus.msg.chan4;
sbusChannelData[5] = sbus.msg.chan5;
sbusChannelData[6] = sbus.msg.chan6;
sbusChannelData[7] = sbus.msg.chan7;
sbusChannelData[8] = sbus.msg.chan8;
sbusChannelData[9] = sbus.msg.chan9;
sbusChannelData[10] = sbus.msg.chan10;
sbusChannelData[11] = sbus.msg.chan11;
sbusChannelData[12] = sbus.msg.chan12;
sbusChannelData[13] = sbus.msg.chan13;
sbusChannelData[14] = sbus.msg.chan14;
sbusChannelData[15] = sbus.msg.chan15;
sbusChannelData[0] = sbusFrame.frame.chan0;
sbusChannelData[1] = sbusFrame.frame.chan1;
sbusChannelData[2] = sbusFrame.frame.chan2;
sbusChannelData[3] = sbusFrame.frame.chan3;
sbusChannelData[4] = sbusFrame.frame.chan4;
sbusChannelData[5] = sbusFrame.frame.chan5;
sbusChannelData[6] = sbusFrame.frame.chan6;
sbusChannelData[7] = sbusFrame.frame.chan7;
sbusChannelData[8] = sbusFrame.frame.chan8;
sbusChannelData[9] = sbusFrame.frame.chan9;
sbusChannelData[10] = sbusFrame.frame.chan10;
sbusChannelData[11] = sbusFrame.frame.chan11;
sbusChannelData[12] = sbusFrame.frame.chan12;
sbusChannelData[13] = sbusFrame.frame.chan13;
sbusChannelData[14] = sbusFrame.frame.chan14;
sbusChannelData[15] = sbusFrame.frame.chan15;
return true;
}

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)
@ -132,3 +132,12 @@
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
// alternative defaults AlienWii32 (activate via OPTIONS="ALIENWII32" during make for NAZE target)
#ifdef ALIENWII32
#define BRUSHED_MOTORS
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB5 (Pin 41)
#define BINDPLUG_PORT GPIOB
#define BINDPLUG_PIN Pin_5
#endif

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