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

Rebased on to master

This commit is contained in:
jflyper 2017-05-07 22:26:47 +09:00
commit 4b80bceb1f
288 changed files with 5099 additions and 2801 deletions

View file

@ -25,6 +25,7 @@
#ifdef BLACKBOX
#include "blackbox.h"
#include "blackbox_encoding.h"
#include "blackbox_io.h"
#include "build/debug.h"
@ -39,10 +40,9 @@
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/sensor.h"
#include "drivers/compass/compass.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/pwm_output.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
@ -65,7 +65,6 @@
#include "sensors/barometer.h"
#include "sensors/battery.h"
#include "sensors/compass.h"
#include "sensors/compass.h"
#include "sensors/gyro.h"
#include "sensors/sonar.h"
@ -83,15 +82,14 @@ PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
.device = DEFAULT_BLACKBOX_DEVICE,
.rate_num = 1,
.rate_denom = 1,
.on_motor_test = 0 // default off
.on_motor_test = 0, // default off
.record_acc = 1
);
#define BLACKBOX_I_INTERVAL 32
#define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
#define SLOW_FRAME_INTERVAL 4096
#define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0]))
#define STATIC_ASSERT(condition, name ) \
typedef char assert_failed_ ## name [(condition) ? 1 : -1 ]
@ -127,7 +125,7 @@ typedef struct blackboxFieldDefinition_s {
uint8_t arr[1];
} blackboxFieldDefinition_t;
#define BLACKBOX_DELTA_FIELD_HEADER_COUNT ARRAY_LENGTH(blackboxFieldHeaderNames)
#define BLACKBOX_DELTA_FIELD_HEADER_COUNT ARRAYLEN(blackboxFieldHeaderNames)
#define BLACKBOX_SIMPLE_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
#define BLACKBOX_CONDITIONAL_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
@ -207,29 +205,29 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
{"rssi", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_RSSI},
/* Gyros and accelerometers base their P-predictions on the average of the previous 2 frames to reduce noise impact */
{"gyroADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"gyroADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"gyroADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"accSmooth", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"accSmooth", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"accSmooth", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"debug", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"debug", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"debug", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"debug", 3, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"gyroADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"gyroADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"gyroADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"accSmooth", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
{"accSmooth", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
{"accSmooth", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
{"debug", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
{"debug", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
{"debug", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
{"debug", 3, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
/* Motors only rarely drops under minthrottle (when stick falls below mincommand), so predict minthrottle for it and use *unsigned* encoding (which is large for negative numbers but more compact for positive ones): */
{"motor", 0, UNSIGNED, .Ipredict = PREDICT(MINMOTOR), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_1)},
{"motor", 0, UNSIGNED, .Ipredict = PREDICT(MINMOTOR), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_1)},
/* Subsequent motors base their I-frame values on the first one, P-frame values on the average of last two frames: */
{"motor", 1, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_2)},
{"motor", 2, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_3)},
{"motor", 3, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_4)},
{"motor", 4, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_5)},
{"motor", 5, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_6)},
{"motor", 6, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_7)},
{"motor", 7, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_8)},
{"motor", 1, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_2)},
{"motor", 2, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_3)},
{"motor", 3, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_4)},
{"motor", 4, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_5)},
{"motor", 5, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_6)},
{"motor", 6, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_7)},
{"motor", 7, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_8)},
/* Tricopter tail servo */
{"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(TRICOPTER)}
{"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(TRICOPTER)}
};
#ifdef GPS
@ -288,7 +286,7 @@ typedef struct blackboxMainState_s {
int16_t rcCommand[4];
int16_t gyroADC[XYZ_AXIS_COUNT];
int16_t accSmooth[XYZ_AXIS_COUNT];
int16_t debug[4];
int16_t debug[DEBUG16_VALUE_COUNT];
int16_t motor[MAX_SUPPORTED_MOTORS];
int16_t servo[MAX_SUPPORTED_SERVOS];
@ -348,7 +346,7 @@ static struct {
// Cache for FLIGHT_LOG_FIELD_CONDITION_* test results:
static uint32_t blackboxConditionCache;
STATIC_ASSERT((sizeof(blackboxConditionCache) * 8) >= FLIGHT_LOG_FIELD_CONDITION_NEVER, too_many_flight_log_conditions);
STATIC_ASSERT((sizeof(blackboxConditionCache) * 8) >= FLIGHT_LOG_FIELD_CONDITION_LAST, too_many_flight_log_conditions);
static uint32_t blackboxIteration;
static uint16_t blackboxPFrameIndex, blackboxIFrameIndex;
@ -376,12 +374,13 @@ static bool blackboxModeActivationConditionPresent = false;
/**
* Return true if it is safe to edit the Blackbox configuration.
*/
bool blackboxMayEditConfig()
bool blackboxMayEditConfig(void)
{
return blackboxState <= BLACKBOX_STATE_STOPPED;
}
static bool blackboxIsOnlyLoggingIntraframes() {
static bool blackboxIsOnlyLoggingIntraframes(void)
{
return blackboxConfig()->rate_num == 1 && blackboxConfig()->rate_denom == 32;
}
@ -442,20 +441,24 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
return blackboxConfig()->rate_num < blackboxConfig()->rate_denom;
case FLIGHT_LOG_FIELD_CONDITION_ACC:
return sensors(SENSOR_ACC) && blackboxConfig()->record_acc;
case FLIGHT_LOG_FIELD_CONDITION_DEBUG:
return debugMode != DEBUG_NONE;
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
return false;
default:
return false;
}
}
static void blackboxBuildConditionCache()
static void blackboxBuildConditionCache(void)
{
FlightLogFieldCondition cond;
blackboxConditionCache = 0;
for (cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) {
for (FlightLogFieldCondition cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) {
if (testBlackboxConditionUncached(cond)) {
blackboxConditionCache |= 1 << cond;
}
@ -567,8 +570,12 @@ static void writeIntraframe(void)
}
blackboxWriteSigned16VBArray(blackboxCurrent->gyroADC, XYZ_AXIS_COUNT);
blackboxWriteSigned16VBArray(blackboxCurrent->accSmooth, XYZ_AXIS_COUNT);
blackboxWriteSigned16VBArray(blackboxCurrent->debug, 4);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
blackboxWriteSigned16VBArray(blackboxCurrent->accSmooth, XYZ_AXIS_COUNT);
}
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
blackboxWriteSigned16VBArray(blackboxCurrent->debug, DEBUG16_VALUE_COUNT);
}
//Motors can be below minimum output when disarmed, but that doesn't happen much
blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - motorOutputLow);
@ -612,7 +619,6 @@ static void blackboxWriteMainStateArrayUsingAveragePredictor(int arrOffsetInHist
static void writeInterframe(void)
{
int x;
int32_t deltas[8];
blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
@ -642,7 +648,7 @@ static void writeInterframe(void)
* The PID D term is frequently set to zero for yaw, which makes the result from the calculation
* always zero. So don't bother recording D results when PID D terms are zero.
*/
for (x = 0; x < XYZ_AXIS_COUNT; x++) {
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x)) {
blackboxWriteSignedVB(blackboxCurrent->axisPID_D[x] - blackboxLast->axisPID_D[x]);
}
@ -652,7 +658,7 @@ static void writeInterframe(void)
* RC tends to stay the same or fairly small for many frames at a time, so use an encoding that
* can pack multiple values per byte:
*/
for (x = 0; x < 4; x++) {
for (int x = 0; x < 4; x++) {
deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x];
}
@ -671,7 +677,7 @@ static void writeInterframe(void)
#ifdef MAG
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
for (x = 0; x < XYZ_AXIS_COUNT; x++) {
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
deltas[optionalFieldCount++] = blackboxCurrent->magADC[x] - blackboxLast->magADC[x];
}
}
@ -697,8 +703,12 @@ static void writeInterframe(void)
//Since gyros, accs and motors are noisy, base their predictions on the average of the history:
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, gyroADC), XYZ_AXIS_COUNT);
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, accSmooth), XYZ_AXIS_COUNT);
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, debug), 4);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, accSmooth), XYZ_AXIS_COUNT);
}
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, debug), DEBUG16_VALUE_COUNT);
}
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, motor), getMotorCount());
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER)) {
@ -753,10 +763,10 @@ static void loadSlowState(blackboxSlowState_t *slow)
* If allowPeriodicWrite is true, the frame is also logged if it has been more than SLOW_FRAME_INTERVAL logging iterations
* since the field was last logged.
*/
static void writeSlowFrameIfNeeded(bool allowPeriodicWrite)
static bool writeSlowFrameIfNeeded(void)
{
// Write the slow frame peridocially so it can be recovered if we ever lose sync
bool shouldWrite = allowPeriodicWrite && blackboxSlowFrameIterationTimer >= SLOW_FRAME_INTERVAL;
bool shouldWrite = blackboxSlowFrameIterationTimer >= SLOW_FRAME_INTERVAL;
if (shouldWrite) {
loadSlowState(&slowHistory);
@ -776,21 +786,11 @@ static void writeSlowFrameIfNeeded(bool allowPeriodicWrite)
if (shouldWrite) {
writeSlowFrame();
}
return shouldWrite;
}
static int gcd(int num, int denom)
void blackboxValidateConfig(void)
{
if (denom == 0) {
return num;
}
return gcd(denom, num % denom);
}
void validateBlackboxConfig()
{
int div;
if (blackboxConfig()->rate_num == 0 || blackboxConfig()->rate_denom == 0
|| blackboxConfig()->rate_num >= blackboxConfig()->rate_denom) {
blackboxConfigMutable()->rate_num = 1;
@ -799,7 +799,7 @@ void validateBlackboxConfig()
/* Reduce the fraction the user entered as much as possible (makes the recorded/skipped frame pattern repeat
* itself more frequently)
*/
div = gcd(blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
const int div = gcd(blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
blackboxConfigMutable()->rate_num /= div;
blackboxConfigMutable()->rate_denom /= div;
@ -814,20 +814,27 @@ void validateBlackboxConfig()
case BLACKBOX_DEVICE_SDCARD:
#endif
case BLACKBOX_DEVICE_SERIAL:
// Device supported, leave the setting alone
// Device supported, leave the setting alone
break;
default:
blackboxConfigMutable()->device = BLACKBOX_DEVICE_SERIAL;
blackboxConfigMutable()->device = BLACKBOX_DEVICE_SERIAL;
}
}
static void blackboxResetIterationTimers(void)
{
blackboxIteration = 0;
blackboxPFrameIndex = 0;
blackboxIFrameIndex = 0;
}
/**
* Start Blackbox logging if it is not already running. Intended to be called upon arming.
*/
void startBlackbox(void)
static void blackboxStart(void)
{
validateBlackboxConfig();
blackboxValidateConfig();
if (!blackboxDeviceOpen()) {
blackboxSetState(BLACKBOX_STATE_DISABLED);
@ -845,22 +852,20 @@ void startBlackbox(void)
//No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
/*
* We use conditional tests to decide whether or not certain fields should be logged. Since our headers
* must always agree with the logged data, the results of these tests must not change during logging. So
* cache those now.
*/
* We use conditional tests to decide whether or not certain fields should be logged. Since our headers
* must always agree with the logged data, the results of these tests must not change during logging. So
* cache those now.
*/
blackboxBuildConditionCache();
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(modeActivationConditions(0), BOXBLACKBOX);
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(modeActivationConditions(0), BOXBLACKBOX);
blackboxIteration = 0;
blackboxPFrameIndex = 0;
blackboxIFrameIndex = 0;
blackboxResetIterationTimers();
/*
* Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
* it finally plays the beep for this arming event.
*/
* Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
* it finally plays the beep for this arming event.
*/
blackboxLastArmingBeep = getArmingBeepTimeMicros();
blackboxLastFlightModeFlags = rcModeActivationMask; // record startup status
@ -870,7 +875,7 @@ void startBlackbox(void)
/**
* Begin Blackbox shutdown.
*/
void finishBlackbox(void)
void blackboxFinish(void)
{
switch (blackboxState) {
case BLACKBOX_STATE_DISABLED:
@ -903,14 +908,14 @@ void startInTestMode(void)
return; // When in test mode, we cannot share the MSP and serial logger port!
}
}
startBlackbox();
blackboxStart();
startedLoggingInTestMode = true;
}
}
void stopInTestMode(void)
{
if(startedLoggingInTestMode) {
finishBlackbox();
blackboxFinish();
startedLoggingInTestMode = false;
}
}
@ -955,7 +960,7 @@ bool inMotorTestMode(void) {
}
#ifdef GPS
static void writeGPSHomeFrame()
static void writeGPSHomeFrame(void)
{
blackboxWrite('H');
@ -1001,50 +1006,36 @@ static void writeGPSFrame(timeUs_t currentTimeUs)
static void loadMainState(timeUs_t currentTimeUs)
{
blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
int i;
blackboxCurrent->time = currentTimeUs;
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
for (int i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->axisPID_P[i] = axisPID_P[i];
}
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->axisPID_I[i] = axisPID_I[i];
}
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->axisPID_D[i] = axisPID_D[i];
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
blackboxCurrent->accSmooth[i] = acc.accSmooth[i];
#ifdef MAG
blackboxCurrent->magADC[i] = mag.magADC[i];
#endif
}
for (i = 0; i < 4; i++) {
for (int i = 0; i < 4; i++) {
blackboxCurrent->rcCommand[i] = rcCommand[i];
}
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
}
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->accSmooth[i] = acc.accSmooth[i];
}
for (i = 0; i < 4; i++) {
for (int i = 0; i < DEBUG16_VALUE_COUNT; i++) {
blackboxCurrent->debug[i] = debug[i];
}
const int motorCount = getMotorCount();
for (i = 0; i < motorCount; i++) {
for (int i = 0; i < motorCount; i++) {
blackboxCurrent->motor[i] = motor[i];
}
blackboxCurrent->vbatLatest = getBatteryVoltageLatest();
blackboxCurrent->amperageLatest = getAmperageLatest();
#ifdef MAG
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->magADC[i] = mag.magADC[i];
}
#endif
#ifdef BARO
blackboxCurrent->BaroAlt = baro.BaroAlt;
#endif
@ -1191,7 +1182,7 @@ static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const v
* Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns
* true iff transmission is complete, otherwise call again later to continue transmission.
*/
static bool blackboxWriteSysinfo()
static bool blackboxWriteSysinfo(void)
{
// Make sure we have enough room in the buffer for our longest line (as of this writing, the "Firmware date" line)
if (blackboxDeviceReserveBufferSpace(64) != BLACKBOX_RESERVE_SUCCESS) {
@ -1236,58 +1227,58 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("rc_rate", "%d", currentControlRateProfile->rcRate8);
BLACKBOX_PRINT_HEADER_LINE("rc_expo", "%d", currentControlRateProfile->rcExpo8);
BLACKBOX_PRINT_HEADER_LINE("rc_rate_yaw", "%d", currentControlRateProfile->rcYawRate8);
BLACKBOX_PRINT_HEADER_LINE("rc_yaw_expo", "%d", currentControlRateProfile->rcYawExpo8);
BLACKBOX_PRINT_HEADER_LINE("rc_expo_yaw", "%d", currentControlRateProfile->rcYawExpo8);
BLACKBOX_PRINT_HEADER_LINE("thr_mid", "%d", currentControlRateProfile->thrMid8);
BLACKBOX_PRINT_HEADER_LINE("thr_expo", "%d", currentControlRateProfile->thrExpo8);
BLACKBOX_PRINT_HEADER_LINE("tpa_rate", "%d", currentControlRateProfile->dynThrPID);
BLACKBOX_PRINT_HEADER_LINE("tpa_breakpoint", "%d", currentControlRateProfile->tpa_breakpoint);
BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile->rates[ROLL],
currentControlRateProfile->rates[PITCH],
currentControlRateProfile->rates[YAW]);
currentControlRateProfile->rates[PITCH],
currentControlRateProfile->rates[YAW]);
BLACKBOX_PRINT_HEADER_LINE("rollPID", "%d,%d,%d", currentPidProfile->P8[ROLL],
currentPidProfile->I8[ROLL],
currentPidProfile->D8[ROLL]);
currentPidProfile->I8[ROLL],
currentPidProfile->D8[ROLL]);
BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d", currentPidProfile->P8[PITCH],
currentPidProfile->I8[PITCH],
currentPidProfile->D8[PITCH]);
currentPidProfile->I8[PITCH],
currentPidProfile->D8[PITCH]);
BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d", currentPidProfile->P8[YAW],
currentPidProfile->I8[YAW],
currentPidProfile->D8[YAW]);
currentPidProfile->I8[YAW],
currentPidProfile->D8[YAW]);
BLACKBOX_PRINT_HEADER_LINE("altPID", "%d,%d,%d", currentPidProfile->P8[PIDALT],
currentPidProfile->I8[PIDALT],
currentPidProfile->D8[PIDALT]);
currentPidProfile->I8[PIDALT],
currentPidProfile->D8[PIDALT]);
BLACKBOX_PRINT_HEADER_LINE("posPID", "%d,%d,%d", currentPidProfile->P8[PIDPOS],
currentPidProfile->I8[PIDPOS],
currentPidProfile->D8[PIDPOS]);
currentPidProfile->I8[PIDPOS],
currentPidProfile->D8[PIDPOS]);
BLACKBOX_PRINT_HEADER_LINE("posrPID", "%d,%d,%d", currentPidProfile->P8[PIDPOSR],
currentPidProfile->I8[PIDPOSR],
currentPidProfile->D8[PIDPOSR]);
currentPidProfile->I8[PIDPOSR],
currentPidProfile->D8[PIDPOSR]);
BLACKBOX_PRINT_HEADER_LINE("navrPID", "%d,%d,%d", currentPidProfile->P8[PIDNAVR],
currentPidProfile->I8[PIDNAVR],
currentPidProfile->D8[PIDNAVR]);
currentPidProfile->I8[PIDNAVR],
currentPidProfile->D8[PIDNAVR]);
BLACKBOX_PRINT_HEADER_LINE("levelPID", "%d,%d,%d", currentPidProfile->P8[PIDLEVEL],
currentPidProfile->I8[PIDLEVEL],
currentPidProfile->D8[PIDLEVEL]);
currentPidProfile->I8[PIDLEVEL],
currentPidProfile->D8[PIDLEVEL]);
BLACKBOX_PRINT_HEADER_LINE("magPID", "%d", currentPidProfile->P8[PIDMAG]);
BLACKBOX_PRINT_HEADER_LINE("velPID", "%d,%d,%d", currentPidProfile->P8[PIDVEL],
currentPidProfile->I8[PIDVEL],
currentPidProfile->D8[PIDVEL]);
currentPidProfile->I8[PIDVEL],
currentPidProfile->D8[PIDVEL]);
BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type", "%d", currentPidProfile->dterm_filter_type);
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz", "%d", currentPidProfile->dterm_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz", "%d", currentPidProfile->yaw_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", currentPidProfile->dterm_notch_hz);
BLACKBOX_PRINT_HEADER_LINE("d_notch_cut", "%d", currentPidProfile->dterm_notch_cutoff);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", currentPidProfile->dterm_notch_cutoff);
BLACKBOX_PRINT_HEADER_LINE("iterm_windup", "%d", currentPidProfile->itermWindupPointPercent);
BLACKBOX_PRINT_HEADER_LINE("vbat_pid_gain", "%d", currentPidProfile->vbatPidCompensation);
BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle", "%d", currentPidProfile->pidAtMinThrottle);
// Betaflight PID controller parameters
BLACKBOX_PRINT_HEADER_LINE("anti_gravity_thresh", "%d", currentPidProfile->itermThrottleThreshold);
BLACKBOX_PRINT_HEADER_LINE("anti_gravity_threshold", "%d", currentPidProfile->itermThrottleThreshold);
BLACKBOX_PRINT_HEADER_LINE("anti_gravity_gain", "%d", currentPidProfile->itermAcceleratorGain);
BLACKBOX_PRINT_HEADER_LINE("setpoint_relax_ratio", "%d", currentPidProfile->setpointRelaxRatio);
BLACKBOX_PRINT_HEADER_LINE("d_setpoint_weight", "%d", currentPidProfile->dtermSetpointWeight);
BLACKBOX_PRINT_HEADER_LINE("yaw_accel_limit", "%d", currentPidProfile->yawRateAccelLimit);
BLACKBOX_PRINT_HEADER_LINE("accel_limit", "%d", currentPidProfile->rateAccelLimit);
BLACKBOX_PRINT_HEADER_LINE("setpoint_relaxation_ratio", "%d", currentPidProfile->setpointRelaxRatio);
BLACKBOX_PRINT_HEADER_LINE("dterm_setpoint_weight", "%d", currentPidProfile->dtermSetpointWeight);
BLACKBOX_PRINT_HEADER_LINE("acc_limit_yaw", "%d", currentPidProfile->yawRateAccelLimit);
BLACKBOX_PRINT_HEADER_LINE("acc_limit", "%d", currentPidProfile->rateAccelLimit);
BLACKBOX_PRINT_HEADER_LINE("pidsum_limit", "%d", currentPidProfile->pidSumLimit);
BLACKBOX_PRINT_HEADER_LINE("pidsum_limit_yaw", "%d", currentPidProfile->pidSumLimitYaw);
// End of Betaflight controller parameters
@ -1296,24 +1287,24 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_type", "%d", gyroConfig()->gyro_soft_lpf_type);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass", "%d", gyroConfig()->gyro_soft_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz", "%d", gyroConfig()->gyro_soft_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1,
gyroConfig()->gyro_soft_notch_hz_2);
gyroConfig()->gyro_soft_notch_hz_2);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1,
gyroConfig()->gyro_soft_notch_cutoff_2);
gyroConfig()->gyro_soft_notch_cutoff_2);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz", "%d", (int)(accelerometerConfig()->acc_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware", "%d", accelerometerConfig()->acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware", "%d", barometerConfig()->baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware", "%d", compassConfig()->mag_hardware);
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm", "%d", armingConfig()->gyro_cal_on_first_arm);
BLACKBOX_PRINT_HEADER_LINE("rc_interp", "%d", rxConfig()->rcInterpolation);
BLACKBOX_PRINT_HEADER_LINE("rc_interp_int", "%d", rxConfig()->rcInterpolationInterval);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation", "%d", rxConfig()->rcInterpolation);
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval", "%d", rxConfig()->rcInterpolationInterval);
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle", "%d", rxConfig()->airModeActivateThreshold);
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider", "%d", rxConfig()->serialrx_provider);
BLACKBOX_PRINT_HEADER_LINE("use_unsynced_pwm", "%d", motorConfig()->dev.useUnsyncedPwm);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_protocol", "%d", motorConfig()->dev.motorPwmProtocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->dev.motorPwmRate);
BLACKBOX_PRINT_HEADER_LINE("digital_idle_value", "%d", motorConfig()->digitalIdleOffsetValue);
BLACKBOX_PRINT_HEADER_LINE("dshot_idle_value", "%d", motorConfig()->digitalIdleOffsetValue);
BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode);
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
@ -1369,7 +1360,7 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
}
/* If an arming beep has played since it was last logged, write the time of the arming beep to the log as a synchronization point */
static void blackboxCheckAndLogArmingBeep()
static void blackboxCheckAndLogArmingBeep(void)
{
flightLogEvent_syncBeep_t eventData;
@ -1384,7 +1375,7 @@ static void blackboxCheckAndLogArmingBeep()
}
/* monitor the flight mode event status and trigger an event record if the state changes */
static void blackboxCheckAndLogFlightMode()
static void blackboxCheckAndLogFlightMode(void)
{
flightLogEvent_flightMode_t eventData; // Add new data for current flight mode flags
@ -1410,12 +1401,31 @@ static bool blackboxShouldLogPFrame(uint32_t pFrameIndex)
return (pFrameIndex + blackboxConfig()->rate_num - 1) % blackboxConfig()->rate_denom < blackboxConfig()->rate_num;
}
static bool blackboxShouldLogIFrame() {
static bool blackboxShouldLogIFrame(void)
{
return blackboxPFrameIndex == 0;
}
/*
* If the GPS home point has been updated, or every 128 I-frames (~10 seconds), write the
* GPS home position.
*
* We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
* still be interpreted correctly.
*/
#ifdef GPS
STATIC_UNIT_TESTED bool blackboxShouldLogGpsHomeFrame(void)
{
if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1]
|| (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) {
return true;
}
return false;
}
#endif
// Called once every FC loop in order to keep track of how many FC loop iterations have passed
static void blackboxAdvanceIterationTimers()
static void blackboxAdvanceIterationTimers(void)
{
blackboxSlowFrameIterationTimer++;
blackboxIteration++;
@ -1436,7 +1446,9 @@ static void blackboxLogIteration(timeUs_t currentTimeUs)
* Don't log a slow frame if the slow data didn't change ("I" frames are already large enough without adding
* an additional item to write at the same time). Unless we're *only* logging "I" frames, then we have no choice.
*/
writeSlowFrameIfNeeded(blackboxIsOnlyLoggingIntraframes());
if (blackboxIsOnlyLoggingIntraframes()) {
writeSlowFrameIfNeeded();
}
loadMainState(currentTimeUs);
writeIntraframe();
@ -1449,23 +1461,14 @@ static void blackboxLogIteration(timeUs_t currentTimeUs)
* We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
* So only log slow frames during loop iterations where we log a main frame.
*/
writeSlowFrameIfNeeded(true);
writeSlowFrameIfNeeded();
loadMainState(currentTimeUs);
writeInterframe();
}
#ifdef GPS
if (feature(FEATURE_GPS)) {
/*
* If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the
* GPS home position.
*
* We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
* still be interpreted correctly.
*/
if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1]
|| (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) {
if (blackboxShouldLogGpsHomeFrame()) {
writeGPSHomeFrame();
writeGPSFrame(currentTimeUs);
} else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0]
@ -1484,15 +1487,13 @@ static void blackboxLogIteration(timeUs_t currentTimeUs)
/**
* Call each flight loop iteration to perform blackbox logging.
*/
void handleBlackbox(timeUs_t currentTimeUs)
void blackboxUpdate(timeUs_t currentTimeUs)
{
int i;
switch (blackboxState) {
case BLACKBOX_STATE_STOPPED:
if (ARMING_FLAG(ARMED)) {
blackboxOpen();
startBlackbox();
blackboxStart();
}
#ifdef USE_FLASHFS
if (IS_RC_MODE_ACTIVE(BOXBLACKBOXERASE)) {
@ -1515,7 +1516,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
*/
if (millis() > xmitState.u.startTime + 100) {
if (blackboxDeviceReserveBufferSpace(BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION) == BLACKBOX_RESERVE_SUCCESS) {
for (i = 0; i < BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
for (int i = 0; i < BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
blackboxWrite(blackboxHeader[xmitState.headerIndex]);
blackboxHeaderBudget--;
}
@ -1529,7 +1530,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER:
blackboxReplenishHeaderBudget();
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAY_LENGTH(blackboxMainFields),
if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAYLEN(blackboxMainFields),
&blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
#ifdef GPS
if (feature(FEATURE_GPS)) {
@ -1543,7 +1544,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
case BLACKBOX_STATE_SEND_GPS_H_HEADER:
blackboxReplenishHeaderBudget();
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
if (!sendFieldDefinition('H', 0, blackboxGpsHFields, blackboxGpsHFields + 1, ARRAY_LENGTH(blackboxGpsHFields),
if (!sendFieldDefinition('H', 0, blackboxGpsHFields, blackboxGpsHFields + 1, ARRAYLEN(blackboxGpsHFields),
NULL, NULL)) {
blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADER);
}
@ -1551,7 +1552,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
case BLACKBOX_STATE_SEND_GPS_G_HEADER:
blackboxReplenishHeaderBudget();
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
if (!sendFieldDefinition('G', 0, blackboxGpsGFields, blackboxGpsGFields + 1, ARRAY_LENGTH(blackboxGpsGFields),
if (!sendFieldDefinition('G', 0, blackboxGpsGFields, blackboxGpsGFields + 1, ARRAYLEN(blackboxGpsGFields),
&blackboxGpsGFields[0].condition, &blackboxGpsGFields[1].condition)) {
blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER);
}
@ -1560,7 +1561,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
case BLACKBOX_STATE_SEND_SLOW_HEADER:
blackboxReplenishHeaderBudget();
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
if (!sendFieldDefinition('S', 0, blackboxSlowFields, blackboxSlowFields + 1, ARRAY_LENGTH(blackboxSlowFields),
if (!sendFieldDefinition('S', 0, blackboxSlowFields, blackboxSlowFields + 1, ARRAYLEN(blackboxSlowFields),
NULL, NULL)) {
blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO);
}
@ -1571,7 +1572,6 @@ void handleBlackbox(timeUs_t currentTimeUs)
//Keep writing chunks of the system info headers until it returns true to signal completion
if (blackboxWriteSysinfo()) {
/*
* Wait for header buffers to drain completely before data logging begins to ensure reliable header delivery
* (overflowing circular buffers causes all data to be discarded, so the first few logged iterations
@ -1611,7 +1611,6 @@ void handleBlackbox(timeUs_t currentTimeUs)
break;
case BLACKBOX_STATE_SHUTTING_DOWN:
//On entry of this state, startTime is set
/*
* Wait for the log we've transmitted to make its way to the logger before we release the serial port,
* since releasing the port clears the Tx buffer.
@ -1676,7 +1675,7 @@ void handleBlackbox(timeUs_t currentTimeUs)
/**
* Call during system startup to initialize the blackbox.
*/
void initBlackbox(void)
void blackboxInit(void)
{
if (blackboxConfig()->device) {
blackboxSetState(BLACKBOX_STATE_STOPPED);

View file

@ -18,9 +18,7 @@
#pragma once
#include "blackbox/blackbox_fielddefs.h"
#include "common/time.h"
#include "config/parameter_group.h"
typedef enum BlackboxDevice {
@ -39,16 +37,15 @@ typedef struct blackboxConfig_s {
uint8_t rate_denom;
uint8_t device;
uint8_t on_motor_test;
uint8_t record_acc;
} blackboxConfig_t;
PG_DECLARE(blackboxConfig_t, blackboxConfig);
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data);
void initBlackbox(void);
void handleBlackbox(timeUs_t currentTimeUs);
void validateBlackboxConfig();
void startBlackbox(void);
void finishBlackbox(void);
void blackboxInit(void);
void blackboxUpdate(timeUs_t currentTimeUs);
void blackboxValidateConfig(void);
void blackboxFinish(void);
bool blackboxMayEditConfig(void);

View file

@ -0,0 +1,490 @@
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include <stdarg.h>
#include <string.h>
#include "platform.h"
#ifdef BLACKBOX
#include "blackbox_encoding.h"
#include "blackbox_io.h"
#include "common/encoding.h"
#include "common/printf.h"
static void _putc(void *p, char c)
{
(void)p;
blackboxWrite(c);
}
static int blackboxPrintfv(const char *fmt, va_list va)
{
return tfp_format(NULL, _putc, fmt, va);
}
//printf() to the blackbox serial port with no blocking shenanigans (so it's caller's responsibility to not write too fast!)
int blackboxPrintf(const char *fmt, ...)
{
va_list va;
va_start(va, fmt);
const int written = blackboxPrintfv(fmt, va);
va_end(va);
return written;
}
/*
* printf a Blackbox header line with a leading "H " and trailing "\n" added automatically. blackboxHeaderBudget is
* decreased to account for the number of bytes written.
*/
void blackboxPrintfHeaderLine(const char *name, const char *fmt, ...)
{
va_list va;
blackboxWrite('H');
blackboxWrite(' ');
blackboxPrint(name);
blackboxWrite(':');
va_start(va, fmt);
const int written = blackboxPrintfv(fmt, va);
va_end(va);
blackboxWrite('\n');
blackboxHeaderBudget -= written + 3;
}
/**
* Write an unsigned integer to the blackbox serial port using variable byte encoding.
*/
void blackboxWriteUnsignedVB(uint32_t value)
{
//While this isn't the final byte (we can only write 7 bits at a time)
while (value > 127) {
blackboxWrite((uint8_t) (value | 0x80)); // Set the high bit to mean "more bytes follow"
value >>= 7;
}
blackboxWrite(value);
}
/**
* Write a signed integer to the blackbox serial port using ZigZig and variable byte encoding.
*/
void blackboxWriteSignedVB(int32_t value)
{
//ZigZag encode to make the value always positive
blackboxWriteUnsignedVB(zigzagEncode(value));
}
void blackboxWriteSignedVBArray(int32_t *array, int count)
{
for (int i = 0; i < count; i++) {
blackboxWriteSignedVB(array[i]);
}
}
void blackboxWriteSigned16VBArray(int16_t *array, int count)
{
for (int i = 0; i < count; i++) {
blackboxWriteSignedVB(array[i]);
}
}
void blackboxWriteS16(int16_t value)
{
blackboxWrite(value & 0xFF);
blackboxWrite((value >> 8) & 0xFF);
}
/**
* Write a 2 bit tag followed by 3 signed fields of 2, 4, 6 or 32 bits
*/
void blackboxWriteTag2_3S32(int32_t *values)
{
static const int NUM_FIELDS = 3;
//Need to be enums rather than const ints if we want to switch on them (due to being C)
enum {
BITS_2 = 0,
BITS_4 = 1,
BITS_6 = 2,
BITS_32 = 3
};
enum {
BYTES_1 = 0,
BYTES_2 = 1,
BYTES_3 = 2,
BYTES_4 = 3
};
int selector = BITS_2, selector2;
/*
* Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes
* below:
*
* Selector possibilities
*
* 2 bits per field ss11 2233,
* 4 bits per field ss00 1111 2222 3333
* 6 bits per field ss11 1111 0022 2222 0033 3333
* 32 bits per field sstt tttt followed by fields of various byte counts
*/
for (int x = 0; x < NUM_FIELDS; x++) {
//Require more than 6 bits?
if (values[x] >= 32 || values[x] < -32) {
selector = BITS_32;
break;
}
//Require more than 4 bits?
if (values[x] >= 8 || values[x] < -8) {
if (selector < BITS_6) {
selector = BITS_6;
}
} else if (values[x] >= 2 || values[x] < -2) { //Require more than 2 bits?
if (selector < BITS_4) {
selector = BITS_4;
}
}
}
switch (selector) {
case BITS_2:
blackboxWrite((selector << 6) | ((values[0] & 0x03) << 4) | ((values[1] & 0x03) << 2) | (values[2] & 0x03));
break;
case BITS_4:
blackboxWrite((selector << 6) | (values[0] & 0x0F));
blackboxWrite((values[1] << 4) | (values[2] & 0x0F));
break;
case BITS_6:
blackboxWrite((selector << 6) | (values[0] & 0x3F));
blackboxWrite((uint8_t)values[1]);
blackboxWrite((uint8_t)values[2]);
break;
case BITS_32:
/*
* Do another round to compute a selector for each field, assuming that they are at least 8 bits each
*
* Selector2 field possibilities
* 0 - 8 bits
* 1 - 16 bits
* 2 - 24 bits
* 3 - 32 bits
*/
selector2 = 0;
//Encode in reverse order so the first field is in the low bits:
for (int x = NUM_FIELDS - 1; x >= 0; x--) {
selector2 <<= 2;
if (values[x] < 128 && values[x] >= -128) {
selector2 |= BYTES_1;
} else if (values[x] < 32768 && values[x] >= -32768) {
selector2 |= BYTES_2;
} else if (values[x] < 8388608 && values[x] >= -8388608) {
selector2 |= BYTES_3;
} else {
selector2 |= BYTES_4;
}
}
//Write the selectors
blackboxWrite((selector << 6) | selector2);
//And now the values according to the selectors we picked for them
for (int x = 0; x < NUM_FIELDS; x++, selector2 >>= 2) {
switch (selector2 & 0x03) {
case BYTES_1:
blackboxWrite(values[x]);
break;
case BYTES_2:
blackboxWrite(values[x]);
blackboxWrite(values[x] >> 8);
break;
case BYTES_3:
blackboxWrite(values[x]);
blackboxWrite(values[x] >> 8);
blackboxWrite(values[x] >> 16);
break;
case BYTES_4:
blackboxWrite(values[x]);
blackboxWrite(values[x] >> 8);
blackboxWrite(values[x] >> 16);
blackboxWrite(values[x] >> 24);
break;
}
}
break;
}
}
/**
* Write a 2 bit tag followed by 3 signed fields of 2, 554, 877 or 32 bits
*/
int blackboxWriteTag2_3SVariable(int32_t *values)
{
static const int FIELD_COUNT = 3;
enum {
BITS_2 = 0,
BITS_554 = 1,
BITS_877 = 2,
BITS_32 = 3
};
enum {
BYTES_1 = 0,
BYTES_2 = 1,
BYTES_3 = 2,
BYTES_4 = 3
};
/*
* Find out how many bits the largest value requires to encode, and use it to choose one of the packing schemes
* below:
*
* Selector possibilities
*
* 2 bits per field ss11 2233,
* 554 bits per field ss11 1112 2222 3333
* 877 bits per field ss11 1111 1122 2222 2333 3333
* 32 bits per field sstt tttt followed by fields of various byte counts
*/
int selector = BITS_2;
int selector2 = 0;
// Require more than 877 bits?
if (values[0] >= 256 || values[0] < -256
|| values[1] >= 128 || values[1] < -128
|| values[2] >= 128 || values[2] < -128) {
selector = BITS_32;
// Require more than 554 bits?
} else if (values[0] >= 16 || values[0] < -16
|| values[1] >= 16 || values[1] < -16
|| values[2] >= 8 || values[2] < -8) {
selector = BITS_877;
// Require more than 2 bits?
} else if (values[0] >= 2 || values[0] < -2
|| values[1] >= 2 || values[1] < -2
|| values[2] >= 2 || values[2] < -2) {
selector = BITS_554;
}
switch (selector) {
case BITS_2:
blackboxWrite((selector << 6) | ((values[0] & 0x03) << 4) | ((values[1] & 0x03) << 2) | (values[2] & 0x03));
break;
case BITS_554:
// 554 bits per field ss11 1112 2222 3333
blackboxWrite((selector << 6) | ((values[0] & 0x1F) << 1) | ((values[1] & 0x1F) >> 4));
blackboxWrite(((values[1] & 0x0F) << 4) | (values[2] & 0x0F));
break;
case BITS_877:
// 877 bits per field ss11 1111 1122 2222 2333 3333
blackboxWrite((selector << 6) | ((values[0] & 0xFF) >> 2));
blackboxWrite(((values[0] & 0x03) << 6) | ((values[1] & 0x7F) >> 1));
blackboxWrite(((values[1] & 0x01) << 7) | (values[2] & 0x7F));
break;
case BITS_32:
/*
* Do another round to compute a selector for each field, assuming that they are at least 8 bits each
*
* Selector2 field possibilities
* 0 - 8 bits
* 1 - 16 bits
* 2 - 24 bits
* 3 - 32 bits
*/
selector2 = 0;
//Encode in reverse order so the first field is in the low bits:
for (int x = FIELD_COUNT - 1; x >= 0; x--) {
selector2 <<= 2;
if (values[x] < 128 && values[x] >= -128) {
selector2 |= BYTES_1;
} else if (values[x] < 32768 && values[x] >= -32768) {
selector2 |= BYTES_2;
} else if (values[x] < 8388608 && values[x] >= -8388608) {
selector2 |= BYTES_3;
} else {
selector2 |= BYTES_4;
}
}
//Write the selectors
blackboxWrite((selector << 6) | selector2);
//And now the values according to the selectors we picked for them
for (int x = 0; x < FIELD_COUNT; x++, selector2 >>= 2) {
switch (selector2 & 0x03) {
case BYTES_1:
blackboxWrite(values[x]);
break;
case BYTES_2:
blackboxWrite(values[x]);
blackboxWrite(values[x] >> 8);
break;
case BYTES_3:
blackboxWrite(values[x]);
blackboxWrite(values[x] >> 8);
blackboxWrite(values[x] >> 16);
break;
case BYTES_4:
blackboxWrite(values[x]);
blackboxWrite(values[x] >> 8);
blackboxWrite(values[x] >> 16);
blackboxWrite(values[x] >> 24);
break;
}
}
break;
}
return selector;
}
/**
* Write an 8-bit selector followed by four signed fields of size 0, 4, 8 or 16 bits.
*/
void blackboxWriteTag8_4S16(int32_t *values)
{
//Need to be enums rather than const ints if we want to switch on them (due to being C)
enum {
FIELD_ZERO = 0,
FIELD_4BIT = 1,
FIELD_8BIT = 2,
FIELD_16BIT = 3
};
uint8_t selector = 0;
//Encode in reverse order so the first field is in the low bits:
for (int x = 3; x >= 0; x--) {
selector <<= 2;
if (values[x] == 0) {
selector |= FIELD_ZERO;
} else if (values[x] < 8 && values[x] >= -8) {
selector |= FIELD_4BIT;
} else if (values[x] < 128 && values[x] >= -128) {
selector |= FIELD_8BIT;
} else {
selector |= FIELD_16BIT;
}
}
blackboxWrite(selector);
int nibbleIndex = 0;
uint8_t buffer = 0;
for (int x = 0; x < 4; x++, selector >>= 2) {
switch (selector & 0x03) {
case FIELD_ZERO:
//No-op
break;
case FIELD_4BIT:
if (nibbleIndex == 0) {
//We fill high-bits first
buffer = values[x] << 4;
nibbleIndex = 1;
} else {
blackboxWrite(buffer | (values[x] & 0x0F));
nibbleIndex = 0;
}
break;
case FIELD_8BIT:
if (nibbleIndex == 0) {
blackboxWrite(values[x]);
} else {
//Write the high bits of the value first (mask to avoid sign extension)
blackboxWrite(buffer | ((values[x] >> 4) & 0x0F));
//Now put the leftover low bits into the top of the next buffer entry
buffer = values[x] << 4;
}
break;
case FIELD_16BIT:
if (nibbleIndex == 0) {
//Write high byte first
blackboxWrite(values[x] >> 8);
blackboxWrite(values[x]);
} else {
//First write the highest 4 bits
blackboxWrite(buffer | ((values[x] >> 12) & 0x0F));
// Then the middle 8
blackboxWrite(values[x] >> 4);
//Only the smallest 4 bits are still left to write
buffer = values[x] << 4;
}
break;
}
}
//Anything left over to write?
if (nibbleIndex == 1) {
blackboxWrite(buffer);
}
}
/**
* Write `valueCount` fields from `values` to the Blackbox using signed variable byte encoding. A 1-byte header is
* written first which specifies which fields are non-zero (so this encoding is compact when most fields are zero).
*
* valueCount must be 8 or less.
*/
void blackboxWriteTag8_8SVB(int32_t *values, int valueCount)
{
uint8_t header;
if (valueCount > 0) {
//If we're only writing one field then we can skip the header
if (valueCount == 1) {
blackboxWriteSignedVB(values[0]);
} else {
//First write a one-byte header that marks which fields are non-zero
header = 0;
// First field should be in low bits of header
for (int i = valueCount - 1; i >= 0; i--) {
header <<= 1;
if (values[i] != 0) {
header |= 0x01;
}
}
blackboxWrite(header);
for (int i = 0; i < valueCount; i++) {
if (values[i] != 0) {
blackboxWriteSignedVB(values[i]);
}
}
}
}
}
/** Write unsigned integer **/
void blackboxWriteU32(int32_t value)
{
blackboxWrite(value & 0xFF);
blackboxWrite((value >> 8) & 0xFF);
blackboxWrite((value >> 16) & 0xFF);
blackboxWrite((value >> 24) & 0xFF);
}
/** Write float value in the integer form **/
void blackboxWriteFloat(float value)
{
blackboxWriteU32(castFloatBytesToInt(value));
}
#endif // BLACKBOX

View file

@ -0,0 +1,34 @@
/*
* 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
int blackboxPrintf(const char *fmt, ...);
void blackboxPrintfHeaderLine(const char *name, const char *fmt, ...);
int blackboxPrint(const char *s);
void blackboxWriteUnsignedVB(uint32_t value);
void blackboxWriteSignedVB(int32_t value);
void blackboxWriteSignedVBArray(int32_t *array, int count);
void blackboxWriteSigned16VBArray(int16_t *array, int count);
void blackboxWriteS16(int16_t value);
void blackboxWriteTag2_3S32(int32_t *values);
int blackboxWriteTag2_3SVariable(int32_t *values);
void blackboxWriteTag8_4S16(int32_t *values);
void blackboxWriteTag8_8SVB(int32_t *values, int valueCount);
void blackboxWriteU32(int32_t value);
void blackboxWriteFloat(float value);

View file

@ -42,6 +42,9 @@ typedef enum FlightLogFieldCondition {
FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME,
FLIGHT_LOG_FIELD_CONDITION_ACC,
FLIGHT_LOG_FIELD_CONDITION_DEBUG,
FLIGHT_LOG_FIELD_CONDITION_NEVER,
FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS,
@ -94,7 +97,8 @@ typedef enum FlightLogFieldEncoding {
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
FLIGHT_LOG_FIELD_ENCODING_NULL = 9, // Nothing is written to the file, take value to be zero
FLIGHT_LOG_FIELD_ENCODING_TAG2_3SVARIABLE = 10
} FlightLogFieldEncoding;
typedef enum FlightLogFieldSign {

File diff suppressed because it is too large Load diff

View file

@ -40,21 +40,6 @@ extern int32_t blackboxHeaderBudget;
void blackboxOpen(void);
void blackboxWrite(uint8_t value);
int blackboxPrintf(const char *fmt, ...);
void blackboxPrintfHeaderLine(const char *name, const char *fmt, ...);
int blackboxPrint(const char *s);
void blackboxWriteUnsignedVB(uint32_t value);
void blackboxWriteSignedVB(int32_t value);
void blackboxWriteSignedVBArray(int32_t *array, int count);
void blackboxWriteSigned16VBArray(int16_t *array, int count);
void blackboxWriteS16(int16_t value);
void blackboxWriteTag2_3S32(int32_t *values);
void blackboxWriteTag8_4S16(int32_t *values);
void blackboxWriteTag8_8SVB(int32_t *values, int valueCount);
void blackboxWriteU32(int32_t value);
void blackboxWriteFloat(float value);
void blackboxDeviceFlush(void);
bool blackboxDeviceFlushForce(void);
bool blackboxDeviceOpen(void);

View file

@ -21,6 +21,7 @@
CMS-displayPort separation by jflyper and martinbudden
*/
//#define CMS_PAGE_DEBUG // For multi-page/menu debugging
//#define CMS_MENU_DEBUG // For external menu content creators
#include <stdbool.h>
@ -129,19 +130,20 @@ static displayPort_t *cmsDisplayPortSelectNext(void)
static bool cmsInMenu = false;
STATIC_UNIT_TESTED const CMS_Menu *currentMenu; // Points to top entry of the current page
typedef struct cmsCtx_s {
const CMS_Menu *menu; // menu for this context
uint8_t page; // page in the menu
int8_t cursorRow; // cursorRow in the page
} cmsCtx_t;
// XXX Does menu backing support backing into second page???
static const CMS_Menu *menuStack[10]; // Stack to save menu transition
static uint8_t menuStackHistory[10];// cursorRow in a stacked menu
static cmsCtx_t menuStack[10];
static uint8_t menuStackIdx = 0;
static OSD_Entry *pageTop; // Points to top entry of the current page
static OSD_Entry *pageTopAlt; // Only 2 pages are allowed (for now)
static uint8_t maxRow; // Max row in the current page
static int8_t pageCount; // Number of pages in the current menu
static OSD_Entry *pageTop; // First entry for the current page
static uint8_t pageMaxRow; // Max row in the current page
static int8_t cursorRow;
static cmsCtx_t currentCtx;
#ifdef CMS_MENU_DEBUG // For external menu content creators
@ -164,19 +166,52 @@ static CMS_Menu menuErr = {
};
#endif
#ifdef CMS_PAGE_DEBUG
#define cmsPageDebug() { \
debug[0] = pageCount; \
debug[1] = currentCtx.page; \
debug[2] = pageMaxRow; \
debug[3] = currentCtx.cursorRow; } struct _dummy
#else
#define cmsPageDebug()
#endif
static void cmsUpdateMaxRow(displayPort_t *instance)
{
maxRow = 0;
pageMaxRow = 0;
for (const OSD_Entry *ptr = pageTop; ptr->type != OME_END; ptr++) {
maxRow++;
pageMaxRow++;
}
if (maxRow > MAX_MENU_ITEMS(instance)) {
maxRow = MAX_MENU_ITEMS(instance);
if (pageMaxRow > MAX_MENU_ITEMS(instance)) {
pageMaxRow = MAX_MENU_ITEMS(instance);
}
maxRow--;
pageMaxRow--;
}
static uint8_t cmsCursorAbsolute(displayPort_t *instance)
{
return currentCtx.cursorRow + currentCtx.page * MAX_MENU_ITEMS(instance);
}
static void cmsPageSelect(displayPort_t *instance, int8_t newpage)
{
currentCtx.page = (newpage + pageCount) % pageCount;
pageTop = &currentCtx.menu->entries[currentCtx.page * MAX_MENU_ITEMS(instance)];
cmsUpdateMaxRow(instance);
displayClearScreen(instance);
}
static void cmsPageNext(displayPort_t *instance)
{
cmsPageSelect(instance, currentCtx.page + 1);
}
static void cmsPagePrev(displayPort_t *instance)
{
cmsPageSelect(instance, currentCtx.page - 1);
}
static void cmsFormatFloat(int32_t value, char *floatString)
@ -377,7 +412,7 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
uint8_t i;
OSD_Entry *p;
uint8_t top = (pDisplay->rows - maxRow) / 2 - 1;
uint8_t top = (pDisplay->rows - pageMaxRow) / 2 - 1;
// Polled (dynamic) value display denominator.
@ -396,17 +431,9 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
SET_PRINTLABEL(p);
SET_PRINTVALUE(p);
}
if (i > MAX_MENU_ITEMS(pDisplay)) // max per page
{
pageTopAlt = pageTop + MAX_MENU_ITEMS(pDisplay);
if (pageTopAlt->type == OME_END)
pageTopAlt = NULL;
}
pDisplay->cleared = false;
} else if (drawPolled) {
for (p = pageTop ; p <= pageTop + maxRow ; p++) {
for (p = pageTop ; p <= pageTop + pageMaxRow ; p++) {
if (IS_DYNAMIC(p))
SET_PRINTVALUE(p);
}
@ -414,19 +441,21 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
// Cursor manipulation
while ((pageTop + cursorRow)->type == OME_Label) // skip label
cursorRow++;
while ((pageTop + currentCtx.cursorRow)->type == OME_Label) // skip label
currentCtx.cursorRow++;
if (pDisplay->cursorRow >= 0 && cursorRow != pDisplay->cursorRow) {
cmsPageDebug();
if (pDisplay->cursorRow >= 0 && currentCtx.cursorRow != pDisplay->cursorRow) {
room -= displayWrite(pDisplay, LEFT_MENU_COLUMN, pDisplay->cursorRow + top, " ");
}
if (room < 30)
return;
if (pDisplay->cursorRow != cursorRow) {
room -= displayWrite(pDisplay, LEFT_MENU_COLUMN, cursorRow + top, " >");
pDisplay->cursorRow = cursorRow;
if (pDisplay->cursorRow != currentCtx.cursorRow) {
room -= displayWrite(pDisplay, LEFT_MENU_COLUMN, currentCtx.cursorRow + top, " >");
pDisplay->cursorRow = currentCtx.cursorRow;
}
if (room < 30)
@ -458,46 +487,61 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
}
}
static void cmsMenuCountPage(displayPort_t *pDisplay)
{
OSD_Entry *p;
for (p = currentCtx.menu->entries; p->type != OME_END; p++);
pageCount = (p - currentCtx.menu->entries - 1) / MAX_MENU_ITEMS(pDisplay) + 1;
}
STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay); // Forward; will be resolved after merging
long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
{
CMS_Menu *pMenu = (CMS_Menu *)ptr;
if (pMenu) {
if (!pMenu) {
return 0;
}
#ifdef CMS_MENU_DEBUG
if (pMenu->GUARD_type != OME_MENU) {
// ptr isn't pointing to a CMS_Menu.
if (pMenu->GUARD_type <= OME_MAX) {
strncpy(menuErrLabel, pMenu->GUARD_text, sizeof(menuErrLabel) - 1);
} else {
strncpy(menuErrLabel, "LABEL UNKNOWN", sizeof(menuErrLabel) - 1);
}
pMenu = &menuErr;
if (pMenu->GUARD_type != OME_MENU) {
// ptr isn't pointing to a CMS_Menu.
if (pMenu->GUARD_type <= OME_MAX) {
strncpy(menuErrLabel, pMenu->GUARD_text, sizeof(menuErrLabel) - 1);
} else {
strncpy(menuErrLabel, "LABEL UNKNOWN", sizeof(menuErrLabel) - 1);
}
pMenu = &menuErr;
}
#endif
if (pMenu != currentCtx.menu) {
// Stack the current menu and move to a new menu.
// The (pMenu == curretMenu) case occurs when reopening for display sw
if (pMenu != currentMenu) {
menuStack[menuStackIdx] = currentMenu;
cursorRow += pageTop - currentMenu->entries; // Convert cursorRow to absolute value
menuStackHistory[menuStackIdx] = cursorRow;
menuStackIdx++;
menuStack[menuStackIdx++] = currentCtx;
currentMenu = pMenu;
cursorRow = 0;
currentCtx.menu = pMenu;
currentCtx.cursorRow = 0;
if (pMenu->onEnter)
pMenu->onEnter();
if (pMenu->onEnter && (pMenu->onEnter() == MENU_CHAIN_BACK)) {
return cmsMenuBack(pDisplay);
}
pageTop = currentMenu->entries;
pageTopAlt = NULL;
cmsMenuCountPage(pDisplay);
cmsPageSelect(pDisplay, 0);
} else {
// The (pMenu == curretMenu) case occurs when reopening for display cycling
// currentCtx.cursorRow has been saved as absolute; convert it back to page + relative
displayClearScreen(pDisplay);
cmsUpdateMaxRow(pDisplay);
int8_t cursorAbs = currentCtx.cursorRow;
currentCtx.cursorRow = cursorAbs % MAX_MENU_ITEMS(pDisplay);
cmsMenuCountPage(pDisplay);
cmsPageSelect(pDisplay, cursorAbs / MAX_MENU_ITEMS(pDisplay));
}
cmsPageDebug();
return 0;
}
@ -505,30 +549,21 @@ STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay)
{
// Let onExit function decide whether to allow exit or not.
if (currentMenu->onExit && currentMenu->onExit(pageTop + cursorRow) < 0)
if (currentCtx.menu->onExit && currentCtx.menu->onExit(pageTop + currentCtx.cursorRow) < 0) {
return -1;
if (menuStackIdx) {
displayClearScreen(pDisplay);
menuStackIdx--;
currentMenu = menuStack[menuStackIdx];
cursorRow = menuStackHistory[menuStackIdx];
// cursorRow is absolute offset of a focused entry when stacked.
// Convert it back to page and relative offset.
pageTop = currentMenu->entries; // Temporary for cmsUpdateMaxRow()
cmsUpdateMaxRow(pDisplay);
if (cursorRow > maxRow) {
// Cursor was in the second page.
pageTopAlt = currentMenu->entries;
pageTop = pageTopAlt + maxRow + 1;
cursorRow -= (maxRow + 1);
cmsUpdateMaxRow(pDisplay); // Update maxRow for the second page
}
}
if (!menuStackIdx) {
return 0;
}
currentCtx = menuStack[--menuStackIdx];
cmsMenuCountPage(pDisplay);
cmsPageSelect(pDisplay, currentCtx.page);
cmsPageDebug();
return 0;
}
@ -540,12 +575,15 @@ STATIC_UNIT_TESTED void cmsMenuOpen(void)
if (!pCurrentDisplay)
return;
cmsInMenu = true;
currentMenu = &menuMain;
currentCtx = (cmsCtx_t){ &menuMain, 0, 0 };
DISABLE_ARMING_FLAG(OK_TO_ARM);
} else {
// Switch display
displayPort_t *pNextDisplay = cmsDisplayPortSelectNext();
if (pNextDisplay != pCurrentDisplay) {
// DisplayPort has been changed.
// Convert cursorRow to absolute value
currentCtx.cursorRow = cmsCursorAbsolute(pCurrentDisplay);
displayRelease(pCurrentDisplay);
pCurrentDisplay = pNextDisplay;
} else {
@ -553,7 +591,7 @@ STATIC_UNIT_TESTED void cmsMenuOpen(void)
}
}
displayGrab(pCurrentDisplay); // grab the display for use by the CMS
cmsMenuChange(pCurrentDisplay, currentMenu);
cmsMenuChange(pCurrentDisplay, currentCtx.menu);
}
static void cmsTraverseGlobalExit(const CMS_Menu *pMenu)
@ -570,39 +608,47 @@ static void cmsTraverseGlobalExit(const CMS_Menu *pMenu)
}
long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
{
if (ptr) {
displayClearScreen(pDisplay);
{
int exitType = (int)ptr;
switch (exitType) {
case CMS_EXIT_SAVE:
case CMS_EXIT_SAVEREBOOT:
cmsTraverseGlobalExit(&menuMain);
if (currentCtx.menu->onExit)
currentCtx.menu->onExit((OSD_Entry *)NULL); // Forced exit
saveConfigAndNotify();
break;
case CMS_EXIT:
break;
}
cmsInMenu = false;
displayRelease(pDisplay);
currentCtx.menu = NULL;
if (exitType == CMS_EXIT_SAVEREBOOT) {
displayClearScreen(pDisplay);
displayWrite(pDisplay, 5, 3, "REBOOTING...");
displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing?
stopMotors();
stopPwmAllMotors();
delay(200);
cmsTraverseGlobalExit(&menuMain);
if (currentMenu->onExit)
currentMenu->onExit((OSD_Entry *)NULL); // Forced exit
saveConfigAndNotify();
}
cmsInMenu = false;
displayRelease(pDisplay);
currentMenu = NULL;
if (ptr)
systemReset();
}
ENABLE_ARMING_FLAG(OK_TO_ARM);
return 0;
}
// Stick/key detection and key codes
#define IS_HI(X) (rcData[X] > 1750)
@ -625,7 +671,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
uint16_t res = BUTTON_TIME;
OSD_Entry *p;
if (!currentMenu)
if (!currentCtx.menu)
return res;
if (key == KEY_MENU) {
@ -639,42 +685,32 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
}
if (key == KEY_DOWN) {
if (cursorRow < maxRow) {
cursorRow++;
if (currentCtx.cursorRow < pageMaxRow) {
currentCtx.cursorRow++;
} else {
if (pageTopAlt) { // we have another page
displayClearScreen(pDisplay);
p = pageTopAlt;
pageTopAlt = pageTop;
pageTop = (OSD_Entry *)p;
cmsUpdateMaxRow(pDisplay);
}
cursorRow = 0; // Goto top in any case
cmsPageNext(pDisplay);
currentCtx.cursorRow = 0; // Goto top in any case
}
}
if (key == KEY_UP) {
cursorRow--;
currentCtx.cursorRow--;
if ((pageTop + cursorRow)->type == OME_Label && cursorRow > 0)
cursorRow--;
// Skip non-title labels
if ((pageTop + currentCtx.cursorRow)->type == OME_Label && currentCtx.cursorRow > 0)
currentCtx.cursorRow--;
if (cursorRow == -1 || (pageTop + cursorRow)->type == OME_Label) {
if (pageTopAlt) {
displayClearScreen(pDisplay);
p = pageTopAlt;
pageTopAlt = pageTop;
pageTop = (OSD_Entry *)p;
cmsUpdateMaxRow(pDisplay);
}
cursorRow = maxRow; // Goto bottom in any case
if (currentCtx.cursorRow == -1 || (pageTop + currentCtx.cursorRow)->type == OME_Label) {
// Goto previous page
cmsPagePrev(pDisplay);
currentCtx.cursorRow = pageMaxRow;
}
}
if (key == KEY_DOWN || key == KEY_UP)
return res;
p = pageTop + cursorRow;
p = pageTop + currentCtx.cursorRow;
switch (p->type) {
case OME_Submenu:
@ -878,19 +914,19 @@ void cmsUpdate(uint32_t currentTimeUs)
if (IS_MID(THROTTLE) && IS_LO(YAW) && IS_HI(PITCH) && !ARMING_FLAG(ARMED)) {
key = KEY_MENU;
}
else if (IS_HI(PITCH)) {
else if (IS_MID(THROTTLE) && IS_MID(YAW) && IS_MID(ROLL) && IS_HI(PITCH)) {
key = KEY_UP;
}
else if (IS_LO(PITCH)) {
else if (IS_MID(THROTTLE) && IS_MID(YAW) && IS_MID(ROLL) && IS_LO(PITCH)) {
key = KEY_DOWN;
}
else if (IS_LO(ROLL)) {
else if (IS_MID(THROTTLE) && IS_MID(YAW) && IS_LO(ROLL) && IS_MID(PITCH)) {
key = KEY_LEFT;
}
else if (IS_HI(ROLL)) {
else if (IS_MID(THROTTLE) && IS_MID(YAW) && IS_HI(ROLL) && IS_MID(PITCH)) {
key = KEY_RIGHT;
}
else if (IS_HI(YAW) || IS_LO(YAW))
else if ((IS_HI(YAW) || IS_LO(YAW)) && IS_MID(THROTTLE) && IS_MID(ROLL) && IS_MID(PITCH))
{
key = KEY_ESC;
}
@ -969,8 +1005,6 @@ void cmsHandler(timeUs_t currentTimeUs)
}
}
// Is initializing with menuMain better?
// Can it be done with the current main()?
void cmsInit(void)
{
cmsDeviceCount = 0;

View file

@ -18,3 +18,9 @@ void cmsUpdate(uint32_t currentTimeUs);
#define CMS_STARTUP_HELP_TEXT1 "MENU: THR MID"
#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT"
#define CMS_STARTUP_HELP_TEXT3 "+ PITCH UP"
// cmsMenuExit special ptr values
#define CMS_EXIT (0)
#define CMS_EXIT_SAVE (1)
#define CMS_EXIT_SAVEREBOOT (2)

View file

@ -178,7 +178,7 @@ static long cmsx_Blackbox_onExit(const OSD_Entry *self)
if (blackboxMayEditConfig()) {
blackboxConfigMutable()->device = cmsx_BlackboxDevice;
validateBlackboxConfig();
blackboxValidateConfig();
}
blackboxConfigMutable()->rate_denom = blackboxConfig_rate_denom;
return 0;

View file

@ -138,8 +138,9 @@ static OSD_Entry menuMainEntries[] =
#endif
{"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0},
{"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc, 0},
{"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void*)1, 0},
{"EXIT", OME_OSD_Exit, cmsMenuExit, (void*)0, 0},
{"EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT, 0},
{"SAVE&EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT_SAVE, 0},
{"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT_SAVEREBOOT, 0},
#ifdef CMS_MENU_DEBUG
{"ERR SAMPLE", OME_Submenu, cmsMenuChange, &menuInfoEntries[0], 0},
#endif

View file

@ -103,7 +103,8 @@ OSD_Entry menuOsdActiveElemsEntries[] =
{
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_RSSI_VALUE], 0},
{"MAIN BATTERY", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"BATTERY VOLTAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"BATTERY USAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_USAGE], 0},
{"AVG CELL VOLTAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_AVG_CELL_VOLTAGE], 0},
{"CROSSHAIRS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CROSSHAIRS], 0},
{"HORIZON", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ARTIFICIAL_HORIZON], 0},

View file

@ -99,6 +99,15 @@ float acos_approx(float x)
}
#endif
int gcd(int num, int denom)
{
if (denom == 0) {
return num;
}
return gcd(denom, num % denom);
}
float powerf(float base, int exp) {
float result = base;
for (int count = 1; count < exp; count++) result *= base;

View file

@ -76,6 +76,7 @@ typedef union {
fp_angles_def angles;
} fp_angles_t;
int gcd(int num, int denom);
float powerf(float base, int exp);
int32_t applyDeadband(int32_t value, int32_t deadband);

View file

@ -27,6 +27,9 @@
#define CONCAT_HELPER(x,y) x ## y
#define CONCAT(x,y) CONCAT_HELPER(x, y)
#define CONCAT2(_1,_2) CONCAT(_1, _2)
#define CONCAT3(_1,_2,_3) CONCAT(CONCAT(_1, _2), _3)
#define CONCAT4(_1,_2,_3,_4) CONCAT(CONCAT3(_1, _2, _3), _4)
#define STR_HELPER(x) #x
#define STR(x) STR_HELPER(x)
@ -34,6 +37,18 @@
#define EXPAND_I(x) x
#define EXPAND(x) EXPAND_I(x)
// expand to t if bit is 1, f when bit is 0. Other bit values are not supported
#define PP_IIF(bit, t, f) PP_IIF_I(bit, t, f)
#define PP_IIF_I(bit, t, f) PP_IIF_ ## bit(t, f)
#define PP_IIF_0(t, f) f
#define PP_IIF_1(t, f) t
// Expand all argumens and call macro with them. When expansion of some argument contains ',', it will be passed as multiple arguments
// #define TAKE3(_1,_2,_3) CONCAT3(_1,_2,_3)
// #define MULTI2 A,B
// PP_CALL(TAKE3, MULTI2, C) expands to ABC
#define PP_CALL(macro, ...) macro(__VA_ARGS__)
#if !defined(UNUSED)
#define UNUSED(x) (void)(x)
#endif

View file

@ -145,7 +145,7 @@ void mpu6000SpiGyroInit(gyroDev_t *gyro)
void mpu6000SpiAccInit(accDev_t *acc)
{
acc->acc_1G = 512 * 4;
acc->acc_1G = 512 * 8;
}
bool mpu6000SpiDetect(const busDevice_t *bus)

View file

@ -234,7 +234,6 @@ void i2cInit(I2CDevice device)
IOConfigGPIO(sda, IOCFG_AF_OD);
#endif
// Init I2C peripheral
HAL_I2C_DeInit(&i2cHandle[device].Handle);
i2cHandle[device].Handle.Instance = i2cHardwareMap[device].dev;
/// TODO: HAL check if I2C timing is correct

View file

@ -88,7 +88,7 @@ static void m25p16_performOneByteCommand(uint8_t command)
* The flash requires this write enable command to be sent before commands that would cause
* a write like program and erase.
*/
static void m25p16_writeEnable()
static void m25p16_writeEnable(void)
{
m25p16_performOneByteCommand(M25P16_INSTRUCTION_WRITE_ENABLE);
@ -96,7 +96,7 @@ static void m25p16_writeEnable()
couldBeBusy = true;
}
static uint8_t m25p16_readStatus()
static uint8_t m25p16_readStatus(void)
{
uint8_t command[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 };
uint8_t in[2];
@ -110,7 +110,7 @@ static uint8_t m25p16_readStatus()
return in[1];
}
bool m25p16_isReady()
bool m25p16_isReady(void)
{
// If couldBeBusy is false, don't bother to poll the flash chip for its status
couldBeBusy = couldBeBusy && ((m25p16_readStatus() & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0);
@ -135,7 +135,7 @@ bool m25p16_waitForReady(uint32_t timeoutMillis)
*
* Returns true if we get valid ident, false if something bad happened like there is no M25P16.
*/
static bool m25p16_readIdentification()
static bool m25p16_readIdentification(void)
{
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 };
uint8_t in[4];
@ -161,37 +161,37 @@ static bool m25p16_readIdentification()
// All supported chips use the same pagesize of 256 bytes
switch (chipID) {
case JEDEC_ID_MICRON_M25P16:
geometry.sectors = 32;
geometry.pagesPerSector = 256;
case JEDEC_ID_MICRON_M25P16:
geometry.sectors = 32;
geometry.pagesPerSector = 256;
break;
case JEDEC_ID_MACRONIX_MX25L3206E:
geometry.sectors = 64;
geometry.pagesPerSector = 256;
case JEDEC_ID_MACRONIX_MX25L3206E:
geometry.sectors = 64;
geometry.pagesPerSector = 256;
break;
case JEDEC_ID_MICRON_N25Q064:
case JEDEC_ID_WINBOND_W25Q64:
case JEDEC_ID_MACRONIX_MX25L6406E:
geometry.sectors = 128;
geometry.pagesPerSector = 256;
case JEDEC_ID_MICRON_N25Q064:
case JEDEC_ID_WINBOND_W25Q64:
case JEDEC_ID_MACRONIX_MX25L6406E:
geometry.sectors = 128;
geometry.pagesPerSector = 256;
break;
case JEDEC_ID_MICRON_N25Q128:
case JEDEC_ID_WINBOND_W25Q128:
geometry.sectors = 256;
geometry.pagesPerSector = 256;
case JEDEC_ID_MICRON_N25Q128:
case JEDEC_ID_WINBOND_W25Q128:
geometry.sectors = 256;
geometry.pagesPerSector = 256;
break;
case JEDEC_ID_MACRONIX_MX25L25635E:
geometry.sectors = 512;
geometry.pagesPerSector = 256;
case JEDEC_ID_MACRONIX_MX25L25635E:
geometry.sectors = 512;
geometry.pagesPerSector = 256;
break;
default:
// Unsupported chip or not an SPI NOR flash
geometry.sectors = 0;
geometry.pagesPerSector = 0;
default:
// Unsupported chip or not an SPI NOR flash
geometry.sectors = 0;
geometry.pagesPerSector = 0;
geometry.sectorSize = 0;
geometry.totalSize = 0;
return false;
geometry.sectorSize = 0;
geometry.totalSize = 0;
return false;
}
geometry.sectorSize = geometry.pagesPerSector * geometry.pageSize;
@ -254,7 +254,7 @@ void m25p16_eraseSector(uint32_t address)
DISABLE_M25P16;
}
void m25p16_eraseCompletely()
void m25p16_eraseCompletely(void)
{
m25p16_waitForReady(BULK_ERASE_TIMEOUT_MILLIS);
@ -281,7 +281,7 @@ void m25p16_pageProgramContinue(const uint8_t *data, int length)
spiTransfer(M25P16_SPI_INSTANCE, NULL, data, length);
}
void m25p16_pageProgramFinish()
void m25p16_pageProgramFinish(void)
{
DISABLE_M25P16;
}
@ -341,7 +341,7 @@ int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length)
*
* Can be called before calling m25p16_init() (the result would have totalSize = 0).
*/
const flashGeometry_t* m25p16_getGeometry()
const flashGeometry_t* m25p16_getGeometry(void)
{
return &geometry;
}

View file

@ -25,18 +25,18 @@
bool m25p16_init(const flashConfig_t *flashConfig);
void m25p16_eraseSector(uint32_t address);
void m25p16_eraseCompletely();
void m25p16_eraseCompletely(void);
void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length);
void m25p16_pageProgramBegin(uint32_t address);
void m25p16_pageProgramContinue(const uint8_t *data, int length);
void m25p16_pageProgramFinish();
void m25p16_pageProgramFinish(void);
int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length);
bool m25p16_isReady();
bool m25p16_isReady(void);
bool m25p16_waitForReady(uint32_t timeoutMillis);
struct flashGeometry_s;
const struct flashGeometry_s* m25p16_getGeometry();
const struct flashGeometry_s* m25p16_getGeometry(void);

View file

@ -36,11 +36,11 @@ bool ws2811Initialised = false;
static TIM_HandleTypeDef TimHandle;
static uint16_t timerChannel = 0;
static bool timerNChannel = false;
void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim)
{
if(htim->Instance == TimHandle.Instance)
{
if(htim->Instance == TimHandle.Instance) {
//HAL_TIM_PWM_Stop_DMA(&TimHandle,WS2811_TIMER_CHANNEL);
ws2811LedDataTransferInProgress = 0;
}
@ -72,18 +72,17 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
BIT_COMPARE_1 = period / 3 * 2;
BIT_COMPARE_0 = period / 3;
TimHandle.Init.Prescaler = prescaler;
TimHandle.Init.Period = period; // 800kHz
TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
if(HAL_TIM_PWM_Init(&TimHandle) != HAL_OK)
{
if(HAL_TIM_PWM_Init(&TimHandle) != HAL_OK) {
/* Initialization Error */
return;
}
static DMA_HandleTypeDef hdma_tim;
static DMA_HandleTypeDef hdma_tim;
ws2811IO = IOGetByTag(ioTag);
IOInit(ws2811IO, OWNER_LED_STRIP, 0);
@ -92,12 +91,12 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
__DMA1_CLK_ENABLE();
/* Set the parameters to be configured */
hdma_tim.Init.Channel = timerHardware->dmaChannel;
hdma_tim.Init.Channel = timerHardware->dmaChannel;
hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH;
hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_tim.Init.MemInc = DMA_MINC_ENABLE;
hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD ;
hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD ;
hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
hdma_tim.Init.Mode = DMA_NORMAL;
hdma_tim.Init.Priority = DMA_PRIORITY_HIGH;
hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
@ -117,8 +116,7 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
dmaSetHandler(timerHardware->dmaIrqHandler, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, dmaSource);
/* Initialize TIMx DMA handle */
if(HAL_DMA_Init(TimHandle.hdma[dmaSource]) != HAL_OK)
{
if(HAL_DMA_Init(TimHandle.hdma[dmaSource]) != HAL_OK) {
/* Initialization Error */
return;
}
@ -127,14 +125,21 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
/* PWM1 Mode configuration: Channel1 */
TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1;
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
timerNChannel = true;
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET;
TIM_OCInitStructure.OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_HIGH: TIM_OCPOLARITY_LOW;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
TIM_OCInitStructure.OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_HIGH : TIM_OCNPOLARITY_LOW;
} else {
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET;
TIM_OCInitStructure.OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_LOW : TIM_OCPOLARITY_HIGH;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
TIM_OCInitStructure.OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_LOW : TIM_OCNPOLARITY_HIGH;
}
TIM_OCInitStructure.Pulse = 0;
TIM_OCInitStructure.OCPolarity = TIM_OCPOLARITY_HIGH;
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
if(HAL_TIM_PWM_ConfigChannel(&TimHandle, &TIM_OCInitStructure, timerChannel) != HAL_OK)
{
if(HAL_TIM_PWM_ConfigChannel(&TimHandle, &TIM_OCInitStructure, timerChannel) != HAL_OK) {
/* Configuration Error */
return;
}
@ -142,21 +147,25 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
ws2811Initialised = true;
}
void ws2811LedStripDMAEnable(void)
{
if (!ws2811Initialised)
{
if (!ws2811Initialised) {
ws2811LedDataTransferInProgress = 0;
return;
}
if (HAL_TIM_PWM_Start_DMA(&TimHandle, timerChannel, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK)
{
/* Starting PWM generation Error */
ws2811LedDataTransferInProgress = 0;
return;
if(timerNChannel) {
if(HAL_TIMEx_PWMN_Start_DMA(&TimHandle, timerChannel, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */
ws2811LedDataTransferInProgress = 0;
return;
}
} else {
if (HAL_TIM_PWM_Start_DMA(&TimHandle, timerChannel, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */
ws2811LedDataTransferInProgress = 0;
return;
}
}
}
#endif

View file

@ -217,3 +217,11 @@
//sport
#define SYM_MIN 0xB3
#define SYM_AVG 0xB4
// Progress bar
#define SYM_PB_START 0x8A
#define SYM_PB_FULL 0x8B
#define SYM_PB_HALF 0x8C
#define SYM_PB_EMPTY 0x8D
#define SYM_PB_END 0x8E
#define SYM_PB_CLOSE 0x8F

View file

@ -59,11 +59,15 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8
TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1;
if (output & TIMER_OUTPUT_N_CHANNEL) {
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET;
TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_HIGH: TIM_OCPOLARITY_LOW;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_HIGH : TIM_OCNPOLARITY_LOW;
} else {
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_SET;
TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_LOW : TIM_OCPOLARITY_HIGH;
TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_LOW : TIM_OCPOLARITY_HIGH;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_SET;
TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_LOW : TIM_OCNPOLARITY_HIGH;
}
TIM_OCInitStructure.Pulse = value;

View file

@ -47,7 +47,7 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
}
}
dmaMotorTimers[dmaMotorTimerCount++].timer = timer;
return dmaMotorTimerCount-1;
return dmaMotorTimerCount - 1;
}
void pwmWriteDigital(uint8_t index, uint16_t value)
@ -63,13 +63,13 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
}
uint16_t packet = (value << 1) | (motor->requestTelemetry ? 1 : 0);
motor->requestTelemetry = false; // reset telemetry request to make sure it's triggered only once in a row
motor->requestTelemetry = false; // reset telemetry request to make sure it's triggered only once in a row
// compute checksum
int csum = 0;
int csum_data = packet;
for (int i = 0; i < 3; i++) {
csum ^= csum_data; // xor data by nibbles
csum ^= csum_data; // xor data by nibbles
csum_data >>= 4;
}
csum &= 0xf;
@ -77,22 +77,17 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
packet = (packet << 4) | csum;
// generate pulses for whole packet
for (int i = 0; i < 16; i++) {
motor->dmaBuffer[i] = (packet & 0x8000) ? MOTOR_BIT_1 : MOTOR_BIT_0; // MSB first
motor->dmaBuffer[i] = (packet & 0x8000) ? MOTOR_BIT_1 : MOTOR_BIT_0; // MSB first
packet <<= 1;
}
if(motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL)
{
if(HAL_TIMEx_PWMN_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK)
{
if (motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
if (HAL_TIMEx_PWMN_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
}
else
{
if(HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK)
{
} else {
if (HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK) {
/* Starting PWM generation Error */
return;
}
@ -102,15 +97,6 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
void pwmCompleteDigitalMotorUpdate(uint8_t motorCount)
{
UNUSED(motorCount);
if (!pwmMotorsEnabled) {
return;
}
for (uint8_t i = 0; i < dmaMotorTimerCount; i++) {
//TIM_SetCounter(dmaMotorTimers[i].timer, 0);
//TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
}
}
static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
@ -119,16 +105,6 @@ static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaSource]);
}
/*static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
{
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
DMA_Cmd(descriptor->stream, DISABLE);
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE);
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
}
}*/
void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
{
motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
@ -138,39 +114,31 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
const IO_t motorIO = IOGetByTag(timerHardware->tag);
const uint8_t timerIndex = getTimerIndex(timer);
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
IOInit(motorIO, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction);
__DMA1_CLK_ENABLE();
if (configureTimer) {
RCC_ClockCmd(timerRCC(timer), ENABLE);
RCC_ClockCmd(timerRCC(timer), ENABLE);
motor->TimHandle.Instance = timerHardware->tim;
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / getDshotHz(pwmProtocolType)) - 1;;
motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
motor->TimHandle.Init.RepetitionCounter = 0;
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
if(HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK)
{
/* Initialization Error */
return;
}
}
else
{
motor->TimHandle = dmaMotors[timerIndex].TimHandle;
motor->TimHandle.Instance = timerHardware->tim;
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / getDshotHz(pwmProtocolType)) - 1;
motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
motor->TimHandle.Init.RepetitionCounter = 0;
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
motor->TimHandle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK) {
/* Initialization Error */
return;
}
motor->timerDmaSource = timerDmaSource(timerHardware->channel);
dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource;
/* Set the parameters to be configured */
motor->hdma_tim.Init.Channel = timerHardware->dmaChannel;
motor->hdma_tim.Init.Channel = timerHardware->dmaChannel;
motor->hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH;
motor->hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE;
motor->hdma_tim.Init.MemInc = DMA_MINC_ENABLE;
@ -184,8 +152,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;
/* Set hdma_tim instance */
if(timerHardware->dmaRef == NULL)
{
if (timerHardware->dmaRef == NULL) {
/* Initialization Error */
return;
}
@ -198,8 +165,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
/* Initialize TIMx DMA handle */
if(HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK)
{
if (HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK) {
/* Initialization Error */
return;
}
@ -209,17 +175,20 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
/* PWM1 Mode configuration: Channel1 */
TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1;
if (output & TIMER_OUTPUT_N_CHANNEL) {
TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_LOW : TIM_OCPOLARITY_HIGH;
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET;
TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_HIGH : TIM_OCPOLARITY_LOW;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_HIGH : TIM_OCNPOLARITY_LOW;
} else {
TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_LOW : TIM_OCPOLARITY_HIGH;
TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_SET;
TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_LOW : TIM_OCPOLARITY_HIGH;
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_SET;
TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_LOW : TIM_OCNPOLARITY_HIGH;
}
TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
TIM_OCInitStructure.Pulse = 0;
if(HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK)
{
if (HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK) {
/* Configuration Error */
return;
}

View file

@ -253,7 +253,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
softSerial->timerHardware = timerTx;
softSerial->txIO = txIO;
softSerial->rxIO = txIO;
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex) + RESOURCE_SOFT_OFFSET);
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
} else {
if (mode & MODE_RX) {
// Need a pin & a timer on RX
@ -262,7 +262,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
softSerial->rxIO = rxIO;
softSerial->timerHardware = timerRx;
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(portIndex) + RESOURCE_SOFT_OFFSET);
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
}
if (mode & MODE_TX) {
@ -281,7 +281,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
// Duplex
softSerial->exTimerHardware = timerTx;
}
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex) + RESOURCE_SOFT_OFFSET);
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
}
}

File diff suppressed because it is too large Load diff

View file

@ -267,6 +267,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
if(tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 || tim == TIM9)
{
TIM_ClockConfigTypeDef sClockSourceConfig;
memset(&sClockSourceConfig, 0, sizeof(sClockSourceConfig));
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
if (HAL_TIM_ConfigClockSource(&timerHandle[timerIndex].Handle, &sClockSourceConfig) != HAL_OK)
{
@ -276,7 +277,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
if(tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 )
{
TIM_MasterConfigTypeDef sMasterConfig;
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
memset(&sMasterConfig, 0, sizeof(sMasterConfig));
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&timerHandle[timerIndex].Handle, &sMasterConfig) != HAL_OK)
{
@ -908,4 +909,4 @@ uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz)
{
return ((uint16_t)((SystemCoreClock / timerClockDivisor(tim) / (prescaler + 1)) / hertz));
}
}

View file

@ -189,7 +189,7 @@ static void cliPrint(const char *str)
bufWriterFlush(cliWriter);
}
static void cliPrintBlankLine()
static void cliPrintLinefeed()
{
cliPrint("\r\n");
}
@ -197,7 +197,7 @@ static void cliPrintBlankLine()
static void cliPrintLine(const char *str)
{
cliPrint(str);
cliPrintBlankLine();
cliPrintLinefeed();
}
#ifdef MINIMAL_CLI
@ -235,7 +235,7 @@ static void cliPrintLinefva(const char *format, va_list va)
{
tfp_format(cliWriter, cliPutp, format, va);
bufWriterFlush(cliWriter);
cliPrintBlankLine();
cliPrintLinefeed();
}
static bool cliDumpPrintLinef(uint8_t dumpMask, bool equalsDefault, const char *format, ...)
@ -378,11 +378,11 @@ static void dumpPgValue(const clivalue_t *value, uint8_t dumpMask)
if (dumpMask & SHOW_DEFAULTS && !equalsDefault) {
cliPrintf(defaultFormat, value->name);
printValuePointer(value, (uint8_t*)pg->address + valueOffset, 0);
cliPrintBlankLine();
cliPrintLinefeed();
}
cliPrintf(format, value->name);
printValuePointer(value, (uint8_t*)pg->copy + valueOffset, 0);
cliPrintBlankLine();
cliPrintLinefeed();
}
}
@ -419,7 +419,7 @@ static void cliPrintVarRange(const clivalue_t *var)
cliPrint(",");
cliPrintf(" %s", tableEntry->values[i]);
}
cliPrintBlankLine();
cliPrintLinefeed();
}
break;
}
@ -451,7 +451,7 @@ static void cliRepeat(char ch, uint8_t len)
for (int i = 0; i < len; i++) {
bufWriterAppend(cliWriter, ch);
}
cliPrintBlankLine();
cliPrintLinefeed();
}
#endif
@ -780,30 +780,30 @@ static void cliSerial(char *cmdline)
}
switch(i) {
case 0:
if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_1000000) {
continue;
}
portConfig.msp_baudrateIndex = baudRateIndex;
break;
case 1:
if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
continue;
}
portConfig.gps_baudrateIndex = baudRateIndex;
break;
case 2:
if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
continue;
}
portConfig.telemetry_baudrateIndex = baudRateIndex;
break;
case 3:
if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
continue;
}
portConfig.blackbox_baudrateIndex = baudRateIndex;
break;
case 0:
if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_1000000) {
continue;
}
portConfig.msp_baudrateIndex = baudRateIndex;
break;
case 1:
if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
continue;
}
portConfig.gps_baudrateIndex = baudRateIndex;
break;
case 2:
if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
continue;
}
portConfig.telemetry_baudrateIndex = baudRateIndex;
break;
case 3:
if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_2470000) {
continue;
}
portConfig.blackbox_baudrateIndex = baudRateIndex;
break;
}
validArgumentCount++;
@ -994,7 +994,7 @@ static void cliAdjustmentRange(char *cmdline)
static void printMotorMix(uint8_t dumpMask, const motorMixer_t *customMotorMixer, const motorMixer_t *defaultCustomMotorMixer)
{
const char *format = "mmix %d %s %s %s %s";
char buf0[8];
char buf0[FTOA_BUFFER_LENGTH];
char buf1[FTOA_BUFFER_LENGTH];
char buf2[FTOA_BUFFER_LENGTH];
char buf3[FTOA_BUFFER_LENGTH];
@ -1485,7 +1485,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer
);
}
cliPrintBlankLine();
cliPrintLinefeed();
}
static void cliServoMix(char *cmdline)
@ -1527,13 +1527,13 @@ static void cliServoMix(char *cmdline)
cliPrintf("s");
for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
cliPrintf("\ti%d", inputSource);
cliPrintBlankLine();
cliPrintLinefeed();
for (uint32_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
cliPrintf("%d", servoIndex);
for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
cliPrintf("\t%s ", (servoParams(servoIndex)->reversedSources & (1 << inputSource)) ? "r" : "n");
cliPrintBlankLine();
cliPrintLinefeed();
}
return;
}
@ -1666,7 +1666,7 @@ static void cliSdInfo(char *cmdline)
}
break;
}
cliPrintBlankLine();
cliPrintLinefeed();
}
#endif
@ -1703,7 +1703,7 @@ static void cliFlashErase(char *cmdline)
cliPrintf(".");
if (i++ > 120) {
i=0;
cliPrintBlankLine();
cliPrintLinefeed();
}
bufWriterFlush(cliWriter);
@ -1711,7 +1711,7 @@ static void cliFlashErase(char *cmdline)
delay(100);
}
beeper(BEEPER_BLACKBOX_ERASE);
cliPrintBlankLine();
cliPrintLinefeed();
cliPrintLine("Done.");
}
@ -1762,7 +1762,7 @@ static void cliFlashRead(char *cmdline)
break;
}
}
cliPrintBlankLine();
cliPrintLinefeed();
}
}
@ -1913,7 +1913,7 @@ static void cliFeature(char *cmdline)
if (mask & (1 << i))
cliPrintf("%s ", featureNames[i]);
}
cliPrintBlankLine();
cliPrintLinefeed();
} else if (strncasecmp(cmdline, "list", len) == 0) {
cliPrint("Available:");
for (uint32_t i = 0; ; i++) {
@ -1921,7 +1921,7 @@ static void cliFeature(char *cmdline)
break;
cliPrintf(" %s", featureNames[i]);
}
cliPrintBlankLine();
cliPrintLinefeed();
return;
} else {
bool remove = false;
@ -1998,12 +1998,12 @@ static void cliBeeper(char *cmdline)
if (mask & (1 << i))
cliPrintf(" %s", beeperNameForTableIndex(i));
}
cliPrintBlankLine();
cliPrintLinefeed();
} else if (strncasecmp(cmdline, "list", len) == 0) {
cliPrint("Available:");
for (uint32_t i = 0; i < beeperCount; i++)
cliPrintf(" %s", beeperNameForTableIndex(i));
cliPrintBlankLine();
cliPrintLinefeed();
return;
} else {
bool remove = false;
@ -2308,7 +2308,7 @@ static void cliMixer(char *cmdline)
break;
cliPrintf(" %s", mixerNames[i]);
}
cliPrintBlankLine();
cliPrintLinefeed();
return;
}
@ -2443,7 +2443,7 @@ static void cliDumpPidProfile(uint8_t pidProfileIndex, uint8_t dumpMask)
changePidProfile(pidProfileIndex);
cliPrintHashLine("profile");
cliProfile("");
cliPrintBlankLine();
cliPrintLinefeed();
dumpAllValues(PROFILE_VALUE, dumpMask);
}
@ -2456,7 +2456,7 @@ static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask)
changeControlRateProfile(rateProfileIndex);
cliPrintHashLine("rateprofile");
cliRateProfile("");
cliPrintBlankLine();
cliPrintLinefeed();
dumpAllValues(PROFILE_RATE_VALUE, dumpMask);
}
@ -2488,9 +2488,9 @@ static void cliGet(char *cmdline)
val = &valueTable[i];
cliPrintf("%s = ", valueTable[i].name);
cliPrintVar(val, 0);
cliPrintBlankLine();
cliPrintLinefeed();
cliPrintVarRange(val);
cliPrintBlankLine();
cliPrintLinefeed();
matchedCommands++;
}
@ -2518,7 +2518,7 @@ static void cliSet(char *cmdline)
val = &valueTable[i];
cliPrintf("%s = ", valueTable[i].name);
cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
cliPrintBlankLine();
cliPrintLinefeed();
}
} else if ((eqptr = strstr(cmdline, "=")) != NULL) {
// has equals
@ -2612,7 +2612,7 @@ static void cliStatus(char *cmdline)
}
}
#endif /* USE_SENSOR_NAMES */
cliPrintBlankLine();
cliPrintLinefeed();
#ifdef USE_SDCARD
cliSdInfo(NULL);
@ -2776,7 +2776,7 @@ static void printResource(uint8_t dumpMask)
const ioTag_t ioTagDefault = *((const ioTag_t *)defaultConfig + resourceTable[i].offset + index);
bool equalsDefault = ioTag == ioTagDefault;
const char *format = "resource %s %d %c%02dn";
const char *format = "resource %s %d %c%02d";
const char *formatUnassigned = "resource %s %d NONE";
if (!ioTagDefault) {
cliDefaultPrintLinef(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index));
@ -2858,15 +2858,15 @@ static void cliResource(char *cmdline)
const char* owner;
owner = ownerNames[ioRecs[i].owner];
cliPrintf("%c%02d: %s ", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner);
cliPrintf("%c%02d: %s", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner);
if (ioRecs[i].index > 0) {
cliPrintf("%d", ioRecs[i].index);
cliPrintf(" %d", ioRecs[i].index);
}
cliPrintLine("\r\n");
cliPrintLinefeed();
}
cliPrintLine("\r\n");
cliPrintLine("\r\n");
cliPrintLinefeed();
#ifdef MINIMAL_CLI
cliPrintLine("DMA:");
#else
@ -3028,7 +3028,7 @@ static void printConfig(char *cmdline, bool doDiff)
if ((dumpMask & (DUMP_ALL | DO_DIFF)) == (DUMP_ALL | DO_DIFF)) {
cliPrintHashLine("reset configuration to default settings");
cliPrint("defaults");
cliPrintBlankLine();
cliPrintLinefeed();
}
cliPrintHashLine("name");
@ -3284,7 +3284,7 @@ static void cliHelp(char *cmdline)
cliPrintf("\r\n\t%s", cmdTable[i].args);
}
#endif
cliPrintBlankLine();
cliPrintLinefeed();
}
}
@ -3344,7 +3344,7 @@ void cliProcess(void)
cliPrompt();
} else if (bufferIndex && (c == '\n' || c == '\r')) {
// enter pressed
cliPrintBlankLine();
cliPrintLinefeed();
// Strip comment starting with # from line
char *p = cliBuffer;

View file

@ -541,8 +541,6 @@ void activateConfig(void)
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
configureAltitudeHold(currentPidProfile);
#endif
}

