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

Merge with upstream

This commit is contained in:
Joel Fuster 2015-01-10 14:31:34 -05:00
commit 09862aed78
80 changed files with 2728 additions and 515 deletions

1273
src/main/blackbox/blackbox.c Normal file

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,47 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "common/axis.h"
#include <stdint.h>
typedef struct blackboxValues_t {
uint32_t time;
int32_t axisPID_P[XYZ_AXIS_COUNT], axisPID_I[XYZ_AXIS_COUNT], axisPID_D[XYZ_AXIS_COUNT];
int16_t rcCommand[4];
int16_t gyroData[XYZ_AXIS_COUNT];
int16_t accSmooth[XYZ_AXIS_COUNT];
int16_t motor[MAX_SUPPORTED_MOTORS];
int16_t servo[MAX_SUPPORTED_SERVOS];
uint16_t vbatLatest;
#ifdef BARO
int32_t BaroAlt;
#endif
#ifdef MAG
int16_t magADC[XYZ_AXIS_COUNT];
#endif
} blackboxValues_t;
void initBlackbox(void);
void handleBlackbox(void);
void startBlackbox(void);
void finishBlackbox(void);

View file

@ -0,0 +1,100 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef enum FlightLogFieldCondition {
FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7,
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8,
FLIGHT_LOG_FIELD_CONDITION_TRICOPTER,
FLIGHT_LOG_FIELD_CONDITION_MAG = 20,
FLIGHT_LOG_FIELD_CONDITION_BARO,
FLIGHT_LOG_FIELD_CONDITION_VBAT,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0 = 40,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1,
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2,
FLIGHT_LOG_FIELD_CONDITION_NEVER = 255,
} FlightLogFieldCondition;
typedef enum FlightLogFieldPredictor {
//No prediction:
FLIGHT_LOG_FIELD_PREDICTOR_0 = 0,
//Predict that the field is the same as last frame:
FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS = 1,
//Predict that the slope between this field and the previous item is the same as that between the past two history items:
FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE = 2,
//Predict that this field is the same as the average of the last two history items:
FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2 = 3,
//Predict that this field is minthrottle
FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE = 4,
//Predict that this field is the same as motor 0
FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0 = 5,
//This field always increments
FLIGHT_LOG_FIELD_PREDICTOR_INC = 6,
//Predict this GPS co-ordinate is the GPS home co-ordinate (or no prediction if that coordinate is not set)
FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD = 7,
//Predict 1500
FLIGHT_LOG_FIELD_PREDICTOR_1500 = 8,
//Predict vbatref, the reference ADC level stored in the header
FLIGHT_LOG_FIELD_PREDICTOR_VBATREF = 9
} FlightLogFieldPredictor;
typedef enum FlightLogFieldEncoding {
FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0, // Signed variable-byte
FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1, // Unsigned variable-byte
FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT = 3, // Unsigned variable-byte but we negate the value before storing, value is 14 bits
FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB = 6,
FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7,
FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8,
FLIGHT_LOG_FIELD_ENCODING_NULL = 9 // Nothing is written to the file, take value to be zero
} FlightLogFieldEncoding;
typedef enum FlightLogFieldSign {
FLIGHT_LOG_FIELD_UNSIGNED = 0,
FLIGHT_LOG_FIELD_SIGNED = 1
} FlightLogFieldSign;
typedef enum FlightLogEvent {
FLIGHT_LOG_EVENT_SYNC_BEEP = 0,
FLIGHT_LOG_EVENT_LOG_END = 255
} FlightLogEvent;

View file

@ -447,6 +447,11 @@ static void resetConf(void)
applyDefaultLedStripConfig(masterConfig.ledConfigs);
#endif
#ifdef BLACKBOX
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
#endif
// alternative defaults AlienWii32 (activate via OPTIONS="ALIENWII32" during make for NAZE target)
#ifdef ALIENWII32
featureSet(FEATURE_RX_SERIAL);
@ -571,28 +576,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;
@ -600,8 +614,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