865
src/main/fc/config.c.orig Executable file
View file

@ -0,0 +1,865 @@
/*
* 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 <string.h>
#include <math.h>
#include "platform.h"
#include "build/build_config.h"
#include "build/debug.h"
#include "blackbox/blackbox_io.h"
#include "cms/cms.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/filter.h"
#include "common/maths.h"
#include "config/config_eeprom.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/compass/compass.h"
#include "drivers/inverter.h"
#include "drivers/io.h"
#include "drivers/light_led.h"
#include "drivers/light_ws2811strip.h"
#include "drivers/max7456.h"
#include "drivers/pwm_esc_detect.h"
#include "drivers/pwm_output.h"
#include "drivers/rx_pwm.h"
#include "drivers/rx_spi.h"
#include "drivers/sdcard.h"
#include "drivers/sensor.h"
#include "drivers/serial.h"
#include "drivers/sonar_hcsr04.h"
#include "drivers/sound_beeper.h"
#include "drivers/system.h"
#include "drivers/timer.h"
#include "drivers/vcd.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/fc_core.h"
#include "fc/fc_rc.h"
#include "fc/rc_adjustments.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "flight/altitude.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
#include "flight/mixer.h"
#include "flight/navigation.h"
#include "flight/pid.h"
#include "flight/servos.h"
#include "io/beeper.h"
#include "io/gimbal.h"
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/motors.h"
#include "io/osd.h"
#include "io/serial.h"
#include "io/servos.h"
#include "io/vtx_control.h"
#include "rx/rx.h"
#include "rx/rx_spi.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "sensors/compass.h"
#include "sensors/gyro.h"
#include "sensors/sensors.h"
#include "telemetry/telemetry.h"
#ifndef USE_OSD_SLAVE
pidProfile_t *currentPidProfile;
#endif
#ifndef DEFAULT_FEATURES
#define DEFAULT_FEATURES 0
#endif
#ifndef DEFAULT_RX_FEATURE
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
#endif
#ifndef RX_SPI_DEFAULT_PROTOCOL
#define RX_SPI_DEFAULT_PROTOCOL 0
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0);
PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
.enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE | FEATURE_FAILSAFE
);
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
#ifndef USE_OSD_SLAVE
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
.pidProfileIndex = 0,
.activeRateProfile = 0,
.debug_mode = DEBUG_MODE,
.task_statistics = true,
.name = { 0 } // FIXME misplaced, see PG_PILOT_CONFIG in CF v1.x
);
#endif
#ifdef USE_OSD_SLAVE
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
.debug_mode = DEBUG_MODE,
.task_statistics = true
);
#endif
#ifdef BEEPER
PG_REGISTER(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 0);
#endif
#ifdef USE_ADC
PG_REGISTER_WITH_RESET_FN(adcConfig_t, adcConfig, PG_ADC_CONFIG, 0);
#endif
#ifdef USE_PWM
PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
#endif
#ifdef USE_PPM
PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
#endif
PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
PG_REGISTER_WITH_RESET_FN(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0);
#ifdef USE_FLASHFS
PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
#ifdef M25P16_CS_PIN
#define FLASH_CONFIG_CSTAG IO_TAG(M25P16_CS_PIN)
#else
#define FLASH_CONFIG_CSTAG IO_TAG_NONE
#endif
PG_RESET_TEMPLATE(flashConfig_t, flashConfig,
.csTag = FLASH_CONFIG_CSTAG
);
#endif // USE_FLASH_FS
#ifdef USE_SDCARD
PG_REGISTER_WITH_RESET_TEMPLATE(sdcardConfig_t, sdcardConfig, PG_SDCARD_CONFIG, 0);
#if defined(SDCARD_DMA_CHANNEL_TX)
#define SDCARD_CONFIG_USE_DMA true
#else
#define SDCARD_CONFIG_USE_DMA false
#endif
PG_RESET_TEMPLATE(sdcardConfig_t, sdcardConfig,
.useDma = SDCARD_CONFIG_USE_DMA
);
#endif
// no template required since defaults are zero
PG_REGISTER(vcdProfile_t, vcdProfile, PG_VCD_CONFIG, 0);
#ifdef SONAR
void resetSonarConfig(sonarConfig_t *sonarConfig)
{
#if defined(SONAR_TRIGGER_PIN) && defined(SONAR_ECHO_PIN)
sonarConfig->triggerTag = IO_TAG(SONAR_TRIGGER_PIN);
sonarConfig->echoTag = IO_TAG(SONAR_ECHO_PIN);
#else
#error Sonar not defined for target
#endif
}
#endif
#ifdef USE_ADC
void pgResetFn_adcConfig(adcConfig_t *adcConfig)
{
#ifdef VBAT_ADC_PIN
adcConfig->vbat.enabled = true;
adcConfig->vbat.ioTag = IO_TAG(VBAT_ADC_PIN);
#endif
#ifdef EXTERNAL1_ADC_PIN
adcConfig->external1.enabled = true;
adcConfig->external1.ioTag = IO_TAG(EXTERNAL1_ADC_PIN);
#endif
#ifdef CURRENT_METER_ADC_PIN
adcConfig->current.enabled = true;
adcConfig->current.ioTag = IO_TAG(CURRENT_METER_ADC_PIN);
#endif
#ifdef RSSI_ADC_PIN
adcConfig->rssi.enabled = true;
adcConfig->rssi.ioTag = IO_TAG(RSSI_ADC_PIN);
#endif
}
#endif // USE_ADC
#if defined(USE_PWM) || defined(USE_PPM)
void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig)
{
#ifdef PPM_PIN
ppmConfig->ioTag = IO_TAG(PPM_PIN);
#else
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].usageFlags & TIM_USE_PPM) {
ppmConfig->ioTag = timerHardware[i].tag;
return;
}
}
ppmConfig->ioTag = IO_TAG_NONE;
#endif
}
void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
{
pwmConfig->inputFilteringMode = INPUT_FILTERING_DISABLED;
int inputIndex = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) {
if (timerHardware[i].usageFlags & TIM_USE_PWM) {
pwmConfig->ioTags[inputIndex] = timerHardware[i].tag;
inputIndex++;
}
}
}
#endif
// Default pin (NONE).
// XXX Does this mess belong here???
#ifdef USE_UART1
# if !defined(UART1_RX_PIN)
# define UART1_RX_PIN NONE
# endif
# if !defined(UART1_TX_PIN)
# define UART1_TX_PIN NONE
# endif
#endif
#ifdef USE_UART2
# if !defined(UART2_RX_PIN)
# define UART2_RX_PIN NONE
# endif
# if !defined(UART2_TX_PIN)
# define UART2_TX_PIN NONE
# endif
#endif
#ifdef USE_UART3
# if !defined(UART3_RX_PIN)
# define UART3_RX_PIN NONE
# endif
# if !defined(UART3_TX_PIN)
# define UART3_TX_PIN NONE
# endif
#endif
#ifdef USE_UART4
# if !defined(UART4_RX_PIN)
# define UART4_RX_PIN NONE
# endif
# if !defined(UART4_TX_PIN)
# define UART4_TX_PIN NONE
# endif
#endif
#ifdef USE_UART5
# if !defined(UART5_RX_PIN)
# define UART5_RX_PIN NONE
# endif
# if !defined(UART5_TX_PIN)
# define UART5_TX_PIN NONE
# endif
#endif
#ifdef USE_UART6
# if !defined(UART6_RX_PIN)
# define UART6_RX_PIN NONE
# endif
# if !defined(UART6_TX_PIN)
# define UART6_TX_PIN NONE
# endif
#endif
#ifdef USE_UART7
# if !defined(UART7_RX_PIN)
# define UART7_RX_PIN NONE
# endif
# if !defined(UART7_TX_PIN)
# define UART7_TX_PIN NONE
# endif
#endif
#ifdef USE_UART8
# if !defined(UART8_RX_PIN)
# define UART8_RX_PIN NONE
# endif
# if !defined(UART8_TX_PIN)
# define UART8_TX_PIN NONE
# endif
#endif
#ifdef USE_SOFTSERIAL1
# if !defined(SOFTSERIAL1_RX_PIN)
# define SOFTSERIAL1_RX_PIN NONE
# endif
# if !defined(SOFTSERIAL1_TX_PIN)
# define SOFTSERIAL1_TX_PIN NONE
# endif
#endif
#ifdef USE_SOFTSERIAL2
# if !defined(SOFTSERIAL2_RX_PIN)
# define SOFTSERIAL2_RX_PIN NONE
# endif
# if !defined(SOFTSERIAL2_TX_PIN)
# define SOFTSERIAL2_TX_PIN NONE
# endif
#endif
void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
{
for (int port = 0 ; port < SERIAL_PORT_MAX_INDEX ; port++) {
serialPinConfig->ioTagRx[port] = IO_TAG(NONE);
serialPinConfig->ioTagTx[port] = IO_TAG(NONE);
}
for (int index = 0 ; index < SERIAL_PORT_COUNT ; index++) {
switch (serialPortIdentifiers[index]) {
case SERIAL_PORT_USART1:
#ifdef USE_UART1
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART1)] = IO_TAG(UART1_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART1)] = IO_TAG(UART1_TX_PIN);
<<<<<<< HEAD
#ifdef INVERTER_PIN_UART1
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART1)] = IO_TAG(INVERTER_PIN_UART1);
#endif
=======
>>>>>>> betaflight/master
#endif
break;
case SERIAL_PORT_USART2:
#ifdef USE_UART2
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART2)] = IO_TAG(UART2_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART2)] = IO_TAG(UART2_TX_PIN);
<<<<<<< HEAD
#ifdef INVERTER_PIN_UART2
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART2)] = IO_TAG(INVERTER_PIN_UART2);
#endif
=======
>>>>>>> betaflight/master
#endif
break;
case SERIAL_PORT_USART3:
#ifdef USE_UART3
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART3)] = IO_TAG(UART3_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART3)] = IO_TAG(UART3_TX_PIN);
<<<<<<< HEAD
#ifdef INVERTER_PIN_UART3
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART3)] = IO_TAG(INVERTER_PIN_UART3);
#endif
=======
>>>>>>> betaflight/master
#endif
break;
case SERIAL_PORT_UART4:
#ifdef USE_UART4
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_UART4)] = IO_TAG(UART4_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_UART4)] = IO_TAG(UART4_TX_PIN);
<<<<<<< HEAD
#ifdef INVERTER_PIN_UART4
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART4)] = IO_TAG(INVERTER_PIN_UART4);
#endif
=======
>>>>>>> betaflight/master
#endif
break;
case SERIAL_PORT_UART5:
#ifdef USE_UART5
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_UART5)] = IO_TAG(UART5_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_UART5)] = IO_TAG(UART5_TX_PIN);
<<<<<<< HEAD
#ifdef INVERTER_PIN_UART5
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART5)] = IO_TAG(INVERTER_PIN_UART5);
#endif
=======
>>>>>>> betaflight/master
#endif
break;
case SERIAL_PORT_USART6:
#ifdef USE_UART6
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART6)] = IO_TAG(UART6_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART6)] = IO_TAG(UART6_TX_PIN);
<<<<<<< HEAD
#ifdef INVERTER_PIN_UART6
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART6)] = IO_TAG(INVERTER_PIN_UART6);
#endif
=======
>>>>>>> betaflight/master
#endif
break;
case SERIAL_PORT_USART7:
#ifdef USE_UART7
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART7)] = IO_TAG(UART7_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART7)] = IO_TAG(UART7_TX_PIN);
#endif
break;
case SERIAL_PORT_USART8:
#ifdef USE_UART8
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART8)] = IO_TAG(UART8_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART8)] = IO_TAG(UART8_TX_PIN);
#endif
break;
case SERIAL_PORT_SOFTSERIAL1:
#ifdef USE_SOFTSERIAL1
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_SOFTSERIAL1)] = IO_TAG(SOFTSERIAL1_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_SOFTSERIAL1)] = IO_TAG(SOFTSERIAL1_TX_PIN);
#endif
break;
case SERIAL_PORT_SOFTSERIAL2:
#ifdef USE_SOFTSERIAL2
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_SOFTSERIAL2)] = IO_TAG(SOFTSERIAL2_RX_PIN);
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_SOFTSERIAL2)] = IO_TAG(SOFTSERIAL2_TX_PIN);
#endif
break;
case SERIAL_PORT_USB_VCP:
break;
case SERIAL_PORT_NONE:
break;
}
}
}
#ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
#define FIRST_PORT_INDEX 1
#define SECOND_PORT_INDEX 0
#else
#define FIRST_PORT_INDEX 0
#define SECOND_PORT_INDEX 1
#endif
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
{
for (int i = 0; i < LED_NUMBER; i++) {
statusLedConfig->ledTags[i] = IO_TAG_NONE;
}
#ifdef LED0
statusLedConfig->ledTags[0] = IO_TAG(LED0);
#endif
#ifdef LED1
statusLedConfig->ledTags[1] = IO_TAG(LED1);
#endif
#ifdef LED2
statusLedConfig->ledTags[2] = IO_TAG(LED2);
#endif
statusLedConfig->polarity = 0
#ifdef LED0_INVERTED
| BIT(0)
#endif
#ifdef LED1_INVERTED
| BIT(1)
#endif
#ifdef LED2_INVERTED
| BIT(2)
#endif
;
}
#ifndef USE_OSD_SLAVE
uint8_t getCurrentPidProfileIndex(void)
{
return systemConfig()->pidProfileIndex;
}
static void setPidProfile(uint8_t pidProfileIndex)
{
if (pidProfileIndex < MAX_PROFILE_COUNT) {
systemConfigMutable()->pidProfileIndex = pidProfileIndex;
currentPidProfile = pidProfilesMutable(pidProfileIndex);
pidInit(currentPidProfile); // re-initialise pid controller to re-initialise filters and config
}
}
uint8_t getCurrentControlRateProfileIndex(void)
{
return systemConfigMutable()->activeRateProfile;
}
uint16_t getCurrentMinthrottle(void)
{
return motorConfig()->minthrottle;
}
#endif
void resetConfigs(void)
{
pgResetAll(MAX_PROFILE_COUNT);
#if defined(TARGET_CONFIG)
targetConfiguration();
#endif
pgActivateProfile(0);
#ifndef USE_OSD_SLAVE
setPidProfile(0);
setControlRateProfile(0);
#endif
#ifdef LED_STRIP
reevaluateLedConfig();
#endif
}
void activateConfig(void)
{
#ifndef USE_OSD_SLAVE
generateThrottleCurve();
resetAdjustmentStates();
useRcControlsConfig(modeActivationConditions(0), currentPidProfile);
useAdjustmentConfig(currentPidProfile);
#ifdef GPS
gpsUsePIDs(currentPidProfile);
#endif
failsafeReset();
setAccelerationTrims(&accelerometerConfigMutable()->accZero);
setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
#endif
}
void validateAndFixConfig(void)
{
#ifndef USE_OSD_SLAVE
if((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)){
motorConfigMutable()->mincommand = 1000;
}
if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
}
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
featureSet(DEFAULT_RX_FEATURE);
}
if (featureConfigured(FEATURE_RX_PPM)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
}
if (featureConfigured(FEATURE_RX_MSP)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
}
if (featureConfigured(FEATURE_RX_SERIAL)) {
featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
}
if (featureConfigured(FEATURE_RX_SPI)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
}
if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
#if defined(STM32F10X)
// rssi adc needs the same ports
featureClear(FEATURE_RSSI_ADC);
// current meter needs the same ports
if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
}
#endif
// software serial needs free PWM ports
featureClear(FEATURE_SOFTSERIAL);
}
#ifdef USE_SOFTSPI
if (featureConfigured(FEATURE_SOFTSPI)) {
featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL);
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_NONE;
#if defined(STM32F10X)
featureClear(FEATURE_LED_STRIP);
// rssi adc needs the same ports
featureClear(FEATURE_RSSI_ADC);
// current meter needs the same ports
if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
}
#endif
}
#endif
// Prevent invalid notch cutoff
if (currentPidProfile->dterm_notch_cutoff >= currentPidProfile->dterm_notch_hz) {
currentPidProfile->dterm_notch_hz = 0;
}
validateAndFixGyroConfig();
#endif
if (!isSerialConfigValid(serialConfig())) {
pgResetFn_serialConfig(serialConfigMutable());
}
#if defined(TARGET_VALIDATECONFIG)
targetValidateConfiguration();
#endif
}
#ifndef USE_OSD_SLAVE
void validateAndFixGyroConfig(void)
{
// Prevent invalid notch cutoff
if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
}
if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
}
float samplingTime = 0.000125f;
if (gyroConfig()->gyro_lpf != GYRO_LPF_256HZ && gyroConfig()->gyro_lpf != GYRO_LPF_NONE) {
pidConfigMutable()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
gyroConfigMutable()->gyro_sync_denom = 1;
gyroConfigMutable()->gyro_use_32khz = false;
samplingTime = 0.001f;
}
if (gyroConfig()->gyro_use_32khz) {
samplingTime = 0.00003125;
// F1 and F3 can't handle high sample speed.
#if defined(STM32F1)
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
#elif defined(STM32F3)
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
#endif
} else {
#if defined(STM32F1)
gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 3);
#endif
}
#if !defined(GYRO_USES_SPI) || !defined(USE_MPU_DATA_READY_SIGNAL)
gyroConfigMutable()->gyro_isr_update = false;
#endif
// check for looptime restrictions based on motor protocol. Motor times have safety margin
const float pidLooptime = samplingTime * gyroConfig()->gyro_sync_denom * pidConfig()->pid_process_denom;
float motorUpdateRestriction;
switch(motorConfig()->dev.motorPwmProtocol) {
case (PWM_TYPE_STANDARD):
motorUpdateRestriction = 1.0f/BRUSHLESS_MOTORS_PWM_RATE;
break;
case (PWM_TYPE_ONESHOT125):
motorUpdateRestriction = 0.0005f;
break;
case (PWM_TYPE_ONESHOT42):
motorUpdateRestriction = 0.0001f;
break;
#ifdef USE_DSHOT
case (PWM_TYPE_DSHOT150):
motorUpdateRestriction = 0.000250f;
break;
case (PWM_TYPE_DSHOT300):
motorUpdateRestriction = 0.0001f;
break;
#endif
default:
motorUpdateRestriction = 0.00003125f;
}
if (pidLooptime < motorUpdateRestriction) {
const uint8_t maxPidProcessDenom = constrain(motorUpdateRestriction / (samplingTime * gyroConfig()->gyro_sync_denom), 1, MAX_PID_PROCESS_DENOM);
pidConfigMutable()->pid_process_denom = MIN(pidConfigMutable()->pid_process_denom, maxPidProcessDenom);
}
// Prevent overriding the max rate of motors
if (motorConfig()->dev.useUnsyncedPwm && (motorConfig()->dev.motorPwmProtocol <= PWM_TYPE_BRUSHED) && motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD) {
uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
if(motorConfig()->dev.motorPwmRate > maxEscRate)
motorConfigMutable()->dev.motorPwmRate = maxEscRate;
}
}
#endif
void readEEPROM(void)
{
#ifndef USE_OSD_SLAVE
suspendRxSignal();
#endif
// Sanity check, read flash
if (!loadEEPROM()) {
failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
}
#ifndef USE_OSD_SLAVE
if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {// sanity check
systemConfigMutable()->activeRateProfile = 0;
}
setControlRateProfile(systemConfig()->activeRateProfile);
if (systemConfig()->pidProfileIndex >= MAX_PROFILE_COUNT) {// sanity check
systemConfigMutable()->pidProfileIndex = 0;
}
setPidProfile(systemConfig()->pidProfileIndex);
#endif
validateAndFixConfig();
activateConfig();
#ifndef USE_OSD_SLAVE
resumeRxSignal();
#endif
}
void writeEEPROM(void)
{
#ifndef USE_OSD_SLAVE
suspendRxSignal();
#endif
writeConfigToEEPROM();
#ifndef USE_OSD_SLAVE
resumeRxSignal();
#endif
}
void resetEEPROM(void)
{
resetConfigs();
writeEEPROM();
}
void ensureEEPROMContainsValidData(void)
{
if (isEEPROMContentValid()) {
return;
}
resetEEPROM();
}
void saveConfigAndNotify(void)
{
writeEEPROM();
readEEPROM();
beeperConfirmationBeeps(1);
}
#ifndef USE_OSD_SLAVE
void changePidProfile(uint8_t pidProfileIndex)
{
if (pidProfileIndex >= MAX_PROFILE_COUNT) {
pidProfileIndex = MAX_PROFILE_COUNT - 1;
}
systemConfigMutable()->pidProfileIndex = pidProfileIndex;
currentPidProfile = pidProfilesMutable(pidProfileIndex);
beeperConfirmationBeeps(pidProfileIndex + 1);
}
#endif
void beeperOffSet(uint32_t mask)
{
#ifdef BEEPER
beeperConfigMutable()->beeper_off_flags |= mask;
#else
UNUSED(mask);
#endif
}
void beeperOffSetAll(uint8_t beeperCount)
{
#ifdef BEEPER
beeperConfigMutable()->beeper_off_flags = (1 << beeperCount) -1;
#else
UNUSED(beeperCount);
#endif
}
void beeperOffClear(uint32_t mask)
{
#ifdef BEEPER
beeperConfigMutable()->beeper_off_flags &= ~(mask);
#else
UNUSED(mask);
#endif
}
void beeperOffClearAll(void)
{
#ifdef BEEPER
beeperConfigMutable()->beeper_off_flags = 0;
#endif
}
uint32_t getBeeperOffMask(void)
{
#ifdef BEEPER
return beeperConfig()->beeper_off_flags;
#else
return 0;
#endif
}
void setBeeperOffMask(uint32_t mask)
{
#ifdef BEEPER
beeperConfigMutable()->beeper_off_flags = mask;
#else
UNUSED(mask);
#endif
}
uint32_t getPreferredBeeperOffMask(void)
{
#ifdef BEEPER
return beeperConfig()->preferred_beeper_off_flags;
#else
return 0;
#endif
}
void setPreferredBeeperOffMask(uint32_t mask)
{
#ifdef BEEPER
beeperConfigMutable()->preferred_beeper_off_flags = mask;
#else
UNUSED(mask);
#endif
}

View file

@ -177,7 +177,7 @@ void mwDisarm(void)
#ifdef BLACKBOX
if (blackboxConfig()->device) {
finishBlackbox();
blackboxFinish();
}
#endif
BEEP_OFF;
@ -555,7 +555,7 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs)
#ifdef BLACKBOX
if (!cliMode && blackboxConfig()->device) {
handleBlackbox(currentTimeUs);
blackboxUpdate(currentTimeUs);
}
#else
UNUSED(currentTimeUs);

View file

@ -550,7 +550,7 @@ void init(void)
#endif
#ifdef BLACKBOX
initBlackbox();
blackboxInit();
#endif
if (mixerConfig()->mixerMode == MIXER_GIMBAL) {

View file

@ -792,7 +792,7 @@ static bool mspOsdSlaveProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostPro
switch (cmdMSP) {
case MSP_STATUS_EX:
sbufWriteU16(dst, 0); // task delta
sbufWriteU16(dst, getTaskDeltaTime(TASK_SERIAL));
#ifdef USE_I2C
sbufWriteU16(dst, i2cGetErrorCounter());
#else
@ -807,7 +807,7 @@ static bool mspOsdSlaveProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostPro
break;
case MSP_STATUS:
sbufWriteU16(dst, 0); // task delta
sbufWriteU16(dst, getTaskDeltaTime(TASK_SERIAL));
#ifdef USE_I2C
sbufWriteU16(dst, i2cGetErrorCounter());
#else
@ -1375,7 +1375,6 @@ static void mspFcDataFlashReadCommand(sbuf_t *dst, sbuf_t *src)
static mspResult_e mspOsdSlaveProcessInCommand(uint8_t cmdMSP, sbuf_t *src) {
UNUSED(cmdMSP);
UNUSED(src);
// Nothing OSD SLAVE specific yet.
return MSP_RESULT_ERROR;
}
#endif
@ -2145,8 +2144,31 @@ void mspFcProcessReply(mspPacket_t *reply)
UNUSED(src); // potentially unused depending on compile options.
switch (reply->cmd) {
case MSP_DISPLAYPORT: {
#ifndef OSD_SLAVE
case MSP_ANALOG:
{
uint8_t batteryVoltage = sbufReadU8(src);
uint16_t mAhDrawn = sbufReadU16(src);
uint16_t rssi = sbufReadU16(src);
uint16_t amperage = sbufReadU16(src);
UNUSED(rssi);
UNUSED(batteryVoltage);
UNUSED(amperage);
UNUSED(mAhDrawn);
#ifdef USE_MSP_CURRENT_METER
currentMeterMSPSet(amperage, mAhDrawn);
#endif
break;
}
#endif
#ifdef USE_OSD_SLAVE
case MSP_DISPLAYPORT:
{
osdSlaveIsLocked = true; // lock it as soon as a MSP_DISPLAYPORT message is received to prevent accidental CLI/DFU mode.
int subCmd = sbufReadU8(src);
switch (subCmd) {
@ -2184,9 +2206,9 @@ void mspFcProcessReply(mspPacket_t *reply)
osdSlaveDrawScreen();
}
}
#endif
break;
}
#endif
}
}

View file

@ -33,3 +33,5 @@ void mspFcInit(void);
void mspOsdSlaveInit(void);
mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn);
void mspFcProcessReply(mspPacket_t *reply);
void mspSerialProcessStreamSchedule(void);

View file

@ -23,6 +23,8 @@
#include "cms/cms.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/utils.h"
@ -81,6 +83,8 @@
#include "telemetry/telemetry.h"
#include "io/osd_slave.h"
#ifdef USE_BST
void taskBstMasterProcess(timeUs_t currentTimeUs);
#endif
@ -115,7 +119,12 @@ static void taskHandleSerial(timeUs_t currentTimeUs)
return;
}
#endif
mspSerialProcess(ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA, mspFcProcessCommand, mspFcProcessReply);
#ifndef OSD_SLAVE
bool evaluateMspData = ARMING_FLAG(ARMED) ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA;
#else
bool evaluateMspData = osdSlaveIsLocked ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA;;
#endif
mspSerialProcess(evaluateMspData, mspFcProcessCommand, mspFcProcessReply);
}
void taskBatteryAlerts(timeUs_t currentTimeUs)

View file

@ -291,7 +291,7 @@ const clivalue_t valueTable[] = {
{ "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO_LPF }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lpf) },
{ "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 32 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_sync_denom) },
{ "gyro_lowpass_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_lpf_type) },
{ "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 255 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_lpf_hz) },
{ "gyro_lowpass_hz", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 255 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_lpf_hz) },
{ "gyro_notch1_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_hz_1) },
{ "gyro_notch1_cutoff", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_cutoff_1) },
{ "gyro_notch2_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_hz_2) },
@ -373,6 +373,7 @@ const clivalue_t valueTable[] = {
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 32 }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, rate_denom) },
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) },
{ "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, on_motor_test) },
{ "blackbox_record_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, record_acc) },
#endif
// PG_MOTOR_CONFIG
@ -380,7 +381,7 @@ const clivalue_t valueTable[] = {
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, maxthrottle) },
{ "min_command", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, mincommand) },
#ifdef USE_DSHOT
{ "digital_idle_value", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, digitalIdleOffsetValue) },
{ "dshot_idle_value", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, digitalIdleOffsetValue) },
#endif
{ "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useUnsyncedPwm) },
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmProtocol) },
@ -463,7 +464,7 @@ const clivalue_t valueTable[] = {
{ "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 255 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcRate8) },
{ "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 255 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawRate8) },
{ "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcExpo8) },
{ "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawExpo8) },
{ "rc_expo_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawExpo8) },
{ "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrMid8) },
{ "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrExpo8) },
{ "roll_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_ROLL]) },
@ -508,7 +509,9 @@ const clivalue_t valueTable[] = {
#endif
// PG_AIRPLANE_CONFIG
#if defined(BARO) || defined(SONAR)
{ "fixedwing_althold_reversed", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_AIRPLANE_CONFIG, offsetof(airplaneConfig_t, fixedwing_althold_reversed) },
#endif
// PG_RC_CONTROLS_CONFIG
{ "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 250 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, alt_hold_deadband) },
@ -521,18 +524,18 @@ const clivalue_t valueTable[] = {
{ "pid_process_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, MAX_PID_PROCESS_DENOM }, PG_PID_CONFIG, offsetof(pidConfig_t, pid_process_denom) },
// PG_PID_PROFILE
{ "d_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_filter_type) },
{ "d_lowpass", VAR_INT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_lpf_hz) },
{ "d_notch_hz", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_hz) },
{ "d_notch_cut", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_cutoff) },
{ "dterm_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_filter_type) },
{ "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_lpf_hz) },
{ "dterm_notch_hz", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_hz) },
{ "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_cutoff) },
{ "vbat_pid_gain", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, vbatPidCompensation) },
{ "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, pidAtMinThrottle) },
{ "anti_gravity_thresh", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 20, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermThrottleThreshold) },
{ "anti_gravity_threshold", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 20, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermThrottleThreshold) },
{ "anti_gravity_gain", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 30000 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermAcceleratorGain) },
{ "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, setpointRelaxRatio) },
{ "d_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 254 }, PG_PID_PROFILE, offsetof(pidProfile_t, dtermSetpointWeight) },
{ "yaw_accel_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, yawRateAccelLimit) },
{ "accel_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, rateAccelLimit) },
{ "dterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 254 }, PG_PID_PROFILE, offsetof(pidProfile_t, dtermSetpointWeight) },
{ "acc_limit_yaw", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, yawRateAccelLimit) },
{ "acc_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, rateAccelLimit) },
{ "crash_dthreshold", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 2000 }, PG_PID_PROFILE, offsetof(pidProfile_t, crash_dthreshold) },
{ "crash_gthreshold", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 2000 }, PG_PID_PROFILE, offsetof(pidProfile_t, crash_gthreshold) },
{ "crash_time", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 5000 }, PG_PID_PROFILE, offsetof(pidProfile_t, crash_time) },
@ -646,6 +649,10 @@ const clivalue_t valueTable[] = {
{ "osd_pidrate_profile_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_PIDRATE_PROFILE]) },
{ "osd_battery_warning_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAIN_BATT_WARNING]) },
{ "osd_avg_cell_voltage_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_AVG_CELL_VOLTAGE]) },
{ "osd_pit_ang_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_PITCH_ANGLE]) },
{ "osd_rol_ang_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ROLL_ANGLE]) },
{ "osd_battery_usage_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAIN_BATT_USAGE]) },
#endif
// PG_SYSTEM_CONFIG

View file

@ -31,6 +31,7 @@
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
@ -45,6 +46,13 @@
#include "sensors/sonar.h"
int32_t AltHold;
static int32_t estimatedVario = 0; // variometer in cm/s
static int32_t estimatedAltitude = 0; // in cm
#if defined(BARO) || defined(SONAR)
enum {
DEBUG_ALTITUDE_ACC,
DEBUG_ALTITUDE_VEL,
@ -57,24 +65,10 @@ PG_RESET_TEMPLATE(airplaneConfig_t, airplaneConfig,
.fixedwing_althold_reversed = false
);
int32_t setVelocity = 0;
uint8_t velocityControl = 0;
int32_t errorVelocityI = 0;
int32_t altHoldThrottleAdjustment = 0;
int32_t AltHold;
int32_t estimatedVario = 0; // variometer in cm/s
static int32_t estimatedAltitude = 0; // in cm
static pidProfile_t *pidProfile;
void configureAltitudeHold(pidProfile_t *initialPidProfile)
{
pidProfile = initialPidProfile;
}
#if defined(BARO) || defined(SONAR)
static int32_t setVelocity = 0;
static uint8_t velocityControl = 0;
static int32_t errorVelocityI = 0;
static int32_t altHoldThrottleAdjustment = 0;
static int16_t initialThrottleHold;
// 40hz update rate (20hz LPF on acc)
@ -187,7 +181,7 @@ int32_t calculateAltHoldThrottleAdjustment(int32_t vel_tmp, float accZ_tmp, floa
if (!velocityControl) {
error = constrain(AltHold - estimatedAltitude, -500, 500);
error = applyDeadband(error, 10); // remove small P parameter to reduce noise near zero position
setVel = constrain((pidProfile->P8[PIDALT] * error / 128), -300, +300); // limit velocity to +/- 3 m/s
setVel = constrain((currentPidProfile->P8[PIDALT] * error / 128), -300, +300); // limit velocity to +/- 3 m/s
} else {
setVel = setVelocity;
}
@ -195,15 +189,15 @@ int32_t calculateAltHoldThrottleAdjustment(int32_t vel_tmp, float accZ_tmp, floa
// P
error = setVel - vel_tmp;
result = constrain((pidProfile->P8[PIDVEL] * error / 32), -300, +300);
result = constrain((currentPidProfile->P8[PIDVEL] * error / 32), -300, +300);
// I
errorVelocityI += (pidProfile->I8[PIDVEL] * error);
errorVelocityI += (currentPidProfile->I8[PIDVEL] * error);
errorVelocityI = constrain(errorVelocityI, -(8192 * 200), (8192 * 200));
result += errorVelocityI / 8192; // I in range +/-200
// D
result -= constrain(pidProfile->D8[PIDVEL] * (accZ_tmp + accZ_old) / 512, -150, 150);
result -= constrain(currentPidProfile->D8[PIDVEL] * (accZ_tmp + accZ_old) / 512, -150, 150);
return result;
}
@ -285,7 +279,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
baroVel = constrain(baroVel, -1500, 1500); // constrain baro velocity +/- 1500cm/s
baroVel = applyDeadband(baroVel, 10); // to reduce noise near zero
}
#endif
#endif // BARO
// apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity).
// By using CF it's possible to correct the drift of integrated accZ (velocity) without loosing the phase, i.e without delay
@ -299,7 +293,7 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)
altHoldThrottleAdjustment = calculateAltHoldThrottleAdjustment(vel_tmp, accZ_tmp, accZ_old);
accZ_old = accZ_tmp;
}
#endif
#endif // defined(BARO) || defined(SONAR)
int32_t getEstimatedAltitude(void)
{

View file

@ -31,9 +31,6 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs);
int32_t getEstimatedAltitude(void);
int32_t getEstimatedVario(void);
struct pidProfile_s;
void configureAltitudeHold(struct pidProfile_s *initialPidProfile);
void applyAltHold(void);
void updateAltHoldState(void);
void updateSonarAltHoldState(void);

View file

@ -88,7 +88,7 @@ void failsafeInit(void)
return;
}
failsafePhase_e failsafePhase()
failsafePhase_e failsafePhase(void)
{
return failsafeState.phase;
}

View file

@ -58,7 +58,7 @@ static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *buf, int len
return 0;
}
#endif
return mspSerialPush(cmd, buf, len);
return mspSerialPush(cmd, buf, len, MSP_DIRECTION_REPLY);
}
static int heartbeat(displayPort_t *displayPort)

View file

@ -28,6 +28,7 @@
#include <stdlib.h>
#include <string.h>
#include <ctype.h>
#include <math.h>
#include "platform.h"
@ -471,6 +472,44 @@ static void osdDrawSingleElement(uint8_t item)
break;
}
case OSD_PITCH_ANGLE:
case OSD_ROLL_ANGLE:
{
const int angle = (item == OSD_PITCH_ANGLE) ? attitude.values.pitch : attitude.values.roll;
tfp_sprintf(buff, "%c%02d.%01d", angle < 0 ? '-' : ' ', abs(angle / 10), abs(angle % 10));
break;
}
case OSD_MAIN_BATT_USAGE:
{
//Set length of indicator bar
#define MAIN_BATT_USAGE_STEPS 10
//Calculate constrained value
float value = constrain(batteryConfig()->batteryCapacity - getMAhDrawn(), 0, batteryConfig()->batteryCapacity);
//Calculate mAh used progress
uint8_t mAhUsedProgress = ceil((value / (batteryConfig()->batteryCapacity / MAIN_BATT_USAGE_STEPS)));
//Create empty battery indicator bar
buff[0] = SYM_PB_START;
for(uint8_t i = 1; i <= MAIN_BATT_USAGE_STEPS; i++) {
if (i <= mAhUsedProgress)
buff[i] = SYM_PB_FULL;
else
buff[i] = SYM_PB_EMPTY;
}
buff[MAIN_BATT_USAGE_STEPS+1] = SYM_PB_CLOSE;
if (mAhUsedProgress > 0 && mAhUsedProgress < MAIN_BATT_USAGE_STEPS) {
buff[1+mAhUsedProgress] = SYM_PB_END;
}
buff[MAIN_BATT_USAGE_STEPS+2] = 0;
break;
}
default:
return;
}
@ -522,6 +561,9 @@ void osdDrawElements(void)
osdDrawSingleElement(OSD_MAIN_BATT_WARNING);
osdDrawSingleElement(OSD_AVG_CELL_VOLTAGE);
osdDrawSingleElement(OSD_DEBUG);
osdDrawSingleElement(OSD_PITCH_ANGLE);
osdDrawSingleElement(OSD_ROLL_ANGLE);
osdDrawSingleElement(OSD_MAIN_BATT_USAGE);
#ifdef GPS
#ifdef CMS
@ -564,9 +606,13 @@ void pgResetFn_osdConfig(osdConfig_t *osdProfile)
osdProfile->item_pos[OSD_MAIN_BATT_WARNING] = OSD_POS(9, 10) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_AVG_CELL_VOLTAGE] = OSD_POS(12, 2) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_DEBUG] = OSD_POS(7, 12) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_PITCH_ANGLE] = OSD_POS(1, 8) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_ROLL_ANGLE] = OSD_POS(1, 9) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_GPS_LAT] = OSD_POS(18, 14) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_GPS_LON] = OSD_POS(18, 15) | VISIBLE_FLAG;
osdProfile->item_pos[OSD_MAIN_BATT_USAGE] = OSD_POS(15, 10) | VISIBLE_FLAG;
osdProfile->units = OSD_UNIT_METRIC;
osdProfile->rssi_alarm = 20;
@ -654,10 +700,14 @@ void osdUpdateAlarms(void)
else
CLR_BLINK(OSD_FLYTIME);
if (getMAhDrawn() >= osdConfig()->cap_alarm)
if (getMAhDrawn() >= osdConfig()->cap_alarm) {
SET_BLINK(OSD_MAH_DRAWN);
else
SET_BLINK(OSD_MAIN_BATT_USAGE);
}
else {
CLR_BLINK(OSD_MAH_DRAWN);
CLR_BLINK(OSD_MAIN_BATT_USAGE);
}
if (alt >= osdConfig()->alt_alarm)
SET_BLINK(OSD_ALTITUDE);
@ -675,6 +725,7 @@ void osdResetAlarms(void)
CLR_BLINK(OSD_MAH_DRAWN);
CLR_BLINK(OSD_ALTITUDE);
CLR_BLINK(OSD_AVG_CELL_VOLTAGE);
CLR_BLINK(OSD_MAIN_BATT_USAGE);
}
static void osdResetStats(void)

View file

@ -53,6 +53,9 @@ typedef enum {
OSD_GPS_LON,
OSD_GPS_LAT,
OSD_DEBUG,
OSD_PITCH_ANGLE,
OSD_ROLL_ANGLE,
OSD_MAIN_BATT_USAGE,
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;

View file

@ -40,6 +40,9 @@
//#define OSD_SLAVE_DEBUG
// when locked the system ignores requests to enter cli or bootloader mode via serial connection.
bool osdSlaveIsLocked = false;
static displayPort_t *osdDisplayPort;
static void osdDrawLogo(int x, int y)

View file

@ -22,6 +22,8 @@
struct displayPort_s;
extern bool osdSlaveIsLocked;
// init
void osdSlaveInit(struct displayPort_s *osdDisplayPort);

View file

@ -85,7 +85,7 @@ typedef enum {
extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
#define SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(x) (((x) <= SERIAL_PORT_USART8) ? (x) : (RESOURCE_SOFT_OFFSET + ((x) - SERIAL_PORT_SOFTSERIAL1)))
#define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) (((x) <= SERIAL_PORT_USART8) ? (x) : (RESOURCE_SOFT_OFFSET + ((x) - SERIAL_PORT_SOFTSERIAL1)))
//
// runtime

View file

@ -69,11 +69,11 @@
#define SERIAL_4WAY_INTERFACE_NAME_STR "m4wFCIntf"
// *** change to adapt Revision
#define SERIAL_4WAY_VER_MAIN 14
#define SERIAL_4WAY_VER_SUB_1 (uint8_t) 4
#define SERIAL_4WAY_VER_SUB_2 (uint8_t) 04
#define SERIAL_4WAY_VER_MAIN 20
#define SERIAL_4WAY_VER_SUB_1 (uint8_t) 0
#define SERIAL_4WAY_VER_SUB_2 (uint8_t) 00
#define SERIAL_4WAY_PROTOCOL_VER 106
#define SERIAL_4WAY_PROTOCOL_VER 107
// *** end
#if (SERIAL_4WAY_VER_MAIN > 24)
@ -254,6 +254,13 @@ void esc4wayRelease(void)
// PARAM: uint8_t Mode
// RETURN: ACK or ACK_I_INVALID_CHANNEL
//Write to Buffer for Verify Device Memory of connected Device //Buffer Len is Max 256 Bytes
//BuffLen = 0 means 256 Bytes
#define cmd_DeviceVerify 0x40 //'@' write
//PARAM: uint8_t ADRESS_Hi + ADRESS_Lo + BUffLen + Buffer[0..255]
//RETURN: ACK
// responses
#define ACK_OK 0x00
// #define ACK_I_UNKNOWN_ERROR 0x01
@ -323,13 +330,16 @@ uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data) {
(pDeviceInfo->words[0] == 0xF850) || (pDeviceInfo->words[0] == 0xE8B1) || \
(pDeviceInfo->words[0] == 0xE8B2))
#define ARM_DEVICE_MATCH ((pDeviceInfo->words[0] == 0x9307) || (pDeviceInfo->words[0] == 0x930A) || \
(pDeviceInfo->words[0] == 0x3306) || (pDeviceInfo->words[0] == 0x3406))
static uint8_t CurrentInterfaceMode;
static uint8_t Connect(uint8_32_u *pDeviceInfo)
{
for (uint8_t I = 0; I < 3; ++I) {
#if (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
if (Stk_ConnectEx(pDeviceInfo) && ATMEL_DEVICE_MATCH) {
if ((CurrentInterfaceMode != imARM_BLB) && Stk_ConnectEx(pDeviceInfo) && ATMEL_DEVICE_MATCH) {
CurrentInterfaceMode = imSK;
return 1;
} else {
@ -340,6 +350,9 @@ static uint8_t Connect(uint8_32_u *pDeviceInfo)
} else if ATMEL_DEVICE_MATCH {
CurrentInterfaceMode = imATM_BLB;
return 1;
} else if ARM_DEVICE_MATCH {
CurrentInterfaceMode = imARM_BLB;
return 1;
}
}
}
@ -351,6 +364,9 @@ static uint8_t Connect(uint8_32_u *pDeviceInfo)
} else if ATMEL_DEVICE_MATCH {
CurrentInterfaceMode = imATM_BLB;
return 1;
} else if ARM_DEVICE_MATCH {
CurrentInterfaceMode = imARM_BLB;
return 1;
}
}
#elif defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
@ -470,6 +486,7 @@ void esc4wayProcess(serialPort_t *mspPort)
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
case imATM_BLB:
case imSIL_BLB:
case imARM_BLB:
{
if (!BL_SendCMDKeepAlive()) { // SetStateDisconnected() included
ACK_OUT = ACK_D_GENERAL_ERROR;
@ -526,9 +543,9 @@ void esc4wayProcess(serialPort_t *mspPort)
case cmd_InterfaceSetMode:
{
#if defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
if ((ParamBuf[0] <= imSK) && (ParamBuf[0] >= imSIL_BLB)) {
if ((ParamBuf[0] <= imARM_BLB) && (ParamBuf[0] >= imSIL_BLB)) {
#elif defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER)
if ((ParamBuf[0] <= imATM_BLB) && (ParamBuf[0] >= imSIL_BLB)) {
if (((ParamBuf[0] <= imATM_BLB)||(ParamBuf[0] == imARM_BLB)) && (ParamBuf[0] >= imSIL_BLB)) {
#elif defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
if (ParamBuf[0] == imSK) {
#endif
@ -551,9 +568,10 @@ void esc4wayProcess(serialPort_t *mspPort)
}
switch (CurrentInterfaceMode)
{
case imSIL_BLB:
case imSIL_BLB:
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
case imATM_BLB:
case imARM_BLB:
{
BL_SendCMDRunRestartBootloader(&DeviceInfo);
break;
@ -614,10 +632,16 @@ void esc4wayProcess(serialPort_t *mspPort)
switch (CurrentInterfaceMode)
{
case imSIL_BLB:
case imARM_BLB:
{
Dummy.bytes[0] = ParamBuf[0];
//Address = Page * 512
ioMem.D_FLASH_ADDR_H = (Dummy.bytes[0] << 1);
if (CurrentInterfaceMode == imARM_BLB) {
// Address =Page * 1024
ioMem.D_FLASH_ADDR_H = (Dummy.bytes[0] << 2);
} else {
// Address =Page * 512
ioMem.D_FLASH_ADDR_H = (Dummy.bytes[0] << 1);
}
ioMem.D_FLASH_ADDR_L = 0;
if (!BL_PageErase(&ioMem)) ACK_OUT = ACK_D_GENERAL_ERROR;
break;
@ -643,6 +667,7 @@ void esc4wayProcess(serialPort_t *mspPort)
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
case imSIL_BLB:
case imATM_BLB:
case imARM_BLB:
{
if(!BL_ReadFlash(CurrentInterfaceMode, &ioMem))
{
@ -727,6 +752,7 @@ void esc4wayProcess(serialPort_t *mspPort)
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
case imSIL_BLB:
case imATM_BLB:
case imARM_BLB:
{
if (!BL_WriteFlash(&ioMem)) {
ACK_OUT = ACK_D_GENERAL_ERROR;
@ -787,6 +813,44 @@ void esc4wayProcess(serialPort_t *mspPort)
}
break;
}
//*** Device Memory Verify Ops ***
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
case cmd_DeviceVerify:
{
switch (CurrentInterfaceMode)
{
case imARM_BLB:
{
ioMem.D_NUM_BYTES = I_PARAM_LEN;
/*
wtf.D_FLASH_ADDR_H=Adress_H;
wtf.D_FLASH_ADDR_L=Adress_L;
wtf.D_PTR_I = BUF_I;
*/
ACK_OUT = BL_VerifyFlash(&ioMem);
switch (ACK_OUT) {
case brSUCCESS:
ACK_OUT = ACK_OK;
break;
case brERRORVERIFY:
ACK_OUT = ACK_I_VERIFY_ERROR;
break;
default:
ACK_OUT = ACK_D_GENERAL_ERROR;
break;
}
break;
}
default:
{
ACK_OUT = ACK_I_INVALID_CMD;
break;
}
}
break;
}
#endif
default:
{
ACK_OUT = ACK_I_INVALID_CMD;

View file

@ -27,6 +27,7 @@
#define imSIL_BLB 1
#define imATM_BLB 2
#define imSK 3
#define imARM_BLB 4
extern uint8_t selected_esc;

View file

@ -48,6 +48,7 @@
#define CMD_ERASE_FLASH 0x02
#define CMD_READ_FLASH_SIL 0x03
#define CMD_VERIFY_FLASH 0x03
#define CMD_VERIFY_FLASH_ARM 0x04
#define CMD_READ_EEPROM 0x04
#define CMD_PROG_EEPROM 0x05
#define CMD_READ_SRAM 0x06
@ -59,14 +60,6 @@
#define CMD_BOOTINIT 0x07
#define CMD_BOOTSIGN 0x08
// Bootloader result codes
#define brSUCCESS 0x30
#define brERRORCOMMAND 0xC1
#define brERRORCRC 0xC2
#define brNONE 0xFF
#define START_BIT_TIMEOUT_MS 2
#define BIT_TIME (52) // 52uS
@ -318,7 +311,7 @@ uint8_t BL_PageErase(ioMem_t *pMem)
if (BL_SendCMDSetAddress(pMem)) {
uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};
BL_SendBuf(sCMD, 2);
return (BL_GetACK((40 / START_BIT_TIMEOUT_MS)) == brSUCCESS);
return (BL_GetACK((1000 / START_BIT_TIMEOUT_MS)) == brSUCCESS);
}
return 0;
}
@ -333,6 +326,17 @@ uint8_t BL_WriteFlash(ioMem_t *pMem)
return BL_WriteA(CMD_PROG_FLASH, pMem, (40 / START_BIT_TIMEOUT_MS));
}
uint8_t BL_VerifyFlash(ioMem_t *pMem)
{
if (BL_SendCMDSetAddress(pMem)) {
if (!BL_SendCMDSetBuffer(pMem)) return 0;
uint8_t sCMD[] = {CMD_VERIFY_FLASH_ARM, 0x01};
BL_SendBuf(sCMD, 2);
return (BL_GetACK(40 / START_BIT_TIMEOUT_MS));
}
return 0;
}
#endif
#if defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && defined(USE_FAKE_ESC)

View file

@ -19,6 +19,12 @@
*/
#pragma once
// Bootloader result codes
#define brSUCCESS 0x30
#define brERRORVERIFY 0xC0
#define brERRORCOMMAND 0xC1
#define brERRORCRC 0xC2
#define brNONE 0xFF
void BL_SendBootInit(void);
uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo);
@ -28,4 +34,5 @@ uint8_t BL_ReadEEprom(ioMem_t *pMem);
uint8_t BL_WriteEEprom(ioMem_t *pMem);
uint8_t BL_WriteFlash(ioMem_t *pMem);
uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem);
uint8_t BL_VerifyFlash(ioMem_t *pMem);
void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo);

View file

@ -695,7 +695,7 @@ bool vtxSmartAudioInit()
void vtxSAProcess(uint32_t now)
{
static bool initialSent = false;
static char initPhase = 0;
if (smartAudioSerialPort == NULL)
return;
@ -708,12 +708,20 @@ void vtxSAProcess(uint32_t now)
// Re-evaluate baudrate after each frame reception
saAutobaud();
if (!initialSent) {
switch (initPhase) {
case 0:
saGetSettings();
saSetFreq(SA_FREQ_GETPIT);
saSendQueue();
initialSent = true;
++initPhase;
return;
case 1:
// Don't send SA_FREQ_GETPIT to V1 device; it act as plain SA_CMD_SET_FREQ,
// and put the device into user frequency mode with uninitialized freq.
if (saDevice.version == 2)
saSetFreq(SA_FREQ_GETPIT);
++initPhase;
break;
}
if ((sa_outstanding != SA_CMD_NONE)
@ -876,7 +884,7 @@ uint16_t saCmsDeviceFreq = 0;
uint8_t saCmsDeviceStatus = 0;
uint8_t saCmsPower;
uint8_t saCmsPitFMode; // In-Range or Out-Range
uint8_t saCmsPitFMode; // Undef(0), In-Range(1) or Out-Range(2)
uint8_t saCmsFselMode; // Channel(0) or User defined(1)
uint16_t saCmsORFreq = 0; // POR frequency
@ -942,10 +950,12 @@ if (saCmsORFreq == 0 && saDevice.orfreq != 0)
if (saCmsUserFreq == 0 && saDevice.freq != 0)
saCmsUserFreq = saDevice.freq;
if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
saCmsPitFMode = 1;
else
saCmsPitFMode = 0;
if (saDevice.version == 2) {
if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE)
saCmsPitFMode = 1;
else
saCmsPitFMode = 0;
}
saCmsStatusString[0] = "-FR"[saCmsOpmodel];
@ -1060,9 +1070,21 @@ static long saCmsConfigPitFModeByGvar(displayPort_t *pDisp, const void *self)
UNUSED(pDisp);
UNUSED(self);
if (saDevice.version == 1) {
// V1 device doesn't support PIT mode; bounce back.
saCmsPitFMode = 0;
return 0;
}
dprintf(("saCmsConfigPitFmodeByGbar: saCmsPitFMode %d\r\n", saCmsPitFMode));
if (saCmsPitFMode == 0) {
// Bounce back
saCmsPitFMode = 1;
return 0;
}
if (saCmsPitFMode == 1) {
saSetMode(SA_MODE_SET_IN_RANGE_PITMODE);
} else {
saSetMode(SA_MODE_SET_OUT_RANGE_PITMODE);
@ -1078,6 +1100,12 @@ static long saCmsConfigOpmodelByGvar(displayPort_t *pDisp, const void *self)
UNUSED(pDisp);
UNUSED(self);
if (saDevice.version == 1) {
if (saCmsOpmodel != SACMS_OPMODEL_FREE)
saCmsOpmodel = SACMS_OPMODEL_FREE;
return 0;
}
uint8_t opmodel = saCmsOpmodel;
dprintf(("saCmsConfigOpmodelByGvar: opmodel %d\r\n", opmodel));
@ -1163,6 +1191,7 @@ static const char * const saCmsFselModeNames[] = {
};
static const char * const saCmsPitFModeNames[] = {
"---",
"PIR",
"POR"
};
@ -1227,6 +1256,9 @@ static long saCmsCommence(displayPort_t *pDisp, const void *self)
static long saCmsSetPORFreqOnEnter(void)
{
if (saDevice.version == 1)
return MENU_CHAIN_BACK;
saCmsORFreqNew = saCmsORFreq;
return 0;

View file

@ -26,10 +26,16 @@ typedef enum {
MSP_RESULT_NO_REPLY = 0
} mspResult_e;
typedef enum {
MSP_DIRECTION_REPLY = 0,
MSP_DIRECTION_REQUEST = 1
} mspDirection_e;
typedef struct mspPacket_s {
sbuf_t buf;
int16_t cmd;
int16_t result;
uint8_t direction;
} mspPacket_t;
struct serialPort_s;

View file

@ -59,7 +59,7 @@
#define MSP_PROTOCOL_VERSION 0
#define API_VERSION_MAJOR 1 // increment when major changes are made
#define API_VERSION_MINOR 35 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
#define API_VERSION_MINOR 36 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
#define API_VERSION_LENGTH 2
@ -101,7 +101,6 @@
#define MSP_NAME 10 //out message Returns user set board name - betaflight
#define MSP_SET_NAME 11 //in message Sets board name - betaflight
//
// MSP commands for Cleanflight original features
//
@ -312,3 +311,4 @@
#define MSP_SERVO_MIX_RULES 241 //out message Returns servo mixer configuration
#define MSP_SET_SERVO_MIX_RULE 242 //in message Sets servo mixer configuration
#define MSP_SET_4WAY_IF 245 //in message Sets 4way interface

View file

@ -27,12 +27,13 @@
#include "io/serial.h"
#include "drivers/system.h"
#include "msp/msp.h"
#include "msp/msp_serial.h"
static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort)
{
memset(mspPortToReset, 0, sizeof(mspPort_t));
@ -138,7 +139,13 @@ static int mspSerialEncode(mspPort_t *msp, mspPacket_t *packet)
serialBeginWrite(msp->port);
const int len = sbufBytesRemaining(&packet->buf);
const int mspLen = len < JUMBO_FRAME_SIZE_LIMIT ? len : JUMBO_FRAME_SIZE_LIMIT;
uint8_t hdr[8] = {'$', 'M', packet->result == MSP_RESULT_ERROR ? '!' : '>', mspLen, packet->cmd};
uint8_t hdr[8] = {
'$',
'M',
packet->result == MSP_RESULT_ERROR ? '!' : packet->direction == MSP_DIRECTION_REPLY ? '>' : '<',
mspLen,
packet->cmd
};
int hdrLen = 5;
#define CHECKSUM_STARTPOS 3 // checksum starts from mspLen field
if (len >= JUMBO_FRAME_SIZE_LIMIT) {
@ -165,6 +172,7 @@ static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspPr
.buf = { .ptr = outBuf, .end = ARRAYEND(outBuf), },
.cmd = -1,
.result = 0,
.direction = MSP_DIRECTION_REPLY,
};
uint8_t *outBufHead = reply.buf.ptr;
@ -172,6 +180,7 @@ static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspPr
.buf = { .ptr = msp->inBuf, .end = msp->inBuf + msp->dataSize, },
.cmd = msp->cmdMSP,
.result = 0,
.direction = MSP_DIRECTION_REQUEST,
};
mspPostProcessFnPtr mspPostProcessFn = NULL;
@ -182,7 +191,6 @@ static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspPr
mspSerialEncode(msp, &reply);
}
msp->c_state = MSP_IDLE;
return mspPostProcessFn;
}
@ -215,7 +223,9 @@ void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessComm
if (!mspPort->port) {
continue;
}
mspPostProcessFnPtr mspPostProcessFn = NULL;
while (serialRxBytesWaiting(mspPort->port)) {
const uint8_t c = serialRead(mspPort->port);
@ -231,9 +241,12 @@ void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessComm
} else if (mspPort->packetType == MSP_PACKET_REPLY) {
mspSerialProcessReceivedReply(mspPort, mspProcessReplyFn);
}
mspPort->c_state = MSP_IDLE;
break; // process one command at a time so as not to block.
}
}
if (mspPostProcessFn) {
waitForSerialPortToFinishTransmitting(mspPort->port);
mspPostProcessFn(mspPort->port);
@ -262,7 +275,7 @@ void mspSerialInit(void)
mspSerialAllocatePorts();
}
int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen, mspDirection_e direction)
{
int ret = 0;
@ -281,6 +294,7 @@ int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
.buf = { .ptr = data, .end = data + datalen, },
.cmd = cmd,
.result = 0,
.direction = direction,
};
ret = mspSerialEncode(mspPort, &push);
@ -288,6 +302,7 @@ int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
return ret; // return the number of bytes written
}
uint32_t mspSerialTxBytesFree()
{
uint32_t ret = UINT32_MAX;

View file

@ -67,11 +67,10 @@ typedef struct mspPort_s {
uint8_t inBuf[MSP_PORT_INBUF_SIZE];
} mspPort_t;
void mspSerialInit(void);
bool mspSerialWaiting(void);
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn, mspProcessReplyFnPtr mspProcessReplyFn);
void mspSerialAllocatePorts(void);
void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort);
int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen);
int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen, mspDirection_e direction);
uint32_t mspSerialTxBytesFree(void);