@ -40,7 +40,8 @@ typedef enum {
FEATURE_RSSI_ADC = 1 << 15,
FEATURE_LED_STRIP = 1 << 16,
FEATURE_DISPLAY = 1 << 17,
FEATURE_ONESHOT125 = 1 << 18
FEATURE_ONESHOT125 = 1 << 18,
FEATURE_BLACKBOX = 1 << 19
} features_e;
bool feature(uint32_t mask);

View file

@ -85,6 +85,8 @@ typedef struct master_t {
uint8_t current_profile_index;
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
uint8_t blackbox_rate_num;
uint8_t blackbox_rate_denom;
uint8_t magic_ef; // magic number, should be 0xEF
uint8_t chk; // XOR checksum

View file

@ -48,4 +48,20 @@
#define LED1_ON
#endif
#ifdef LED2
#define LED2_TOGGLE digitalToggle(LED2_GPIO, LED2_PIN);
#ifndef LED2_INVERTED
#define LED2_OFF digitalHi(LED2_GPIO, LED2_PIN);
#define LED2_ON digitalLo(LED2_GPIO, LED2_PIN);
#else
#define LED2_OFF digitalLo(LED2_GPIO, LED2_PIN);
#define LED2_ON digitalHi(LED2_GPIO, LED2_PIN);
#endif // inverted
#else
#define LED2_TOGGLE
#define LED2_OFF
#define LED2_ON
#endif
void ledInit(void);

View file

@ -46,6 +46,12 @@ void ledInit(void)
{
.gpio = LED1_GPIO,
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
#ifdef LED2
{
.gpio = LED2_GPIO,
.cfg = { LED2_PIN, Mode_Out_PP, Speed_2MHz }
}
#endif
};
@ -58,9 +64,13 @@ void ledInit(void)
#ifdef LED1
RCC_APB2PeriphClockCmd(LED1_PERIPHERAL, ENABLE);
#endif
#ifdef LED2
RCC_APB2PeriphClockCmd(LED2_PERIPHERAL, ENABLE);
#endif
LED0_OFF;
LED1_OFF;
LED2_OFF;
for (i = 0; i < gpio_count; i++) {
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);

View file

@ -45,6 +45,11 @@ extern uint16_t cycleTime;
int16_t heading, magHold;
int16_t axisPID[3];
#ifdef BLACKBOX
int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
#endif
uint8_t dynP8[3], dynI8[3], dynD8[3];
static int32_t errorGyroI[3] = { 0, 0, 0 };
@ -189,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
@ -246,6 +252,12 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
delta1[axis] = delta;
DTerm = (deltaSum * dynD8[axis]) / 32;
axisPID[axis] = PTerm + ITerm - DTerm;
#ifdef BLACKBOX
axisPID_P[axis] = PTerm;
axisPID_I[axis] = ITerm;
axisPID_D[axis] = -DTerm;
#endif
}
}
@ -329,6 +341,12 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
// -----calculate total PID output
axisPID[axis] = PTerm + ITerm + DTerm;
#ifdef BLACKBOX
axisPID_P[axis] = PTerm;
axisPID_I[axis] = ITerm;
axisPID_D[axis] = DTerm;
#endif
}
}

View file

@ -127,6 +127,8 @@ extern int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AX
extern int32_t accSum[XYZ_AXIS_COUNT];
extern int16_t axisPID[XYZ_AXIS_COUNT];
extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
extern int16_t heading, magHold;
extern int32_t AltHold;

View file

@ -121,6 +121,5 @@ void writeAllMotors(int16_t mc);
void mixerLoadMix(int index, motorMixer_t *customMixers);
void mixerResetMotors(void);
void mixTable(void);
void filterServos(void);
void writeServos(void);
void writeMotors(void);

View file