View file

@ -227,17 +227,14 @@ void scheduler(void)
const timeUs_t currentTimeUs = micros();
// Check for realtime tasks
timeUs_t timeToNextRealtimeTask = TIMEUS_MAX;
bool outsideRealtimeGuardInterval = true;
for (const cfTask_t *task = queueFirst(); task != NULL && task->staticPriority >= TASK_PRIORITY_REALTIME; task = queueNext()) {
const timeUs_t nextExecuteAt = task->lastExecutedAt + task->desiredPeriod;
if ((int32_t)(currentTimeUs - nextExecuteAt) >= 0) {
timeToNextRealtimeTask = 0;
} else {
const timeUs_t newTimeInterval = nextExecuteAt - currentTimeUs;
timeToNextRealtimeTask = MIN(timeToNextRealtimeTask, newTimeInterval);
if ((timeDelta_t)(currentTimeUs - nextExecuteAt) >= 0) {
outsideRealtimeGuardInterval = false;
break;
}
}
const bool outsideRealtimeGuardInterval = (timeToNextRealtimeTask > 0);
// The task to be invoked
cfTask_t *selectedTask = NULL;

View file

@ -76,9 +76,13 @@ static batteryState_e consumptionState;
#ifdef USE_VIRTUAL_CURRENT_METER
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_VIRTUAL
#else
#ifdef USE_MSP_CURRENT_METER
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_MSP
#else
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_NONE
#endif
#endif
#endif
#ifdef BOARD_HAS_VOLTAGE_DIVIDER
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
@ -302,6 +306,11 @@ void batteryInit(void)
case CURRENT_METER_ESC:
#ifdef ESC_SENSOR
currentMeterESCInit();
#endif
break;
case CURRENT_METER_MSP:
#ifdef USE_MSP_CURRENT_METER
currentMeterMSPInit();
#endif
break;
@ -362,6 +371,12 @@ void batteryUpdateCurrentMeter(timeUs_t currentTimeUs)
currentMeterESCRefresh(lastUpdateAt);
currentMeterESCReadCombined(&currentMeter);
}
#endif
break;
case CURRENT_METER_MSP:
#ifdef USE_MSP_CURRENT_METER
currentMeterMSPRefresh(currentTimeUs);
currentMeterMSPRead(&currentMeter);
#endif
break;

View file

@ -56,12 +56,15 @@ const uint8_t currentMeterIds[] = {
CURRENT_METER_ID_ESC_MOTOR_11,
CURRENT_METER_ID_ESC_MOTOR_12,
#endif
#ifdef USE_MSP_CURRENT_METER
CURRENT_METER_ID_MSP_1,
#endif
};
const uint8_t supportedCurrentMeterCount = ARRAYLEN(currentMeterIds);
//
// ADC/Virtual/ESC shared
// ADC/Virtual/ESC/MSP shared
//
void currentMeterReset(currentMeter_t *meter)
@ -225,6 +228,45 @@ void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter)
}
#endif
#ifdef USE_MSP_CURRENT_METER
#include "common/streambuf.h"
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h"
currentMeterMSPState_t currentMeterMSPState;
void currentMeterMSPSet(uint16_t amperage, uint16_t mAhDrawn)
{
// We expect the FC's MSP_ANALOG response handler to call this function
currentMeterMSPState.amperage = amperage;
currentMeterMSPState.mAhDrawn = mAhDrawn;
}
void currentMeterMSPInit(void)
{
memset(&currentMeterMSPState, 0, sizeof(currentMeterMSPState_t));
}
void currentMeterMSPRefresh(timeUs_t currentTimeUs)
{
// periodically request MSP_ANALOG
static timeUs_t streamRequestAt = 0;
if (cmp32(currentTimeUs, streamRequestAt) > 0) {
streamRequestAt = currentTimeUs + ((1000 * 1000) / 10); // 10hz
mspSerialPush(MSP_ANALOG, NULL, 0, MSP_DIRECTION_REQUEST);
}
}
void currentMeterMSPRead(currentMeter_t *meter)
{
meter->amperageLatest = currentMeterMSPState.amperage;
meter->amperage = currentMeterMSPState.amperage;
meter->mAhDrawn = currentMeterMSPState.mAhDrawn;
}
#endif
//
// API for current meters using IDs
//
@ -241,6 +283,11 @@ void currentMeterRead(currentMeterId_e id, currentMeter_t *meter)
currentMeterVirtualRead(meter);
}
#endif
#ifdef USE_MSP_CURRENT_METER
else if (id == CURRENT_METER_ID_MSP_1) {
currentMeterMSPRead(meter);
}
#endif
#ifdef USE_ESC_SENSOR
else if (id == CURRENT_METER_ID_ESC_COMBINED_1) {
currentMeterESCReadCombined(meter);

View file

@ -17,6 +17,7 @@
#pragma once
#include "common/time.h"
#include "current_ids.h"
typedef enum {
@ -24,6 +25,7 @@ typedef enum {
CURRENT_METER_ADC,
CURRENT_METER_VIRTUAL,
CURRENT_METER_ESC,
CURRENT_METER_MSP,
CURRENT_METER_MAX = CURRENT_METER_ESC
} currentMeterSource_e;
@ -48,6 +50,7 @@ typedef enum {
CURRENT_SENSOR_VIRTUAL = 0,
CURRENT_SENSOR_ADC,
CURRENT_SENSOR_ESC,
CURRENT_SENSOR_MSP
} currentSensor_e;
@ -93,6 +96,21 @@ typedef struct currentMeterESCState_s {
int32_t amperage; // current read by current sensor in centiampere (1/100th A)
} currentMeterESCState_t;
//
// MSP
//
typedef struct currentMeterMSPState_s {
int32_t mAhDrawn; // milliampere hours drawn from the battery since start
int32_t amperage; // current read by current sensor in centiampere (1/100th A)
} currentMeterMSPState_t;
//
// Current Meter API
//
void currentMeterReset(currentMeter_t *meter);
void currentMeterADCInit(void);
@ -108,6 +126,11 @@ void currentMeterESCRefresh(int32_t lastUpdateAt);
void currentMeterESCReadCombined(currentMeter_t *meter);
void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter);
void currentMeterMSPInit(void);
void currentMeterMSPRefresh(timeUs_t currentTimeUs);
void currentMeterMSPRead(currentMeter_t *meter);
void currentMeterMSPSet(uint16_t amperage, uint16_t mAhDrawn);
//
// API for reading current meters by id.
//

View file

@ -66,4 +66,7 @@ typedef enum {
CURRENT_METER_ID_VIRTUAL_1 = 80, // 80-89 for virtual meters
CURRENT_METER_ID_VIRTUAL_2,
CURRENT_METER_ID_MSP_1 = 90, // 90-99 for MSP meters
CURRENT_METER_ID_MSP_2,
} currentMeterId_e;

View file

@ -74,7 +74,13 @@ gyro_t gyro;
STATIC_UNIT_TESTED gyroDev_t gyroDev0;
static int16_t gyroTemperature0;
static uint16_t calibratingG = 0;
typedef struct gyroCalibration_s {
int32_t g[XYZ_AXIS_COUNT];
stdev_t var[XYZ_AXIS_COUNT];
uint16_t calibratingG;
} gyroCalibration_t;
STATIC_UNIT_TESTED gyroCalibration_t gyroCalibration;
static filterApplyFnPtr softLpfFilterApplyFn;
static void *softLpfFilter[3];
@ -412,12 +418,12 @@ void gyroInitFilters(void)
bool isGyroCalibrationComplete(void)
{
return calibratingG == 0;
return gyroCalibration.calibratingG == 0;
}
static bool isOnFinalGyroCalibrationCycle(void)
static bool isOnFinalGyroCalibrationCycle(const gyroCalibration_t *gyroCalibration)
{
return calibratingG == 1;
return gyroCalibration->calibratingG == 1;
}
static uint16_t gyroCalculateCalibratingCycles(void)
@ -425,56 +431,50 @@ static uint16_t gyroCalculateCalibratingCycles(void)
return (CALIBRATING_GYRO_CYCLES / gyro.targetLooptime) * CALIBRATING_GYRO_CYCLES;
}
static bool isOnFirstGyroCalibrationCycle(void)
static bool isOnFirstGyroCalibrationCycle(const gyroCalibration_t *gyroCalibration)
{
return calibratingG == gyroCalculateCalibratingCycles();
return gyroCalibration->calibratingG == gyroCalculateCalibratingCycles();
}
void gyroSetCalibrationCycles(void)
{
calibratingG = gyroCalculateCalibratingCycles();
gyroCalibration.calibratingG = gyroCalculateCalibratingCycles();
}
STATIC_UNIT_TESTED void performGyroCalibration(gyroDev_t *gyroDev, uint8_t gyroMovementCalibrationThreshold)
STATIC_UNIT_TESTED void performGyroCalibration(gyroDev_t *gyroDev, gyroCalibration_t *gyroCalibration, uint8_t gyroMovementCalibrationThreshold)
{
static int32_t g[3];
static stdev_t var[3];
for (int axis = 0; axis < 3; axis++) {
// Reset g[axis] at start of calibration
if (isOnFirstGyroCalibrationCycle()) {
g[axis] = 0;
devClear(&var[axis]);
if (isOnFirstGyroCalibrationCycle(gyroCalibration)) {
gyroCalibration->g[axis] = 0;
devClear(&gyroCalibration->var[axis]);
// gyroZero is set to zero until calibration complete
gyroDev->gyroZero[axis] = 0;
}
// Sum up CALIBRATING_GYRO_CYCLES readings
g[axis] += gyroDev->gyroADC[axis];
devPush(&var[axis], gyroDev->gyroADC[axis]);
gyroCalibration->g[axis] += gyroDev->gyroADCRaw[axis];
devPush(&gyroCalibration->var[axis], gyroDev->gyroADCRaw[axis]);
// Reset global variables to prevent other code from using un-calibrated data
gyroDev->gyroADC[axis] = 0;
gyroDev->gyroZero[axis] = 0;
if (isOnFinalGyroCalibrationCycle(gyroCalibration)) {
const float stddev = devStandardDeviation(&gyroCalibration->var[axis]);
if (isOnFinalGyroCalibrationCycle()) {
const float dev = devStandardDeviation(&var[axis]);
DEBUG_SET(DEBUG_GYRO, DEBUG_GYRO_CALIBRATION, lrintf(dev));
DEBUG_SET(DEBUG_GYRO, DEBUG_GYRO_CALIBRATION, lrintf(stddev));
// check deviation and startover in case the model was moved
if (gyroMovementCalibrationThreshold && dev > gyroMovementCalibrationThreshold) {
if (gyroMovementCalibrationThreshold && stddev > gyroMovementCalibrationThreshold) {
gyroSetCalibrationCycles();
return;
}
gyroDev->gyroZero[axis] = (g[axis] + (gyroCalculateCalibratingCycles() / 2)) / gyroCalculateCalibratingCycles();
gyroDev->gyroZero[axis] = (gyroCalibration->g[axis] + (gyroCalculateCalibratingCycles() / 2)) / gyroCalculateCalibratingCycles();
}
}
if (isOnFinalGyroCalibrationCycle()) {
if (isOnFinalGyroCalibrationCycle(gyroCalibration)) {
schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics
beeper(BEEPER_GYRO_CALIBRATED);
}
calibratingG--;
gyroCalibration->calibratingG--;
}
@ -489,14 +489,13 @@ static bool gyroUpdateISR(gyroDev_t* gyroDev)
#endif
gyroDev->dataReady = false;
// move gyro data into 32-bit variables to avoid overflows in calculations
gyroDev->gyroADC[X] = gyroDev->gyroADCRaw[X];
gyroDev->gyroADC[Y] = gyroDev->gyroADCRaw[Y];
gyroDev->gyroADC[Z] = gyroDev->gyroADCRaw[Z];
gyroDev->gyroADC[X] = (int32_t)gyroDev->gyroADCRaw[X] - (int32_t)gyroDev->gyroZero[X];
gyroDev->gyroADC[Y] = (int32_t)gyroDev->gyroADCRaw[Y] - (int32_t)gyroDev->gyroZero[Y];
gyroDev->gyroADC[Z] = (int32_t)gyroDev->gyroADCRaw[Z] - (int32_t)gyroDev->gyroZero[Z];
alignSensors(gyroDev->gyroADC, gyroDev->gyroAlign);
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroDev->gyroADC[axis] -= gyroDev->gyroZero[axis];
// scale gyro output to degrees per second
float gyroADCf = (float)gyroDev->gyroADC[axis] * gyroDev->scale;
gyroADCf = softLpfFilterApplyFn(softLpfFilter[axis], gyroADCf);
@ -522,15 +521,8 @@ void gyroUpdate(void)
return;
}
gyroDev0.dataReady = false;
// move gyro data into 32-bit variables to avoid overflows in calculations
gyroDev0.gyroADC[X] = gyroDev0.gyroADCRaw[X];
gyroDev0.gyroADC[Y] = gyroDev0.gyroADCRaw[Y];
gyroDev0.gyroADC[Z] = gyroDev0.gyroADCRaw[Z];
alignSensors(gyroDev0.gyroADC, gyroDev0.gyroAlign);
const bool calibrationComplete = isGyroCalibrationComplete();
if (calibrationComplete) {
if (isGyroCalibrationComplete()) {
#if defined(GYRO_USES_SPI) && defined(USE_MPU_DATA_READY_SIGNAL)
// SPI-based gyro so can read and update in ISR
if (gyroConfig()->gyro_isr_update) {
@ -541,12 +533,23 @@ void gyroUpdate(void)
#ifdef DEBUG_MPU_DATA_READY_INTERRUPT
debug[3] = (uint16_t)(micros() & 0xffff);
#endif
// move gyro data into 32-bit variables to avoid overflows in calculations
gyroDev0.gyroADC[X] = (int32_t)gyroDev0.gyroADCRaw[X] - (int32_t)gyroDev0.gyroZero[X];
gyroDev0.gyroADC[Y] = (int32_t)gyroDev0.gyroADCRaw[Y] - (int32_t)gyroDev0.gyroZero[Y];
gyroDev0.gyroADC[Z] = (int32_t)gyroDev0.gyroADCRaw[Z] - (int32_t)gyroDev0.gyroZero[Z];
alignSensors(gyroDev0.gyroADC, gyroDev0.gyroAlign);
} else {
performGyroCalibration(&gyroDev0, gyroConfig()->gyroMovementCalibrationThreshold);
performGyroCalibration(&gyroDev0, &gyroCalibration, gyroConfig()->gyroMovementCalibrationThreshold);
// Reset gyro values to zero to prevent other code from using uncalibrated data
gyro.gyroADCf[X] = 0.0f;
gyro.gyroADCf[Y] = 0.0f;
gyro.gyroADCf[Z] = 0.0f;
// still calibrating, so no need to further process gyro data
return;
}
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroDev0.gyroADC[axis] -= gyroDev0.gyroZero[axis];
// scale gyro output to degrees per second
float gyroADCf = (float)gyroDev0.gyroADC[axis] * gyroDev0.scale;
@ -561,11 +564,6 @@ void gyroUpdate(void)
gyro.gyroADCf[axis] = gyroADCf;
}
if (!calibrationComplete) {
gyroDev0.gyroADC[X] = lrintf(gyro.gyroADCf[X] / gyroDev0.scale);
gyroDev0.gyroADC[Y] = lrintf(gyro.gyroADCf[Y] / gyroDev0.scale);
gyroDev0.gyroADC[Z] = lrintf(gyro.gyroADCf[Z] / gyroDev0.scale);
}
#ifdef USE_GYRO_DATA_ANALYSE
gyroDataAnalyse(&gyroDev0, &gyro);
#endif

View file

@ -1,6 +1,6 @@
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 and ALIENFLIGHTNGF7 target)
AlienWii is now AlienFlight. This designs are released for public and some for noncommercial use at:
AlienWii is now AlienFlight. This designs are released partially for public (CC BY-SA 4.0) and some for noncommercial use (CC BY-NC-SA 4.0) at:
http://www.alienflight.com
@ -8,7 +8,7 @@ AlienFlight F3 Eagle files are available at:
https://github.com/MJ666/Flight-Controllers
AlienFlightNG (Next Generation) designs are released for noncommercial use can be found here:
AlienFlightNG (Next Generation) designs are released for noncommercial use (CC BY-NC-SA 4.0) or (CC BY-NC-ND 4.0) can be found here:
http://www.alienflightng.com
@ -50,10 +50,10 @@ Here are the general hardware specifications for this boards:
(*) 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). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.

View file

@ -1,6 +1,6 @@
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 and ALIENFLIGHTNGF7 target)
AlienWii is now AlienFlight. This designs are released for public and some for noncommercial use at:
AlienWii is now AlienFlight. This designs are released partially for public (CC BY-SA 4.0) and some for noncommercial use (CC BY-NC-SA 4.0) at:
http://www.alienflight.com
@ -8,7 +8,7 @@ AlienFlight F3 Eagle files are available at:
https://github.com/MJ666/Flight-Controllers
AlienFlightNG (Next Generation) designs are released for noncommercial use can be found here:
AlienFlightNG (Next Generation) designs are released for noncommercial use (CC BY-NC-SA 4.0) or (CC BY-NC-ND 4.0) can be found here:
http://www.alienflightng.com
@ -50,10 +50,10 @@ Here are the general hardware specifications for this boards:
(*) 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). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.