@ -62,7 +62,10 @@ const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUN
SCENARIO_CLI_ONLY,
SCENARIO_GPS_PASSTHROUGH_ONLY,
SCENARIO_MSP_ONLY,
SCENARIO_SMARTPORT_TELEMETRY_ONLY
SCENARIO_SMARTPORT_TELEMETRY_ONLY,
SCENARIO_BLACKBOX_ONLY,
SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH
};
static serialConfig_t *serialConfig;
@ -81,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},
@ -102,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}
@ -118,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)
@ -136,7 +139,8 @@ const functionConstraint_t functionConstraints[] = {
{ FUNCTION_MSP, 9600, 115200, NO_AUTOBAUD, SPF_NONE },
{ FUNCTION_SERIAL_RX, 9600, 115200, NO_AUTOBAUD, SPF_SUPPORTS_SBUS_MODE | SPF_SUPPORTS_CALLBACK },
{ FUNCTION_TELEMETRY, 9600, 19200, NO_AUTOBAUD, SPF_NONE },
{ FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE }
{ FUNCTION_SMARTPORT_TELEMETRY, 57600, 57600, NO_AUTOBAUD, SPF_SUPPORTS_BIDIR_MODE },
{ FUNCTION_BLACKBOX, 115200,115200, NO_AUTOBAUD, SPF_NONE }
};
#define FUNCTION_CONSTRAINT_COUNT (sizeof(functionConstraints) / sizeof(functionConstraint_t))
@ -544,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

@ -25,7 +25,8 @@ typedef enum {
FUNCTION_SMARTPORT_TELEMETRY = (1 << 3),
FUNCTION_SERIAL_RX = (1 << 4),
FUNCTION_GPS = (1 << 5),
FUNCTION_GPS_PASSTHROUGH = (1 << 6)
FUNCTION_GPS_PASSTHROUGH = (1 << 6),
FUNCTION_BLACKBOX = (1 << 7)
} serialPortFunction_e;
typedef enum {
@ -52,10 +53,12 @@ typedef enum {
SCENARIO_MSP_CLI_TELEMETRY_GPS_PASTHROUGH = FUNCTION_MSP | FUNCTION_CLI | FUNCTION_TELEMETRY | FUNCTION_SMARTPORT_TELEMETRY | FUNCTION_GPS_PASSTHROUGH,
SCENARIO_SERIAL_RX_ONLY = FUNCTION_SERIAL_RX,
SCENARIO_TELEMETRY_ONLY = FUNCTION_TELEMETRY,
SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY
SCENARIO_SMARTPORT_TELEMETRY_ONLY = FUNCTION_SMARTPORT_TELEMETRY,
SCENARIO_BLACKBOX_ONLY = FUNCTION_BLACKBOX,
SCENARIO_MSP_CLI_BLACKBOX_GPS_PASTHROUGH = FUNCTION_CLI | FUNCTION_MSP | FUNCTION_BLACKBOX | FUNCTION_GPS_PASSTHROUGH
} serialPortFunctionScenario_e;
#define SERIAL_PORT_SCENARIO_COUNT 10
#define SERIAL_PORT_SCENARIO_COUNT 12
#define SERIAL_PORT_SCENARIO_MAX (SERIAL_PORT_SCENARIO_COUNT - 1)
extern const serialPortFunctionScenario_e serialPortScenarios[SERIAL_PORT_SCENARIO_COUNT];
@ -73,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 {
@ -125,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

@ -135,7 +135,8 @@ static const char * const featureNames[] = {
"RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", NULL
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
"BLACKBOX", NULL
};
// sync this with sensors_e
@ -219,7 +220,7 @@ const clivalue_t valueTable[] = {
{ "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, 0, MAX_SUPPORTED_RC_CHANNEL_COUNT },
{ "rssi_scale", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, RSSI_SCALE_MIN, RSSI_SCALE_MAX },
{ "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, RSSI_SCALE_MIN, RSSI_SCALE_MAX },
{ "input_filtering_mode", VAR_INT8 | MASTER_VALUE, &masterConfig.inputFilteringMode, 0, 1 },
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
@ -406,6 +407,9 @@ const clivalue_t valueTable[] = {
{ "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], 0, 200 },
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
};
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))

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 2 // 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);
@ -1080,7 +1097,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_LED_STRIP_CONFIG:
headSerialReply(MAX_LED_STRIP_LENGTH * 4);
headSerialReply(MAX_LED_STRIP_LENGTH * 6);
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
serialize16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET);
@ -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
@ -1128,10 +1145,16 @@ static bool processInCommand(void)
magHold = read16();
break;
case MSP_SET_RAW_RC:
// FIXME need support for more than 8 channels
for (i = 0; i < 8; i++)
rcData[i] = read16();
rxMspFrameRecieve();
{
uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t);
if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) {
headSerialError(0);
} else {
for (i = 0; i < channelCount; i++)
rcData[i] = read16();
rxMspFrameRecieve();
}
}
break;
case MSP_SET_ACC_TRIM:
currentProfile->accelerometerTrims.values.pitch = read16();
@ -1368,7 +1391,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 +1412,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++) {
@ -1400,22 +1441,29 @@ static bool processInCommand(void)
break;
case MSP_SET_LED_STRIP_CONFIG:
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
uint16_t mask;
// currently we're storing directions and functions in a uint16 (flags)
// the msp uses 2 x uint16_t to cater for future expansion
mask = read16();
ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK;
{
uint8_t ledCount = currentPort->dataSize / 6;
if (ledCount != MAX_LED_STRIP_LENGTH) {
headSerialError(0);
break;
}
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
uint16_t mask;
// currently we're storing directions and functions in a uint16 (flags)
// the msp uses 2 x uint16_t to cater for future expansion
mask = read16();
ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK;
mask = read16();
ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
mask = read16();
ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
mask = read8();
ledConfig->xy = CALCULATE_LED_X(mask);
mask = read8();
ledConfig->xy = CALCULATE_LED_X(mask);
mask = read8();
ledConfig->xy |= CALCULATE_LED_Y(mask);
mask = read8();
ledConfig->xy |= CALCULATE_LED_Y(mask);
}
}
break;
#endif