View file

@ -1,6 +1,6 @@
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 and ALIENFLIGHTNGF7 target)
AlienWii is now AlienFlight. This designs are released for public and some for noncommercial use at:
AlienWii is now AlienFlight. This designs are released partially for public (CC BY-SA 4.0) and some for noncommercial use (CC BY-NC-SA 4.0) at:
http://www.alienflight.com
@ -8,7 +8,7 @@ AlienFlight F3 Eagle files are available at:
https://github.com/MJ666/Flight-Controllers
AlienFlightNG (Next Generation) designs are released for noncommercial use can be found here:
AlienFlightNG (Next Generation) designs are released for noncommercial use (CC BY-NC-SA 4.0) or (CC BY-NC-ND 4.0) can be found here:
http://www.alienflightng.com
@ -50,10 +50,10 @@ Here are the general hardware specifications for this boards:
(*) 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). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.

View file

@ -1,6 +1,6 @@
# AlienFlight (ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 and ALIENFLIGHTNGF7 target)
AlienWii is now AlienFlight. This designs are released for public and some for noncommercial use at:
AlienWii is now AlienFlight. This designs are released partially for public (CC BY-SA 4.0) and some for noncommercial use (CC BY-NC-SA 4.0) at:
http://www.alienflight.com
@ -8,7 +8,7 @@ AlienFlight F3 Eagle files are available at:
https://github.com/MJ666/Flight-Controllers
AlienFlightNG (Next Generation) designs are released for noncommercial use can be found here:
AlienFlightNG (Next Generation) designs are released for noncommercial use (CC BY-NC-SA 4.0) or (CC BY-NC-ND 4.0) can be found here:
http://www.alienflightng.com
@ -50,10 +50,10 @@ Here are the general hardware specifications for this boards:
(*) 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). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
set spektrum_sat_bind = 5
(**) This receiver is based on the uSky and OpenSky projects. http://www.fishpepper.de
For more detail of the different bind modes please refer the CleanFlight Spektrum Bind document.