View file

@ -66,6 +66,7 @@
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "config/runtime_config.h"
@ -73,8 +74,8 @@
#include "config/config_profile.h"
#include "config/config_master.h"
#ifdef NAZE
#include "target/NAZE/hardware_revision.h"
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
#include "build_config.h"
@ -145,13 +146,15 @@ void init(void)
SetSysClock(masterConfig.emf_avoidance);
#endif
#ifdef NAZE
#ifdef USE_HARDWARE_REVISION_DETECTION
detectHardwareRevision();
#endif
systemInit();
#ifdef SPEKTRUM_BIND
ledInit();
#ifdef SPEKTRUM_BIND
if (feature(FEATURE_RX_SERIAL)) {
switch (masterConfig.rxConfig.serialrx_provider) {
case SERIALRX_SPEKTRUM1024:
@ -169,8 +172,6 @@ void init(void)
timerInit(); // timer must be initialized before any channel is allocated
ledInit();
#ifdef BEEPER
beeperConfig_t beeperConfig = {
.gpioMode = Mode_Out_OD,
@ -200,7 +201,7 @@ void init(void)
spiInit(SPI2);
#endif
#ifdef NAZE
#ifdef USE_HARDWARE_REVISION_DETECTION
updateHardwareRevision();
#endif
@ -344,6 +345,10 @@ void init(void)
initTelemetry();
#endif
#ifdef BLACKBOX
initBlackbox();
#endif
previousTime = micros();
if (masterConfig.mixerMode == MIXER_GIMBAL) {
@ -385,6 +390,10 @@ void init(void)
#endif
}
#endif
#ifdef CJMCU
LED2_ON;
#endif
}
#ifdef SOFTSERIAL_LOOPBACK

View file

@ -67,6 +67,7 @@
#include "io/statusindicator.h"
#include "rx/msp.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox.h"
#include "config/runtime_config.h"
#include "config/config.h"
@ -306,6 +307,15 @@ void mwDisarm(void)
}
}
#endif
#ifdef BLACKBOX
if (feature(FEATURE_BLACKBOX)) {
finishBlackbox();
if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
mspAllocateSerialPorts(&masterConfig.serialConfig);
}
}
#endif
}
}
@ -327,6 +337,16 @@ void mwArm(void)
}
}
#endif
#ifdef BLACKBOX
if (feature(FEATURE_BLACKBOX)) {
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
if (sharedBlackboxAndMspPort) {
mspReleasePortIfAllocated(sharedBlackboxAndMspPort);
}
startBlackbox();
}
#endif
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
return;
@ -539,17 +559,17 @@ void processRx(void)
DISABLE_FLIGHT_MODE(ANGLE_MODE); // failsafe support
}
if (IS_RC_MODE_ACTIVE(BOXHORIZON) && canUseHorizonMode) {
if (IS_RC_MODE_ACTIVE(BOXHORIZON) && canUseHorizonMode) {
DISABLE_FLIGHT_MODE(ANGLE_MODE);
DISABLE_FLIGHT_MODE(ANGLE_MODE);
if (!FLIGHT_MODE(HORIZON_MODE)) {
resetErrorAngle();
ENABLE_FLIGHT_MODE(HORIZON_MODE);
}
} else {
DISABLE_FLIGHT_MODE(HORIZON_MODE);
}
if (!FLIGHT_MODE(HORIZON_MODE)) {
resetErrorAngle();
ENABLE_FLIGHT_MODE(HORIZON_MODE);
}
} else {
DISABLE_FLIGHT_MODE(HORIZON_MODE);
}
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
LED1_ON;
@ -696,9 +716,14 @@ void loop(void)
);
mixTable();
filterServos();
writeServos();
writeMotors();
#ifdef BLACKBOX
if (!cliMode && feature(FEATURE_BLACKBOX)) {
handleBlackbox();
}
#endif
}
#ifdef TELEMETRY