View file

@ -27,10 +27,10 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // S1_IN
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S3_IN
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S4_IN
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S5_IN
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S6_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S4_IN DMA2_ST3 DMA2_ST2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S6_IN DMA2_ST7
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S10_OUT 1 DMA1_ST7
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S6_OUT 2 DMA1_ST1

View file

@ -21,13 +21,11 @@
#define USBD_PRODUCT_STRING "AnyFCF7"
#define USE_ESC_SENSOR
#define LED0 PB7
#define LED1 PB6
//#define BEEPER PB2
//#define BEEPER_INVERTED
#define BEEPER PB2 // Unused pin, can be mapped to elsewhere
#define BEEPER_INVERTED
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
@ -111,6 +109,7 @@
#define SPI4_MOSI_PIN PE14
#define USE_SDCARD
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD3
#define SDCARD_DETECT_EXTI_LINE EXTI_Line3
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource3

View file

@ -0,0 +1,19 @@
# AnyFC-M7
* STM32F722 board, made by [@sambas](https://github.com/sambas)
* OSHW CC BY-SA 3.0
* Source: https://github.com/sambas/hw/tree/master/AnyFCM7
* 1st test with betaflight: https://www.youtube.com/watch?v=E4KqkaSy30g
## HW info
* STM32F722RET6 64lqfp 216MHz
* MPU6000 SPI
* MS5611 baro
* 4 uarts available + VCP
* 10 pwm outputs + 6 inputs
* external I2C
* external SPI (shared with U4/5)
* 128Mb dataflash logging (SPI)
* Voltage measurement, with 10k/1k divider

View file

@ -0,0 +1,46 @@
/*
* 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 <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // S1_IN
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S4_IN DMA2_ST3 DMA2_ST2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0 ), // S6_IN DMA2_ST7
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S10_OUT 1 DMA1_ST7
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S6_OUT 2 DMA1_ST1
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S5_OUT 3 DMA1_ST3
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1 ), // S1_OUT 4 DMA1_ST7 DMA1_ST6
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S2_OUT DMA1_ST4
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, 1 ), // S3_OUT DMA2_ST6 DMA2_ST2
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0 ), // S4_OUT DMA1_ST5
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S7_OUT DMA1_ST2
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, 0 ), // S8_OUT DMA2_ST6
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S9_OUT DMA1_ST4
};

View file

@ -0,0 +1,130 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "ANYM"
#define USBD_PRODUCT_STRING "AnyFCM7"
#define USE_ESC_SENSOR
#define LED0 PB6 //red
#define LED1 PB9 //blue
#define BEEPER PB2 // Unused pin, can be mapped to elsewhere
#define BEEPER_INVERTED
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
// MPU6000 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_INT_EXTI PC4
#define USE_EXTI
#define MAG
//#define USE_MAG_HMC5883
//#define HMC5883_BUS I2C_DEVICE_EXT
//#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
//#define MAG_HMC5883_ALIGN CW90_DEG
#define BARO
#define USE_BARO_MS5611
#define USABLE_TIMER_CHANNEL_COUNT 16
#define USE_VCP
#define VBUS_SENSING_PIN PA8
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
//#define USE_UART2
#define UART2_RX_PIN PA3
#define UART2_TX_PIN PA2
//#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PC11
#define UART4_TX_PIN PC10
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 7 //VCP, USART1, UART4, UART5, USART6, SOFTSERIAL x 2
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PC2
#define SPI2_MOSI_PIN PC1
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C_DEVICE (I2CDEV_2)
#define USE_ADC
#define VBAT_ADC_PIN PC0
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12))

View file

@ -0,0 +1,8 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/barometer/barometer_ms5611.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c

View file

@ -144,8 +144,6 @@
#define VBAT_ADC_PIN PC3
#define CURRENT_METER_ADC_PIN PC2
#define USE_ESC_SENSOR
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL

View file

@ -0,0 +1,14 @@
MCU: STM32F722RE
IMU: MPU-6000
IMU Interrupt: yes
BARO: NO
VCP: YES
Hardware UARTS:
OSD: uses a AB7456 chip
Blackbox: SD Card
PPM/UART NOT Shared: YES
Battery Voltage Sensor: 10:1
Current sensor: 0.5 mOhm, 250 Current scale in the setting
Integrated Voltage Regulator: 1.2A 5v
Integrated Volrage Regulator: 1.2A 7.8V for clean vtx and camera power
120A Current sensing PDB and 150A burst current for 10S on the current sensing Resistor

View file

@ -0,0 +1,42 @@
/*
* 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 <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
// DSHOT will work for motor 1-6.
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM4, CH3, PB8, TIM_USE_PPM | TIM_USE_LED, TIMER_INPUT_ENABLED, 0), // PPM -DMA1_ST7
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // PWM1 - DMA1_ST6
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // PWM2 - DMA2_ST2
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM3 - DMA1_ST1
DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM4 - DMA1_ST2
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 2), // PWM5 - DMA2_ST3
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM6 - DMA1_ST0
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, 0), // S5_OUT - DMA2_ST6
};

View file

@ -0,0 +1,135 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "CLR7"
#define USBD_PRODUCT_STRING "CL_RACING F7"
#define LED0 PB0
#define BEEPER PB4
#define BEEPER_INVERTED
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define ACC
#define USE_ACC_SPI_MPU6000
#define GYRO
#define USE_GYRO_SPI_MPU6000
// MPU6000 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO_MPU6000_ALIGN CW0_DEG
#define ACC_MPU6000_ALIGN CW0_DEG
#define OSD
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3
#define MAX7456_SPI_CS_PIN PA15
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SDCARD
#define SDCARD_DETECT_PIN PB7
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF1_5
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA2
#define SDCARD_DMA_CHANNEL DMA_CHANNEL_0
#define USE_VCP
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 5
#define USE_I2C
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define BOARD_HAS_CURRENT_SENSOR
#define CURRENT_METER_ADC_PIN PC1
#define VBAT_ADC_PIN PC2
#define RSSI_ADC_PIN PC3
#define CURRENT_METER_SCALE_DEFAULT 250 // 3/120A = 25mv/A
// LED strip configuration.
#define LED_STRIP
#define SPEKTRUM_BIND_PIN UART6_RX_PIN
#define BINDPLUG_PIN PB2
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_UART SERIAL_PORT_USART6
#define TELEMETRY_UART SERIAL_PORT_USART1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 9
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )

View file

@ -0,0 +1,6 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c\
drivers/max7456.c

View file

@ -1,130 +0,0 @@
/*
* 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 <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <platform.h>
#ifdef TARGET_CONFIG
#include "blackbox/blackbox.h"
#include "common/axis.h"
#include "common/maths.h"
#include "config/feature.h"
#include "io/ledstrip.h"
#include "io/serial.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_controls.h"
#include "flight/failsafe.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/servos.h"
#include "rx/rx.h"
#include "sensors/battery.h"
#include "sensors/gyro.h"
#include "telemetry/telemetry.h"
void targetApplyDefaultLedStripConfig(ledConfig_t *ledConfigs)
{
const ledConfig_t defaultLedStripConfig[] = {
DEFINE_LED( 0, 0, 6, LD(WEST), LF(COLOR), LO(WARNING), 0 ),
DEFINE_LED( 0, 1, 6, LD(WEST), LF(COLOR), LO(WARNING), 0 ),
DEFINE_LED( 0, 8, 6, LD(WEST), LF(COLOR), LO(WARNING), 0 ),
DEFINE_LED( 7, 15, 6, 0, LF(COLOR), 0, 0 ),
DEFINE_LED( 8, 15, 6, 0, LF(COLOR), 0, 0 ),
DEFINE_LED( 7, 14, 6, 0, LF(COLOR), 0, 0 ),
DEFINE_LED( 8, 14, 6, 0, LF(COLOR), 0, 0 ),
DEFINE_LED( 15, 8, 6, LD(EAST), LF(COLOR), LO(WARNING), 0 ),
DEFINE_LED( 15, 1, 6, LD(EAST), LF(COLOR), LO(WARNING), 0 ),
DEFINE_LED( 15, 0, 6, LD(EAST), LF(COLOR), LO(WARNING), 0 ),
};
memcpy(ledConfigs, &defaultLedStripConfig, MIN(LED_MAX_STRIP_LENGTH, sizeof(defaultLedStripConfig)));
}
// alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(void)
{
motorConfigMutable()->minthrottle = 1025;
motorConfigMutable()->maxthrottle = 1980;
motorConfigMutable()->mincommand = 1000;
servoConfigMutable()->dev.servoCenterPulse = 1500;
batteryConfigMutable()->vbatmaxcellvoltage = 45;
batteryConfigMutable()->vbatmincellvoltage = 30;
batteryConfigMutable()->vbatwarningcellvoltage = 35;
flight3DConfigMutable()->deadband3d_low = 1406;
flight3DConfigMutable()->deadband3d_high = 1514;
flight3DConfigMutable()->neutral3d = 1460;
flight3DConfigMutable()->deadband3d_throttle = 0;
failsafeConfigMutable()->failsafe_procedure = 1;
failsafeConfigMutable()->failsafe_throttle_low_delay = 10;
gyroConfigMutable()->gyro_sync_denom = 1;
pidConfigMutable()->pid_process_denom = 3;
blackboxConfigMutable()->rate_num = 1;
blackboxConfigMutable()->rate_denom = 1;
rcControlsConfigMutable()->deadband = 5;
rcControlsConfigMutable()->yaw_deadband = 5;
failsafeConfigMutable()->failsafe_delay = 10;
telemetryConfigMutable()->telemetry_inversion = 1;
pidProfilesMutable(0)->vbatPidCompensation = 1;
pidProfilesMutable(0)->P8[ROLL] = 46; // new PID with preliminary defaults test carefully
pidProfilesMutable(0)->I8[ROLL] = 48;
pidProfilesMutable(0)->D8[ROLL] = 23;
pidProfilesMutable(0)->P8[PITCH] = 89;
pidProfilesMutable(0)->I8[PITCH] = 59;
pidProfilesMutable(0)->D8[PITCH] = 25;
pidProfilesMutable(0)->P8[YAW] = 129;
pidProfilesMutable(0)->I8[YAW] = 50;
pidProfilesMutable(0)->D8[YAW] = 20;
controlRateProfilesMutable(0)->rates[FD_ROLL] = 86;
controlRateProfilesMutable(0)->rates[FD_PITCH] = 86;
controlRateProfilesMutable(0)->rates[FD_YAW] = 80;
targetApplyDefaultLedStripConfig(ledStripConfigMutable()->ledConfigs);
}
void targetValidateConfiguration()
{
serialConfigMutable()->portConfigs[0].functionMask = FUNCTION_MSP;
if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
featureClear(FEATURE_RX_PARALLEL_PWM);
featureClear(FEATURE_RX_MSP);
featureSet(FEATURE_RX_PPM);
}
}
#endif

View file

@ -20,8 +20,6 @@
#define TARGET_BOARD_IDENTIFIER "CLBR"
#define BST_DEVICE_NAME "COLIBRI RACE"
#define BST_DEVICE_NAME_LENGTH 12
#define TARGET_CONFIG
#define TARGET_VALIDATECONFIG
#define TARGET_BUS_INIT
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT

View file

View file

@ -17,7 +17,13 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "FYF3"
#ifdef FURYF3OSD
#define TARGET_BOARD_IDENTIFIER "FY3O"
// #define USBD_PRODUCT_STRING "FuryF3OSD"
#else
#define TARGET_BOARD_IDENTIFIER "FYF3"
// #define USBD_PRODUCT_STRING "FuryF3"
#endif
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define CONFIG_PREFER_ACC_ON
@ -63,10 +69,6 @@
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW90_DEG
#define BARO
#define USE_BARO_MS5611
#define USE_BARO_BMP280
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
@ -76,37 +78,58 @@
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
//#define USE_FLASHFS
//#define USE_FLASH_M25P16
//#define M25P16_CS_PIN PB12
//#define M25P16_SPI_INSTANCE SPI2
#ifdef FURYF3OSD
#define OSD
// include the max7456 driver
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI1
#define MAX7456_SPI_CS_PIN PC13
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_CS_PIN PB12
#define M25P16_SPI_INSTANCE SPI2
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_FEATURES (FEATURE_OSD)
#define BOARD_HAS_CURRENT_SENSOR
#else
#define SDCARD_DETECT_INVERTED
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_PIN PB2
#define SDCARD_DETECT_EXTI_LINE EXTI_Line2
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PB2
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define BARO
#define USE_BARO_MS5611
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
#endif
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4)
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define USE_VCP
#define USE_UART1
@ -117,6 +140,13 @@
#define SERIAL_PORT_COUNT 6
#define SOFTSERIAL1_RX_PIN PB0
#define SOFTSERIAL1_TX_PIN PB1
#define SONAR
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
@ -129,15 +159,6 @@
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define SOFTSERIAL1_RX_PIN PB0
#define SOFTSERIAL1_TX_PIN PB1
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define BOARD_HAS_VOLTAGE_DIVIDER
#define USE_ADC
#define ADC_INSTANCE ADC1
@ -145,10 +166,6 @@
#define RSSI_ADC_PIN PA1
#define CURRENT_METER_ADC_PIN PA2
#define SONAR
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define SPEKTRUM_BIND_PIN UART3_RX_PIN

View file

@ -1,12 +1,21 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD ONBOARDFLASH
ifeq ($(TARGET), FURYF3OSD)
FEATURES += VCP ONBOARDFLASH
else
FEATURES += VCP SDCARD
endif
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/barometer/barometer_ms5611.c \
drivers/barometer/barometer_bmp280.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_icm20689.c
ifeq ($(TARGET), FURYF3OSD)
TARGET_SRC += \
drivers/max7456.c
else
TARGET_SRC += \
drivers/barometer/barometer_ms5611.c
endif

View file

View file

@ -25,22 +25,15 @@
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
/*
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM_IN
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
*/
// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 }, // LED Strip
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1 ), // S1_OUT - DMA1_ST6_CH3
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S2_OUT - DMA1_ST7_CH5
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S3_OUT - DMA1_ST2_CH5
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S4_OUT - DMA1_ST1_CH3
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1 ), // S1_OUT - DMA1_ST6_CH3
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S2_OUT - DMA1_ST7_CH5
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_INVERTED, 0 ), // S3_OUT - DMA2_ST2_CH0
// DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S3_OUT - DMA1_ST2_CH5
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S4_OUT - DMA1_ST1_CH3
DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0 ), // LED_STRIP - DMA1_ST2_CH6
DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0 ), // LED_STRIP - DMA1_ST2_CH6
};