View file

@ -265,6 +265,10 @@ void processRxChannels(void)
{
uint8_t chan;
if (feature(FEATURE_RX_MSP)) {
return; // rcData will have already been updated by MSP_SET_RAW_RC
}
bool shouldCheckPulse = true;
if (feature(FEATURE_FAILSAFE) && feature(FEATURE_RX_PPM)) {
@ -341,7 +345,7 @@ void parseRcChannels(const char *input, rxConfig_t *rxConfig)
for (c = input; *c; c++) {
s = strchr(rcChannelLetters, *c);
if (s)
if (s && (s < rcChannelLetters + MAX_MAPPABLE_RX_INPUTS))
rxConfig->rcmap[s - rcChannelLetters] = c - input;
}
}

View file

@ -24,6 +24,8 @@
#include "drivers/gpio.h"
#include "drivers/system.h"
#include "drivers/light_led.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "io/serial.h"
@ -176,11 +178,12 @@ bool spekShouldBind(uint8_t spektrum_sat_bind)
void spektrumBind(rxConfig_t *rxConfig)
{
int i;
if (!spekShouldBind(rxConfig->spektrum_sat_bind)) {
return;
}
LED1_ON;
gpio_config_t cfg = {
BIND_PIN,
Mode_Out_OD,
@ -193,16 +196,22 @@ void spektrumBind(rxConfig_t *rxConfig)
// Bind window is around 20-140ms after powerup
delay(60);
LED1_OFF;
for (i = 0; i < rxConfig->spektrum_sat_bind; i++) {
LED0_OFF;
LED2_OFF;
// RX line, drive low for 120us
digitalLo(BIND_PORT, BIND_PIN);
delayMicroseconds(120);
LED0_ON;
LED2_ON;
// RX line, drive high for 120us
digitalHi(BIND_PORT, BIND_PIN);
delayMicroseconds(120);
}
#ifndef HARDWARE_BIND_PLUG

View file

@ -31,6 +31,7 @@ uint16_t batteryWarningVoltage;
uint16_t batteryCriticalVoltage;
uint8_t vbat = 0; // battery voltage in 0.1V steps
uint16_t vbatLatest = 0; // most recent unsmoothed raw reading from vbat adc
int32_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A)
int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
@ -54,7 +55,7 @@ void updateBatteryVoltage(void)
uint16_t vbatSampleTotal = 0;
// store the battery voltage with some other recent battery voltage readings
vbatSamples[(currentSampleIndex++) % BATTERY_SAMPLE_COUNT] = adcGetChannel(ADC_BATTERY);
vbatSamples[(currentSampleIndex++) % BATTERY_SAMPLE_COUNT] = vbatLatest = adcGetChannel(ADC_BATTERY);
// calculate vbat based on the average of recent readings
for (index = 0; index < BATTERY_SAMPLE_COUNT; index++) {

View file

@ -42,6 +42,7 @@ typedef enum {
} batteryState_e;
extern uint8_t vbat;
extern uint16_t vbatLatest;
extern uint8_t batteryCellCount;
extern uint16_t batteryWarningVoltage;
extern int32_t amperage;

View file

@ -77,6 +77,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -71,6 +71,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM16
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -0,0 +1,53 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "build_config.h"
#include "drivers/system.h"
#include "drivers/bus_spi.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/accgyro_spi_mpu6500.h"
#include "hardware_revision.h"
static const char * const hardwareRevisionNames[] = {
"Unknown",
"R1",
"R2"
};
uint8_t hardwareRevision = UNKNOWN;
void detectHardwareRevision(void)
{
if (GPIOC->IDR & GPIO_Pin_15) {
hardwareRevision = REV_2;
} else {
hardwareRevision = REV_1;
}
}
void updateHardwareRevision(void)
{
}

View file

@ -0,0 +1,27 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
typedef enum cjmcuHardwareRevision_t {
UNKNOWN = 0,
REV_1, // Blue LED3
REV_2 // Green LED3
} cjmcuHardwareRevision_e;
extern uint8_t hardwareRevision;
void updateHardwareRevision(void);
void detectHardwareRevision(void);

View file

@ -18,16 +18,17 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
#define FLASH_PAGE_COUNT 64
#define FLASH_PAGE_SIZE ((uint16_t)0x400)
#define LED0_GPIO GPIOC
#define LED0_PIN Pin_13 // PC13 (LED)
#define LED0_PIN Pin_14 // PC14 (LED)
#define LED0
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED1_GPIO GPIOC
#define LED1_PIN Pin_14 // PC14 (LED)
#define LED1_PIN Pin_13 // PC13 (LED)
#define LED1
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED2_GPIO GPIOC

View file

@ -104,6 +104,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -17,7 +17,8 @@
#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 USE_HARDWARE_REVISION_DETECTION
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
@ -124,6 +125,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -43,6 +43,7 @@
#define SENSORS_SET (SENSOR_ACC)
#define GPS
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -102,6 +102,7 @@
#define LED_STRIP
#define LED_STRIP_TIMER TIM3
#define BLACKBOX
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE

View file

@ -87,6 +87,7 @@
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
#define BLACKBOX
#define SERIAL_RX
#define GPS
#define DISPLAY

View file

@ -56,6 +56,7 @@
#define SENSORS_SET (SENSOR_ACC)
#define BLACKBOX
#define GPS
#define LED_STRIP
#define LED_STRIP_TIMER TIM16

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 5 // 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