View file

@ -17,9 +17,13 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "FYF4"
#define USBD_PRODUCT_STRING "FuryF4"
#ifdef FURYF4OSD
#define TARGET_BOARD_IDENTIFIER "FY4O"
#define USBD_PRODUCT_STRING "FuryF4OSD"
#else
#define TARGET_BOARD_IDENTIFIER "FYF4"
#define USBD_PRODUCT_STRING "FuryF4"
#endif
#define LED0 PB5
#define LED1 PB4
@ -67,45 +71,50 @@
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define BARO
#define USE_BARO_MS5611
#define MS5611_I2C_INSTANCE I2CDEV_1
#ifdef FURYF4OSD
#define OSD
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN PB12
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_FEATURES FEATURE_OSD
#else
#define USE_SDCARD
#define BARO
#define USE_BARO_MS5611
#define MS5611_I2C_INSTANCE I2CDEV_1
#define SDCARD_DETECT_INVERTED
#define USE_SDCARD
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12
#define SDCARD_DETECT_INVERTED
/*
#define SDCARD_DETECT_PIN PD2
#define SDCARD_DETECT_EXTI_LINE EXTI_Line2
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOD
#define SDCARD_DETECT_EXTI_IRQn EXTI2_IRQn
#define SDCARD_DETECT_PIN PD2
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PB12
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PB3
*/
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
//#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
//#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
//#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
//#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
//#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
//#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
//#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
//#define SDCARD_DMA_CHANNEL DMA_Channel_0
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
#endif
#define USE_FLASHFS
#define USE_FLASH_M25P16
@ -119,7 +128,7 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
//#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11
@ -167,16 +176,13 @@
#define CURRENT_METER_ADC_PIN PC3
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_UART SERIAL_PORT_USART1
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_ESC_SENSOR
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff

View file

@ -1,10 +1,20 @@
F405_TARGETS += $(TARGET)
FEATURES += SDCARD VCP ONBOARDFLASH
ifeq ($(TARGET), FURYF4OSD)
FEATURES += VCP ONBOARDFLASH
else
FEATURES += VCP ONBOARDFLASH SDCARD
endif
TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_icm20689.c \
drivers/barometer/barometer_ms5611.c
drivers/accgyro/accgyro_spi_icm20689.c
ifeq ($(TARGET), FURYF4OSD)
TARGET_SRC += \
drivers/max7456.c
else
TARGET_SRC += \
drivers/barometer/barometer_ms5611.c
endif

View file

@ -21,8 +21,6 @@
#define USBD_PRODUCT_STRING "FuryF7"
#define USE_ESC_SENSOR
#define LED0 PB5
#define LED1 PB4

View file

@ -120,7 +120,6 @@
#define USE_ADC
#define VBAT_ADC_PIN PC3
//#define USE_ESC_SENSOR
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL

View file

@ -0,0 +1,42 @@
/*
* 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 <stdint.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED, 0),
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0),
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0),
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0),
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0),
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1),
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0),
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0),
DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0),
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0),
};

View file

@ -0,0 +1,159 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "NU72"
#define USBD_PRODUCT_STRING "NucleoF722"
//#define USE_ESC_TELEMETRY
#define LED0 PB7 // blue
#define LED1 PB14 // red
#define BEEPER PA0
#define BEEPER_INVERTED
#define ACC
#define USE_FAKE_ACC
#define USE_ACC_MPU6050
#define ACC_MPU6050_ALIGN CW270_DEG
#define GYRO
#define USE_FAKE_GYRO
#define USE_GYRO_MPU6050
#define GYRO_MPU6050_ALIGN CW270_DEG
// MPU6050 interrupts
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_INT_EXTI PB15
#define USE_EXTI
#define MAG
#define USE_FAKE_MAG
#define USE_MAG_HMC5883
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define BARO
#define USE_FAKE_BARO
#define USE_BARO_MS5611
#define USABLE_TIMER_CHANNEL_COUNT 11
#define USE_VCP
#define VBUS_SENSING_PIN PA9
//#define USE_UART1
//#define UART1_RX_PIN PA10
//#define UART1_TX_PIN PA9
#define USE_UART2
#define UART2_RX_PIN PD6
#define UART2_TX_PIN PD5
#define USE_UART3
#define UART3_RX_PIN PD9
#define UART3_TX_PIN PD8
#define USE_UART4
#define UART4_RX_PIN PC11
#define UART4_TX_PIN PC10
//#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PC12
//#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
//#define USE_UART7
#define UART7_RX_PIN PE7
#define UART7_TX_PIN PE8
//#define USE_UART8
#define UART8_RX_PIN PE0
#define UART8_TX_PIN PE1
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define SERIAL_PORT_COUNT 6 //VCP, USART2, USART3, UART4,SOFTSERIAL x 2
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_4
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI4_NSS_PIN PE11
#define SPI4_SCK_PIN PE12
#define SPI4_MISO_PIN PE13
#define SPI4_MOSI_PIN PE14
//#define USE_SDCARD
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PF14
#define SDCARD_DETECT_EXTI_LINE EXTI_Line14
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOF
#define SDCARD_DETECT_EXTI_IRQn EXTI9_15_IRQn
#define SDCARD_SPI_INSTANCE SPI4
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
#define SDCARD_DMA_CHANNEL_TX DMA2_Stream1
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF1_5
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA2
#define SDCARD_DMA_CHANNEL DMA_CHANNEL_4
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1)
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define USE_ADC
#define VBAT_ADC_PIN PA3
#define CURRENT_METER_ADC_PIN PC0
#define RSSI_ADC_GPIO_PIN PC3
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#undef USE_UNCOMMON_MIXERS
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0xffff
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11))

View file

@ -0,0 +1,12 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += SDCARD VCP
TARGET_SRC = \
drivers/accgyro/accgyro_fake.c \
drivers/accgyro/accgyro_mpu6050.c \
drivers/barometer/barometer_fake.c \
drivers/barometer/barometer_ms5611.c \
drivers/compass/compass_fake.c \
drivers/compass/compass_hmc5883l.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c

View file

@ -45,6 +45,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 1), // S3_OUT D1_ST6
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S4_OUT D1_ST1
#if defined(CL_RACINGF4)
DEF_TIM(TIM3, CH1, PB4, TIM_USE_BEEPER, TIMER_OUTPUT_ENABLED, 0 ), // BEEPER PWM
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), // S5_OUT
#elif defined(OMNIBUSF4SD)
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S5_OUT

View file

@ -41,6 +41,7 @@
//#define LED1 PB4 // Remove this at the next major release
#define BEEPER PB4
#define BEEPER_INVERTED
#define BEEPER_PWM_HZ 3800 // Beeper PWM frequency in Hz
#ifdef OMNIBUSF4SD
#define INVERTER_PIN_UART6 PC8 // Omnibus F4 V3 and later
@ -191,16 +192,16 @@
//#define RSSI_ADC_PIN PA0
#endif
#define USE_ESC_SENSOR
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define AVOID_UART1_FOR_PWM_PPM
#if defined(CL_RACINGF4)
#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD )
#define SPEKTRUM_BIND_PIN UART6_RX_PIN
#else
#define DEFAULT_FEATURES (FEATURE_OSD)
#define AVOID_UART1_FOR_PWM_PPM
#define SPEKTRUM_BIND_PIN UART1_RX_PIN
#endif
#define SPEKTRUM_BIND_PIN UART1_RX_PIN
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
@ -209,13 +210,13 @@
#define TARGET_IO_PORTD BIT(2)
#ifdef CL_RACINGF4
#define USABLE_TIMER_CHANNEL_COUNT 6
#define USED_TIMERS ( TIM_N(4) | TIM_N(8) )
#define USABLE_TIMER_CHANNEL_COUNT 7
#define USED_TIMERS ( TIM_N(3) | TIM_N(4) | TIM_N(4) | TIM_N(8) )
#else
#ifdef OMNIBUSF4SD
#define USABLE_TIMER_CHANNEL_COUNT 13
#else
#define USABLE_TIMER_CHANNEL_COUNT 12
#endif
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
#endif

View file

@ -37,12 +37,12 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0), // S4_OUT D1_ST1
#ifdef REVOLT
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED for REVOLT D1_ST0
#else
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 1, 0), // S5_OUT / LED for REVO D1_ST4
#ifdef AIRBOTF4
#elif defined(AIRBOTF4) || defined(AIRBOTF4SD)
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 1, 0), // S5_OUT
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 1, 0), // S6_OUT
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED D1_ST0, n/a on older AIRBOTF4
#else
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 1, 0), // S5_OUT / LED
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 1, 0), // S6_OUT D1_ST2
#endif /* AIRBOTF4 */
#endif /* REVOLT */
#endif
};

View file

@ -48,8 +48,6 @@
#endif
#define USE_ESC_SENSOR
#define LED0 PB5
#if defined(PODIUMF4)
#define LED1 PB4

View file

@ -180,6 +180,8 @@
#define USE_OSD_OVER_MSP_DISPLAYPORT
#define USE_SLOW_MSP_DISPLAYPORT_RATE_WHEN_UNARMED
#define USE_MSP_CURRENT_METER
#define USE_ESC_SENSOR
#define REMAP_TIM17_DMA

View file

@ -163,6 +163,8 @@
#define OSD
#define USE_OSD_OVER_MSP_DISPLAYPORT
#define USE_MSP_CURRENT_METER
#undef USE_DASHBOARD
#define TRANSPONDER

View file

@ -20,33 +20,17 @@
#include <platform.h>
#include "common/axis.h"
#include "drivers/sensor.h"
#include "drivers/compass/compass.h"
#include "drivers/serial.h"
#include "fc/rc_controls.h"
#include "flight/failsafe.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "rx/rx.h"
#ifdef TARGET_CONFIG
#include "io/serial.h"
#include "telemetry/telemetry.h"
#include "rx/rx.h"
#include "sensors/sensors.h"
#include "sensors/compass.h"
#include "sensors/barometer.h"
#include "config/feature.h"
#include "telemetry/telemetry.h"
#include "fc/config.h"
#ifdef TARGET_CONFIG
void targetConfiguration(void)
{
barometerConfigMutable()->baro_hardware = BARO_DEFAULT;

View file

@ -162,6 +162,7 @@
#define OSD
#define USE_OSD_OVER_MSP_DISPLAYPORT
#define USE_MSP_CURRENT_METER
#define LED_STRIP
#define TRANSPONDER

View file

@ -45,12 +45,14 @@
#ifdef STM32F4
#define USE_DSHOT
#define USE_ESC_SENSOR
#define I2C3_OVERCLOCK true
#define TELEMETRY_IBUS
#endif
#ifdef STM32F7
#define USE_DSHOT
#define USE_ESC_SENSOR
#define I2C3_OVERCLOCK true
#define I2C4_OVERCLOCK true
#define TELEMETRY_IBUS

View file

@ -46,6 +46,12 @@ battery_unittest_SRC := \
$(USER_DIR)/common/maths.c
blackbox_encoding_unittest_SRC := \
$(USER_DIR)/blackbox/blackbox_encoding.c \
$(USER_DIR)/common/encoding.c \
$(USER_DIR)/common/printf.c \
$(USER_DIR)/common/typeconversion.c
cms_unittest_SRC := \
$(USER_DIR)/cms/cms.c \
$(USER_DIR)/common/typeconversion.c \
@ -117,7 +123,8 @@ rx_ranges_unittest_SRC := \
rx_rx_unittest_SRC := \
$(USER_DIR)/rx/rx.c \
$(USER_DIR)/common/maths.c
$(USER_DIR)/common/maths.c \
$(USER_DIR)/config/feature.c
sensor_gyro_unittest_SRC := \
@ -232,11 +239,11 @@ include ../../make/build_verbosity.mk
# House-keeping build targets.
## test : Build and run the Unit Tests (default goal)
test: $(TESTS:%=test-%)
test: $(TESTS:%=test_%)
## junittest : Build and run the Unit Tests, producing Junit XML result files."
junittest: EXEC_OPTS = "--gtest_output=xml:$<_results.xml"
junittest: $(TESTS:%=test-%)
junittest: $(TESTS:%=test_%)
@ -258,7 +265,7 @@ help what usage: Makefile
@$(foreach test, $(TESTS), echo " $(OBJECT_DIR)/$(test)/$(test)";)
@echo ""
@echo "Any of the Unit Test programs can be used as goals to build and run:"
@$(foreach test, $(TESTS), echo " test-$(test)";)
@$(foreach test, $(TESTS), echo " test_$(test)";)
## clean : Cleanup the UnitTest binaries.
clean :
@ -350,7 +357,7 @@ $(OBJECT_DIR)/$1/$1 : $$($$1_OBJS) \
$(V1) $(CXX) $(CXX_FLAGS) $(PG_FLAGS) $$^ -o $$@
test-$1: $(OBJECT_DIR)/$1/$1
test_$1: $(OBJECT_DIR)/$1/$1
$(V1) $$< $$(EXEC_OPTS) "$(STDOUT)" && echo "running $$@: PASS"
endef

View file

@ -0,0 +1,259 @@
/*
*
* 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 <stdint.h>
#include <string.h>
extern "C" {
#include "platform.h"
#include "blackbox/blackbox.h"
#include "blackbox/blackbox_encoding.h"
#include "common/utils.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/serial.h"
#include "io/serial.h"
}
#include "unittest_macros.h"
#include "gtest/gtest.h"
static serialPort_t *blackboxPort;
static int serialWritePos = 0;
static int serialReadPos = 0;
static int serialReadEnd = 0;
#define SERIAL_BUFFER_SIZE 256
static uint8_t serialReadBuffer[SERIAL_BUFFER_SIZE];
static uint8_t serialWriteBuffer[SERIAL_BUFFER_SIZE];
serialPort_t serialTestInstance;
void serialWrite(serialPort_t *instance, uint8_t ch)
{
EXPECT_EQ(instance, &serialTestInstance);
EXPECT_LT(serialWritePos, sizeof(serialWriteBuffer));
serialWriteBuffer[serialWritePos++] = ch;
}
void serialWriteBuf(serialPort_t *instance, const uint8_t *data, int count)
{
while(count--)
serialWrite(instance, *data++);
}
void serialBeginWrite(serialPort_t *instance)
{
EXPECT_EQ(instance, &serialTestInstance);
}
void serialEndWrite(serialPort_t *instance)
{
EXPECT_EQ(instance, &serialTestInstance);
}
uint32_t serialRxBytesWaiting(const serialPort_t *instance)
{
EXPECT_EQ(instance, &serialTestInstance);
EXPECT_GE(serialReadEnd, serialReadPos);
int ret = serialReadEnd - serialReadPos;
if (ret >= 0) return ret;
return 0;
}
uint8_t serialRead(serialPort_t *instance)
{
EXPECT_EQ(instance, &serialTestInstance);
EXPECT_LT(serialReadPos, serialReadEnd);
const uint8_t ch = serialReadBuffer[serialReadPos++];
return ch;
}
uint32_t serialTxBytesFree(const serialPort_t *instance)
{
UNUSED(instance);
return SERIAL_BUFFER_SIZE - serialWritePos;
}
bool isSerialTransmitBufferEmpty(const serialPort_t *instance)
{
EXPECT_EQ(instance, &serialTestInstance);
return true;
}
void serialTestResetBuffers()
{
blackboxPort = &serialTestInstance;
memset(&serialReadBuffer, 0, sizeof(serialReadBuffer));
serialReadPos = 0;
serialReadEnd = 0;
memset(&serialWriteBuffer, 0, sizeof(serialWriteBuffer));
serialWritePos = 0;
}
TEST(BlackboxEncodingTest, TestWriteUnsignedVB)
{
serialTestResetBuffers();
blackboxWriteUnsignedVB(0);
EXPECT_EQ(0, serialWriteBuffer[0]);
blackboxWriteUnsignedVB(128);
EXPECT_EQ(0x80, serialWriteBuffer[1]);
EXPECT_EQ(1, serialWriteBuffer[2]);
}
TEST(BlackboxTest, TestWriteTag2_3SVariable_BITS2)
{
serialTestResetBuffers();
uint8_t *buf = &serialWriteBuffer[0];
int selector;
int32_t v[3];
// 2 bits per field ss11 2233,
v[0] = 0;
v[1] = 0;
v[2] = 0;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(0, selector);
EXPECT_EQ(0, buf[0]);
EXPECT_EQ(0, buf[1]); // ensure next byte has not been written
++buf;
v[0] = 1;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(0x10, buf[0]); // 00010000
EXPECT_EQ(0, buf[1]); // ensure next byte has not been written
++buf;
v[0] = 1;
v[1] = 1;
v[2] = 1;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(0, selector);
EXPECT_EQ(0x15, buf[0]); // 00010101
EXPECT_EQ(0, buf[1]); // ensure next byte has not been written
++buf;
v[0] = -1;
v[1] = -1;
v[2] = -1;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(0, selector);
EXPECT_EQ(0x3F, buf[0]); // 00111111
EXPECT_EQ(0, buf[1]); // ensure next byte has not been written
++buf;
v[0] = -2;
v[1] = -2;
v[2] = -2;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(0, selector);
EXPECT_EQ(0x2A, buf[0]); // 00101010
EXPECT_EQ(0, buf[1]); // ensure next byte has not been written
++buf;
}
TEST(BlackboxTest, TestWriteTag2_3SVariable_BITS554)
{
serialTestResetBuffers();
uint8_t *buf = &serialWriteBuffer[0];
int selector;
int32_t v[3];
// 554 bits per field ss11 1112 2222 3333
// 5 bits per field [-16, 15], 4 bits per field [-8, 7]
v[0] = 15;
v[1] = 15;
v[2] = 7;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(1, selector);
EXPECT_EQ(0x5E, buf[0]); // 0101 1110
EXPECT_EQ(0xF7, buf[1]); // 1111 0111
EXPECT_EQ(0, buf[2]); // ensure next byte has not been written
buf += 2;
v[0] = -16;
v[1] = -16;
v[2] = -8;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(1, selector);
EXPECT_EQ(0x61, buf[0]); // 0110 0001
EXPECT_EQ(0x08, buf[1]); // 0000 1000
EXPECT_EQ(0, buf[2]); // ensure next byte has not been written
buf += 2;
v[0] = 7;
v[1] = 8;
v[2] = 5;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(1, selector);
EXPECT_EQ(0x4E, buf[0]); // 0100 1110
EXPECT_EQ(0x85, buf[1]); // 1000 0101
EXPECT_EQ(0, buf[2]); // ensure next byte has not been written
buf += 2;
}
TEST(BlackboxTest, TestWriteTag2_3SVariable_BITS887)
{
serialTestResetBuffers();
uint8_t *buf = &serialWriteBuffer[0];
int selector;
int32_t v[3];
// 877 bits per field ss11 1111 1122 2222 2333 3333
// 8 bits per field [-128, 127], 7 bits per field [-64, 63]
v[0] = 127;
v[1] = 63;
v[2] = 63;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(2, selector);
EXPECT_EQ(0x9F, buf[0]); // 1001 1111
EXPECT_EQ(0xDF, buf[1]); // 1101 1111
EXPECT_EQ(0xBF, buf[2]); // 1011 1111
EXPECT_EQ(0, buf[3]); // ensure next byte has not been written
buf += 3;
v[0] = -128;
v[1] = -64;
v[2] = -64;
selector = blackboxWriteTag2_3SVariable(v);
EXPECT_EQ(2, selector);
EXPECT_EQ(0xA0, buf[0]); // 1010 0000
EXPECT_EQ(0x20, buf[1]); // 0010 0000
EXPECT_EQ(0x40, buf[2]); // 0100 0000
EXPECT_EQ(0, buf[3]); // ensure next byte has not been written
buf += 3;
}
// STUBS
extern "C" {
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
int32_t blackboxHeaderBudget;
void mspSerialAllocatePorts(void) {}
void blackboxWrite(uint8_t value) {serialWrite(blackboxPort, value);}
int blackboxPrint(const char *s)
{
const uint8_t *pos = (uint8_t*)s;
while (*pos) {
serialWrite(blackboxPort, *pos);
pos++;
}
const int length = pos - (uint8_t*)s;
return length;
}
}

View file

@ -24,16 +24,26 @@ extern "C" {
#include "platform.h"
#include "rx/rx.h"
#include "io/rc_controls.h"
#include "fc/rc_controls.h"
#include "common/maths.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
uint32_t rcModeActivationMask;
void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationConditions);
void rxResetFlightChannelStatus(void);
bool rxHaveValidFlightChannels(void);
bool isPulseValid(uint16_t pulseDuration);
void rxUpdateFlightChannelStatus(uint8_t channel, uint16_t pulseDuration);
PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0);
PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
.enabledFeatures = 0
);
PG_REGISTER_ARRAY(modeActivationCondition_t, MAX_MODE_ACTIVATION_CONDITION_COUNT, modeActivationConditions, PG_MODE_ACTIVATION_PROFILE, 0);
}
#include "unittest_macros.h"
@ -69,10 +79,10 @@ TEST(RxTest, TestValidFlightChannels)
modeActivationConditions[0].range.endStep = CHANNEL_VALUE_TO_STEP(1600);
// when
rxInit(&rxConfig, modeActivationConditions);
rxInit();
// then (ARM channel should be positioned just 1 step above active range to init to OFF)
EXPECT_EQ(1625, rcData[modeActivationConditions[0].auxChannelIndex + NON_AUX_CHANNEL_COUNT]);
//!! EXPECT_EQ(1625, rcData[modeActivationConditions[0].auxChannelIndex + NON_AUX_CHANNEL_COUNT]);
// given
rxResetFlightChannelStatus();
@ -84,7 +94,7 @@ TEST(RxTest, TestValidFlightChannels)
}
// then
EXPECT_TRUE(rxHaveValidFlightChannels());
//!! EXPECT_TRUE(rxHaveValidFlightChannels());
}
TEST(RxTest, TestInvalidFlightChannels)
@ -111,10 +121,10 @@ TEST(RxTest, TestInvalidFlightChannels)
memset(&channelPulses, 1500, sizeof(channelPulses));
// and
rxInit(&rxConfig, modeActivationConditions);
rxInit();
// then (ARM channel should be positioned just 1 step below active range to init to OFF)
EXPECT_EQ(1375, rcData[modeActivationConditions[0].auxChannelIndex + NON_AUX_CHANNEL_COUNT]);
//!! EXPECT_EQ(1375, rcData[modeActivationConditions[0].auxChannelIndex + NON_AUX_CHANNEL_COUNT]);
// and
for (uint8_t stickChannelIndex = 0; stickChannelIndex < STICK_CHANNEL_COUNT; stickChannelIndex++) {
@ -168,11 +178,6 @@ extern "C" {
uint32_t micros(void) { return 0; }
uint32_t millis(void) { return 0; }
bool feature(uint32_t mask) {
UNUSED(mask);
return false;
}
bool isPPMDataBeingReceived(void) {
return testData.isPPMDataBeingReceived;
}
@ -182,10 +187,16 @@ extern "C" {
}
void resetPPMDataReceivedState(void) {}
bool rxMspFrameComplete(void) { return false; }
void rxMspInit(rxConfig_t *, rxRuntimeConfig_t *, rcReadRawDataPtr *) {}
void rxPwmInit(rxRuntimeConfig_t *, rcReadRawDataPtr *) {}
void crsfRxInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void ibusInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void jetiExBusInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void sbusInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void spektrumInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void sumdInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void sumhInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void xBusInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void rxMspInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void rxPwmInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
}

Some files were not shown because too many files have changed in this diff Show more