mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 04:15:44 +03:00
Merge https://github.com/cleanflight/cleanflight into virtualcurrent
This commit is contained in:
commit
a37c6ee9ee
29 changed files with 562 additions and 222 deletions
|
@ -1,6 +1,6 @@
|
|||
# Configuration
|
||||
|
||||
Cleanflight is configured primarilty using the Cleanflight Configurator GUI.
|
||||
Cleanflight is configured primarily using the Cleanflight Configurator GUI.
|
||||
|
||||
Both the command line interface and GUI are accessible by connecting to a serial port on the target,
|
||||
be it a USB virtual serial port, physical hardware UART port or a SoftSerial port.
|
||||
|
@ -15,7 +15,7 @@ __Due to ongoing development, the fact that the GUI cannot yet backup all your s
|
|||
|
||||
## GUI
|
||||
|
||||

|
||||

|
||||
|
||||
The GUI tool is the preferred way of configuration. The GUI tool also includes a terminal which
|
||||
can be used to interact with the CLI.
|
||||
|
|
Before Width: | Height: | Size: 70 KiB After Width: | Height: | Size: 70 KiB |
|
@ -16,6 +16,8 @@ This project could really do with some functional tests which test the behaviour
|
|||
|
||||
All pull requests to add/improve the testability of the code or testing methods are highly sought!
|
||||
|
||||
Note: Tests are written in C++ and linked with with firmware's C code.
|
||||
|
||||
##General principals
|
||||
|
||||
1. Name everything well.
|
||||
|
@ -48,22 +50,3 @@ You can run them on the command line to execute the tests and to see the test re
|
|||
You can also step-debug the tests in eclipse and you can use the GoogleTest test runner to make building and re-running the tests simple.
|
||||
|
||||
The tests are currently always compiled with debugging information enabled, there may be additional warnings, if you see any warnings please attempt to fix them and submit pull requests with the fixes.
|
||||
|
||||
|
||||
##TODO
|
||||
|
||||
* Test OpenLRSNG's RSSI PWM on AUX5-8.
|
||||
* Add support for UART3/4 on STM32F3.
|
||||
* Cleanup validateAndFixConfig and pwm_mapping.c to use some kind of feature/timer/io pin mapping to remove #ifdef
|
||||
* Split RX config into RC config and RX config.
|
||||
* Enabling/disabling features should not take effect until reboot since. Main loop executes and uses new flags as they are set in the cli but
|
||||
appropriate init methods will not have been called which results in undefined behaviour and could damage connected devices - this is a legacy
|
||||
problem from baseflight.
|
||||
* Solve all the naze rev4/5 HSE_VALUE == 8000000/1200000 checking, the checks should only apply to the naze32 target. See system_stm32f10x.c/SetSysClock().
|
||||
|
||||
##Known Issues
|
||||
|
||||
* Softserial RX on STM32F3 does not work. TX is fine.
|
||||
* Dynamic throttle PID does not work with new pid controller.
|
||||
* Autotune does not work yet with with new pid controller.
|
||||
|
||||
|
|
|
@ -74,7 +74,6 @@
|
|||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
#include "blackbox_fielddefs.h"
|
||||
#include "blackbox.h"
|
||||
|
||||
#define BLACKBOX_BAUDRATE 115200
|
||||
|
@ -83,6 +82,9 @@
|
|||
|
||||
#define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0]))
|
||||
|
||||
#define STATIC_ASSERT(condition, name ) \
|
||||
typedef char assert_failed_ ## name [(condition) ? 1 : -1 ]
|
||||
|
||||
// Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
|
||||
#define STR_HELPER(x) #x
|
||||
#define STR(x) STR_HELPER(x)
|
||||
|
@ -235,7 +237,8 @@ typedef enum BlackboxState {
|
|||
BLACKBOX_STATE_SEND_GPS_G_HEADERS,
|
||||
BLACKBOX_STATE_SEND_SYSINFO,
|
||||
BLACKBOX_STATE_PRERUN,
|
||||
BLACKBOX_STATE_RUNNING
|
||||
BLACKBOX_STATE_RUNNING,
|
||||
BLACKBOX_STATE_SHUTTING_DOWN
|
||||
} BlackboxState;
|
||||
|
||||
typedef struct gpsState_t {
|
||||
|
@ -267,8 +270,11 @@ static struct {
|
|||
} u;
|
||||
} xmitState;
|
||||
|
||||
// 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 uint32_t blackboxIteration;
|
||||
static uint32_t blackboxPFrameIndex, blackboxIFrameIndex;
|
||||
|
||||
|
@ -671,6 +677,9 @@ static void blackboxSetState(BlackboxState newState)
|
|||
blackboxPFrameIndex = 0;
|
||||
blackboxIFrameIndex = 0;
|
||||
break;
|
||||
case BLACKBOX_STATE_SHUTTING_DOWN:
|
||||
xmitState.u.startTime = millis();
|
||||
break;
|
||||
default:
|
||||
;
|
||||
}
|
||||
|
@ -894,6 +903,14 @@ static void releaseBlackboxPort(void)
|
|||
serialSetBaudRate(blackboxPort, previousBaudRate);
|
||||
|
||||
endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX);
|
||||
|
||||
/*
|
||||
* Normally this would be handled by mw.c, but since we take an unknown amount
|
||||
* of time to shut down asynchronously, we're the only ones that know when to call it.
|
||||
*/
|
||||
if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
|
||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||
}
|
||||
}
|
||||
|
||||
void startBlackbox(void)
|
||||
|
@ -931,10 +948,18 @@ void startBlackbox(void)
|
|||
|
||||
void finishBlackbox(void)
|
||||
{
|
||||
if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED) {
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
if (blackboxState == BLACKBOX_STATE_RUNNING) {
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
|
||||
} else if (blackboxState != BLACKBOX_STATE_DISABLED && blackboxState != BLACKBOX_STATE_STOPPED
|
||||
&& blackboxState != BLACKBOX_STATE_SHUTTING_DOWN) {
|
||||
/*
|
||||
* We're shutting down in the middle of transmitting headers, so we can't log a "log completed" event.
|
||||
* Just give the port back and stop immediately.
|
||||
*/
|
||||
releaseBlackboxPort();
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1141,7 +1166,6 @@ static bool blackboxWriteSysinfo()
|
|||
blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H P interval:%d/%d\n");
|
||||
|
||||
break;
|
||||
case 5:
|
||||
blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
||||
|
@ -1163,7 +1187,7 @@ static bool blackboxWriteSysinfo()
|
|||
blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H gyro.scale:0x%x\n") + 6;
|
||||
break;
|
||||
break;
|
||||
case 9:
|
||||
blackboxPrintf("H acc_1G:%u\n", acc_1G);
|
||||
|
||||
|
@ -1193,10 +1217,49 @@ static bool blackboxWriteSysinfo()
|
|||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Write the given event to the log immediately
|
||||
*/
|
||||
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
|
||||
{
|
||||
if (blackboxState != BLACKBOX_STATE_RUNNING)
|
||||
return;
|
||||
|
||||
//Shared header for event frames
|
||||
blackboxWrite('E');
|
||||
blackboxWrite(event);
|
||||
|
||||
//Now serialize the data for this specific frame type
|
||||
switch (event) {
|
||||
case FLIGHT_LOG_EVENT_SYNC_BEEP:
|
||||
writeUnsignedVB(data->syncBeep.time);
|
||||
break;
|
||||
case FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_START:
|
||||
blackboxWrite(data->autotuneCycleStart.phase);
|
||||
blackboxWrite(data->autotuneCycleStart.cycle);
|
||||
blackboxWrite(data->autotuneCycleStart.p);
|
||||
blackboxWrite(data->autotuneCycleStart.i);
|
||||
blackboxWrite(data->autotuneCycleStart.d);
|
||||
break;
|
||||
case FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_RESULT:
|
||||
blackboxWrite(data->autotuneCycleResult.overshot);
|
||||
blackboxWrite(data->autotuneCycleStart.p);
|
||||
blackboxWrite(data->autotuneCycleStart.i);
|
||||
blackboxWrite(data->autotuneCycleStart.d);
|
||||
break;
|
||||
case FLIGHT_LOG_EVENT_LOG_END:
|
||||
blackboxPrint("End of log");
|
||||
blackboxWrite(0);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Beep the buzzer and write the current time to the log as a synchronization point
|
||||
static void blackboxPlaySyncBeep()
|
||||
{
|
||||
uint32_t now = micros();
|
||||
flightLogEvent_syncBeep_t eventData;
|
||||
|
||||
eventData.time = micros();
|
||||
|
||||
/*
|
||||
* The regular beep routines aren't going to work for us, because they queue up the beep to be executed later.
|
||||
|
@ -1207,10 +1270,7 @@ static void blackboxPlaySyncBeep()
|
|||
// Have the regular beeper code turn off the beep for us eventually, since that's not timing-sensitive
|
||||
queueConfirmationBeep(1);
|
||||
|
||||
blackboxWrite('E');
|
||||
blackboxWrite(FLIGHT_LOG_EVENT_SYNC_BEEP);
|
||||
|
||||
writeUnsignedVB(now);
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_SYNC_BEEP, (flightLogEventData_t *) &eventData);
|
||||
}
|
||||
|
||||
void handleBlackbox(void)
|
||||
|
@ -1269,9 +1329,9 @@ void handleBlackbox(void)
|
|||
blackboxSetState(BLACKBOX_STATE_PRERUN);
|
||||
break;
|
||||
case BLACKBOX_STATE_PRERUN:
|
||||
blackboxPlaySyncBeep();
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
||||
|
||||
blackboxPlaySyncBeep();
|
||||
break;
|
||||
case BLACKBOX_STATE_RUNNING:
|
||||
// On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
|
||||
|
@ -1317,6 +1377,20 @@ void handleBlackbox(void)
|
|||
blackboxIFrameIndex++;
|
||||
}
|
||||
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.
|
||||
*
|
||||
* Don't wait longer than it could possibly take if something funky happens.
|
||||
*/
|
||||
if (millis() > xmitState.u.startTime + 200 || isSerialTransmitBufferEmpty(blackboxPort)) {
|
||||
releaseBlackboxPort();
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -17,9 +17,12 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "common/axis.h"
|
||||
#include <stdint.h>
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "blackbox/blackbox_fielddefs.h"
|
||||
|
||||
typedef struct blackboxValues_t {
|
||||
uint32_t time;
|
||||
|
||||
|
@ -41,6 +44,8 @@ typedef struct blackboxValues_t {
|
|||
#endif
|
||||
} blackboxValues_t;
|
||||
|
||||
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data);
|
||||
|
||||
void initBlackbox(void);
|
||||
void handleBlackbox(void);
|
||||
void startBlackbox(void);
|
||||
|
|
|
@ -93,5 +93,40 @@ typedef enum FlightLogFieldSign {
|
|||
|
||||
typedef enum FlightLogEvent {
|
||||
FLIGHT_LOG_EVENT_SYNC_BEEP = 0,
|
||||
FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_START = 10,
|
||||
FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_RESULT = 11,
|
||||
FLIGHT_LOG_EVENT_LOG_END = 255
|
||||
} FlightLogEvent;
|
||||
|
||||
typedef struct flightLogEvent_syncBeep_t {
|
||||
uint32_t time;
|
||||
} flightLogEvent_syncBeep_t;
|
||||
|
||||
typedef struct flightLogEvent_autotuneCycleStart_t {
|
||||
uint8_t phase;
|
||||
uint8_t cycle;
|
||||
uint8_t p;
|
||||
uint8_t i;
|
||||
uint8_t d;
|
||||
} flightLogEvent_autotuneCycleStart_t;
|
||||
|
||||
typedef struct flightLogEvent_autotuneCycleResult_t {
|
||||
uint8_t overshot;
|
||||
uint8_t p;
|
||||
uint8_t i;
|
||||
uint8_t d;
|
||||
} flightLogEvent_autotuneCycleResult_t;
|
||||
|
||||
typedef union flightLogEventData_t
|
||||
{
|
||||
flightLogEvent_syncBeep_t syncBeep;
|
||||
flightLogEvent_autotuneCycleStart_t autotuneCycleStart;
|
||||
flightLogEvent_autotuneCycleResult_t autotuneCycleResult;
|
||||
|
||||
} flightLogEventData_t;
|
||||
|
||||
typedef struct flightLogEvent_t
|
||||
{
|
||||
FlightLogEvent event;
|
||||
flightLogEventData_t data;
|
||||
} flightLogEvent_t;
|
||||
|
|
|
@ -69,7 +69,7 @@ static void putchw(void *putp, putcf putf, int n, char z, char *bf)
|
|||
putf(putp, ch);
|
||||
}
|
||||
|
||||
void tfp_format(void *putp, putcf putf, char *fmt, va_list va)
|
||||
void tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
|
||||
{
|
||||
char bf[12];
|
||||
|
||||
|
@ -154,7 +154,7 @@ void init_printf(void *putp, void (*putf) (void *, char))
|
|||
stdout_putp = putp;
|
||||
}
|
||||
|
||||
void tfp_printf(char *fmt, ...)
|
||||
void tfp_printf(const char *fmt, ...)
|
||||
{
|
||||
va_list va;
|
||||
va_start(va, fmt);
|
||||
|
@ -168,7 +168,7 @@ static void putcp(void *p, char c)
|
|||
*(*((char **) p))++ = c;
|
||||
}
|
||||
|
||||
void tfp_sprintf(char *s, char *fmt, ...)
|
||||
void tfp_sprintf(char *s, const char *fmt, ...)
|
||||
{
|
||||
va_list va;
|
||||
|
||||
|
|
|
@ -107,10 +107,10 @@ regs Kusti, 23.10.2004
|
|||
|
||||
void init_printf(void *putp, void (*putf) (void *, char));
|
||||
|
||||
void tfp_printf(char *fmt, ...);
|
||||
void tfp_sprintf(char *s, char *fmt, ...);
|
||||
void tfp_printf(const char *fmt, ...);
|
||||
void tfp_sprintf(char *s, const char *fmt, ...);
|
||||
|
||||
void tfp_format(void *putp, void (*putf) (void *, char), char *fmt, va_list va);
|
||||
void tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list va);
|
||||
|
||||
#define printf tfp_printf
|
||||
#define sprintf tfp_sprintf
|
||||
|
|
|
@ -90,9 +90,9 @@ int a2d(char ch)
|
|||
return -1;
|
||||
}
|
||||
|
||||
char a2i(char ch, char **src, int base, int *nump)
|
||||
char a2i(char ch, const char **src, int base, int *nump)
|
||||
{
|
||||
char *p = *src;
|
||||
const char *p = *src;
|
||||
int num = 0;
|
||||
int digit;
|
||||
while ((digit = a2d(ch)) >= 0) {
|
||||
|
|
|
@ -20,7 +20,7 @@ void uli2a(unsigned long int num, unsigned int base, int uc, char *bf);
|
|||
void li2a(long num, char *bf);
|
||||
void ui2a(unsigned int num, unsigned int base, int uc, char *bf);
|
||||
void i2a(int num, char *bf);
|
||||
char a2i(char ch, char **src, int base, int *nump);
|
||||
char a2i(char ch, const char **src, int base, int *nump);
|
||||
char *ftoa(float x, char *floatString);
|
||||
float fastA2F(const char *p);
|
||||
|
||||
|
|
|
@ -159,6 +159,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
pidProfile->D_f[YAW] = 0.05f;
|
||||
pidProfile->A_level = 5.0f;
|
||||
pidProfile->H_level = 3.0f;
|
||||
pidProfile->H_sensitivity = 75;
|
||||
}
|
||||
|
||||
#ifdef GPS
|
||||
|
|
|
@ -31,6 +31,9 @@
|
|||
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
/*
|
||||
|
@ -97,6 +100,12 @@ typedef enum {
|
|||
PHASE_SAVE_OR_RESTORE_PIDS,
|
||||
} autotunePhase_e;
|
||||
|
||||
typedef enum {
|
||||
CYCLE_TUNE_I = 0,
|
||||
CYCLE_TUNE_PD,
|
||||
CYCLE_TUNE_PD2
|
||||
} autotuneCycle_e;
|
||||
|
||||
static const pidIndex_e angleIndexToPidIndexMap[] = {
|
||||
PIDROLL,
|
||||
PIDPITCH
|
||||
|
@ -112,7 +121,7 @@ static pidProfile_t pidBackup;
|
|||
static uint8_t pidController;
|
||||
static uint8_t pidIndex;
|
||||
static bool rising;
|
||||
static uint8_t cycleCount; // TODO can we replace this with an enum to improve readability.
|
||||
static autotuneCycle_e cycle;
|
||||
static uint32_t timeoutAt;
|
||||
static angle_index_t autoTuneAngleIndex;
|
||||
static autotunePhase_e phase = PHASE_IDLE;
|
||||
|
@ -140,10 +149,33 @@ bool isAutotuneIdle(void)
|
|||
return phase == PHASE_IDLE;
|
||||
}
|
||||
|
||||
#ifdef BLACKBOX
|
||||
|
||||
static void autotuneLogCycleStart()
|
||||
{
|
||||
if (feature(FEATURE_BLACKBOX)) {
|
||||
flightLogEvent_autotuneCycleStart_t eventData;
|
||||
|
||||
eventData.phase = phase;
|
||||
eventData.cycle = cycle;
|
||||
eventData.p = pid.p * MULTIWII_P_MULTIPLIER;
|
||||
eventData.i = pid.i * MULTIWII_I_MULTIPLIER;
|
||||
eventData.d = pid.d;
|
||||
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_START, (flightLogEventData_t*)&eventData);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
static void startNewCycle(void)
|
||||
{
|
||||
rising = !rising;
|
||||
secondPeakAngle = firstPeakAngle = 0;
|
||||
|
||||
#ifdef BLACKBOX
|
||||
autotuneLogCycleStart();
|
||||
#endif
|
||||
}
|
||||
|
||||
static void updatePidIndex(void)
|
||||
|
@ -155,8 +187,7 @@ static void updateTargetAngle(void)
|
|||
{
|
||||
if (rising) {
|
||||
targetAngle = AUTOTUNE_TARGET_ANGLE;
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
targetAngle = -AUTOTUNE_TARGET_ANGLE;
|
||||
}
|
||||
|
||||
|
@ -210,30 +241,48 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin
|
|||
debug[3] = DEGREES_TO_DECIDEGREES(secondPeakAngle);
|
||||
|
||||
} else if (secondPeakAngle > 0) {
|
||||
if (cycleCount == 0) {
|
||||
// when checking the I value, we would like to overshoot the target position by half of the max oscillation.
|
||||
if (currentAngle - targetAngle < AUTOTUNE_MAX_OSCILLATION_ANGLE / 2) {
|
||||
pid.i *= AUTOTUNE_INCREASE_MULTIPLIER;
|
||||
} else {
|
||||
pid.i *= AUTOTUNE_DECREASE_MULTIPLIER;
|
||||
if (pid.i < AUTOTUNE_MINIMUM_I_VALUE) {
|
||||
pid.i = AUTOTUNE_MINIMUM_I_VALUE;
|
||||
switch (cycle) {
|
||||
case CYCLE_TUNE_I:
|
||||
// when checking the I value, we would like to overshoot the target position by half of the max oscillation.
|
||||
if (currentAngle - targetAngle < AUTOTUNE_MAX_OSCILLATION_ANGLE / 2) {
|
||||
pid.i *= AUTOTUNE_INCREASE_MULTIPLIER;
|
||||
} else {
|
||||
pid.i *= AUTOTUNE_DECREASE_MULTIPLIER;
|
||||
if (pid.i < AUTOTUNE_MINIMUM_I_VALUE) {
|
||||
pid.i = AUTOTUNE_MINIMUM_I_VALUE;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// go back to checking P and D
|
||||
cycleCount = 1;
|
||||
pidProfile->I8[pidIndex] = 0;
|
||||
startNewCycle();
|
||||
} else {
|
||||
// we are checking P and D values
|
||||
// set up to look for the 2nd peak
|
||||
firstPeakAngle = currentAngle;
|
||||
timeoutAt = millis() + AUTOTUNE_SETTLING_DELAY_MS;
|
||||
#ifdef BLACKBOX
|
||||
if (feature(FEATURE_BLACKBOX)) {
|
||||
flightLogEvent_autotuneCycleResult_t eventData;
|
||||
|
||||
eventData.overshot = currentAngle - targetAngle < AUTOTUNE_MAX_OSCILLATION_ANGLE / 2 ? 0 : 1;
|
||||
eventData.p = pidProfile->P8[pidIndex];
|
||||
eventData.i = pidProfile->I8[pidIndex];
|
||||
eventData.d = pidProfile->D8[pidIndex];
|
||||
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_RESULT, (flightLogEventData_t*)&eventData);
|
||||
}
|
||||
#endif
|
||||
|
||||
// go back to checking P and D
|
||||
cycle = CYCLE_TUNE_PD;
|
||||
pidProfile->I8[pidIndex] = 0;
|
||||
startNewCycle();
|
||||
break;
|
||||
|
||||
case CYCLE_TUNE_PD:
|
||||
case CYCLE_TUNE_PD2:
|
||||
// we are checking P and D values
|
||||
// set up to look for the 2nd peak
|
||||
firstPeakAngle = currentAngle;
|
||||
timeoutAt = millis() + AUTOTUNE_SETTLING_DELAY_MS;
|
||||
break;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
// we saw the first peak. looking for the second
|
||||
// We saw the first peak while tuning PD, looking for the second
|
||||
|
||||
if (currentAngle < firstPeakAngle) {
|
||||
firstPeakAngle = currentAngle;
|
||||
|
@ -266,8 +315,8 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin
|
|||
pid.d *= AUTOTUNE_INCREASE_MULTIPLIER;
|
||||
}
|
||||
#else
|
||||
pid.p *= AUTOTUNE_DECREASE_MULTIPLIER;
|
||||
pid.d *= AUTOTUNE_INCREASE_MULTIPLIER;
|
||||
pid.p *= AUTOTUNE_DECREASE_MULTIPLIER;
|
||||
pid.d *= AUTOTUNE_INCREASE_MULTIPLIER;
|
||||
#endif
|
||||
} else {
|
||||
// undershot
|
||||
|
@ -286,15 +335,30 @@ float autotune(angle_index_t angleIndex, const rollAndPitchInclination_t *inclin
|
|||
pidProfile->P8[pidIndex] = pid.p * MULTIWII_P_MULTIPLIER;
|
||||
pidProfile->D8[pidIndex] = pid.d;
|
||||
|
||||
// switch to the other direction and start a new cycle
|
||||
startNewCycle();
|
||||
#ifdef BLACKBOX
|
||||
if (feature(FEATURE_BLACKBOX)) {
|
||||
flightLogEvent_autotuneCycleResult_t eventData;
|
||||
|
||||
if (++cycleCount == 3) {
|
||||
// switch to testing I value
|
||||
cycleCount = 0;
|
||||
eventData.overshot = secondPeakAngle > targetAngleAtPeak ? 1 : 0;
|
||||
eventData.p = pidProfile->P8[pidIndex];
|
||||
eventData.i = pidProfile->I8[pidIndex];
|
||||
eventData.d = pidProfile->D8[pidIndex];
|
||||
|
||||
pidProfile->I8[pidIndex] = pid.i * MULTIWII_I_MULTIPLIER;
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_AUTOTUNE_CYCLE_RESULT, (flightLogEventData_t*)&eventData);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (cycle == CYCLE_TUNE_PD2) {
|
||||
// switch to testing I value
|
||||
cycle = CYCLE_TUNE_I;
|
||||
|
||||
pidProfile->I8[pidIndex] = pid.i * MULTIWII_I_MULTIPLIER;
|
||||
} else {
|
||||
cycle = CYCLE_TUNE_PD2;
|
||||
}
|
||||
|
||||
// switch to the other direction for the new cycle
|
||||
startNewCycle();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -344,7 +408,7 @@ void autotuneBeginNextPhase(pidProfile_t *pidProfileToTune, uint8_t pidControlle
|
|||
}
|
||||
|
||||
rising = true;
|
||||
cycleCount = 1;
|
||||
cycle = CYCLE_TUNE_PD;
|
||||
secondPeakAngle = firstPeakAngle = 0;
|
||||
|
||||
pidProfile = pidProfileToTune;
|
||||
|
@ -360,6 +424,10 @@ void autotuneBeginNextPhase(pidProfile_t *pidProfileToTune, uint8_t pidControlle
|
|||
|
||||
pidProfile->D8[pidIndex] = pid.d;
|
||||
pidProfile->I8[pidIndex] = 0;
|
||||
|
||||
#ifdef BLACKBOX
|
||||
autotuneLogCycleStart();
|
||||
#endif
|
||||
}
|
||||
|
||||
void autotuneEndPhase(void)
|
||||
|
|
|
@ -57,10 +57,10 @@ static float errorGyroIf[3] = { 0.0f, 0.0f, 0.0f };
|
|||
static int32_t errorAngleI[2] = { 0, 0 };
|
||||
|
||||
static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim);
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig);
|
||||
|
||||
typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim); // pid controller function prototype
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype
|
||||
|
||||
pidControllerFuncPtr pid_controller = pidMultiWii; // which pid controller are we using, defaultMultiWii
|
||||
|
||||
|
@ -97,18 +97,42 @@ bool shouldAutotune(void)
|
|||
#endif
|
||||
|
||||
static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim)
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
float RateError, errorAngle, AngleRate, gyroRate;
|
||||
float ITerm,PTerm,DTerm;
|
||||
int32_t stickPosAil, stickPosEle, mostDeflectedPos;
|
||||
static float lastGyroRate[3];
|
||||
static float delta1[3], delta2[3];
|
||||
float delta, deltaSum;
|
||||
float dT;
|
||||
int axis;
|
||||
float horizonLevelStrength = 1;
|
||||
|
||||
dT = (float)cycleTime * 0.000001f;
|
||||
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
|
||||
// Figure out the raw stick positions
|
||||
stickPosAil = getRcStickDeflection(FD_ROLL, rxConfig->midrc);
|
||||
stickPosEle = getRcStickDeflection(FD_PITCH, rxConfig->midrc);
|
||||
|
||||
if(abs(stickPosAil) > abs(stickPosEle)){
|
||||
mostDeflectedPos = abs(stickPosAil);
|
||||
}
|
||||
else {
|
||||
mostDeflectedPos = abs(stickPosEle);
|
||||
}
|
||||
|
||||
// Progressively turn off the horizon self level strength as the stick is banged over
|
||||
horizonLevelStrength = (float)(500 - mostDeflectedPos) / 500; // 1 at centre stick, 0 = max stick deflection
|
||||
if(pidProfile->H_sensitivity == 0){
|
||||
horizonLevelStrength = 0;
|
||||
} else {
|
||||
horizonLevelStrength = constrainf(((horizonLevelStrength - 1) * (100 / pidProfile->H_sensitivity)) + 1, 0, 1);
|
||||
}
|
||||
}
|
||||
|
||||
// ----------PID controller----------
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
// -----Get the desired angle rate depending on flight mode
|
||||
|
@ -139,7 +163,7 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
AngleRate = (float)((controlRateConfig->rollPitchRate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max yaw rate
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
// mix up angle error to desired AngleRate to add a little auto-level feel
|
||||
AngleRate += errorAngle * pidProfile->H_level;
|
||||
AngleRate += errorAngle * pidProfile->H_level * horizonLevelStrength;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -181,8 +205,10 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
}
|
||||
|
||||
static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim)
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
|
||||
int axis, prop;
|
||||
int32_t error, errorAngle;
|
||||
int32_t PTerm, ITerm, PTermACC = 0, ITermACC = 0, PTermGYRO = 0, ITermGYRO = 0, DTerm;
|
||||
|
@ -264,8 +290,10 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
#define GYRO_I_MAX 256
|
||||
|
||||
static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||
rollAndPitchTrims_t *angleTrim)
|
||||
rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
|
||||
int32_t errorAngle;
|
||||
int axis;
|
||||
int32_t delta, deltaSum;
|
||||
|
|
|
@ -42,6 +42,7 @@ typedef struct pidProfile_s {
|
|||
float D_f[3];
|
||||
float A_level;
|
||||
float H_level;
|
||||
uint8_t H_sensitivity;
|
||||
} pidProfile_t;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -378,24 +378,28 @@ void showBatteryPage(void)
|
|||
void showSensorsPage(void)
|
||||
{
|
||||
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
|
||||
static const char *format = "%c = %5d %5d %5d";
|
||||
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(" X Y Z");
|
||||
|
||||
if (sensors(SENSOR_ACC)) {
|
||||
tfp_sprintf(lineBuffer, "A = %5d %5d %5d", accSmooth[X], accSmooth[Y], accSmooth[Z]);
|
||||
tfp_sprintf(lineBuffer, format, 'A', accSmooth[X], accSmooth[Y], accSmooth[Z]);
|
||||
padLineBuffer();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(lineBuffer);
|
||||
}
|
||||
|
||||
if (sensors(SENSOR_GYRO)) {
|
||||
tfp_sprintf(lineBuffer, "G = %5d %5d %5d", gyroADC[X], gyroADC[Y], gyroADC[Z]);
|
||||
tfp_sprintf(lineBuffer, format, 'G', gyroADC[X], gyroADC[Y], gyroADC[Z]);
|
||||
padLineBuffer();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(lineBuffer);
|
||||
}
|
||||
|
||||
#ifdef MAG
|
||||
if (sensors(SENSOR_MAG)) {
|
||||
tfp_sprintf(lineBuffer, "M = %5d %5d %5d", magADC[X], magADC[Y], magADC[Z]);
|
||||
tfp_sprintf(lineBuffer, format, 'M', magADC[X], magADC[Y], magADC[Z]);
|
||||
padLineBuffer();
|
||||
i2c_OLED_set_line(rowIndex++);
|
||||
i2c_OLED_send_string(lineBuffer);
|
||||
|
|
|
@ -50,14 +50,26 @@
|
|||
static bool ledStripInitialised = false;
|
||||
static failsafe_t* failsafe;
|
||||
|
||||
//#define USE_LED_ANIMATION
|
||||
|
||||
// timers
|
||||
#ifdef USE_LED_ANIMATION
|
||||
static uint32_t nextAnimationUpdateAt = 0;
|
||||
#endif
|
||||
|
||||
static uint32_t nextIndicatorFlashAt = 0;
|
||||
static uint32_t nextWarningFlashAt = 0;
|
||||
|
||||
#define LED_STRIP_20HZ ((1000 * 1000) / 20)
|
||||
#define LED_STRIP_10HZ ((1000 * 1000) / 10)
|
||||
#define LED_STRIP_5HZ ((1000 * 1000) / 5)
|
||||
|
||||
#if MAX_LED_STRIP_LENGTH > WS2811_LED_STRIP_LENGTH
|
||||
#error "Led strip length must match driver"
|
||||
#endif
|
||||
|
||||
hsvColor_t *colors;
|
||||
|
||||
//#define USE_LED_ANIMATION
|
||||
|
||||
// H S V
|
||||
#define LED_BLACK { 0, 0, 0}
|
||||
#define LED_WHITE { 0, 255, 255}
|
||||
|
@ -185,6 +197,7 @@ static const modeColorIndexes_t angleModeColors = {
|
|||
COLOR_ORANGE
|
||||
};
|
||||
|
||||
#ifdef MAG
|
||||
static const modeColorIndexes_t magModeColors = {
|
||||
COLOR_MINT_GREEN,
|
||||
COLOR_DARK_VIOLET,
|
||||
|
@ -193,6 +206,7 @@ static const modeColorIndexes_t magModeColors = {
|
|||
COLOR_BLUE,
|
||||
COLOR_ORANGE
|
||||
};
|
||||
#endif
|
||||
|
||||
static const modeColorIndexes_t baroModeColors = {
|
||||
COLOR_LIGHT_BLUE,
|
||||
|
@ -436,15 +450,6 @@ void generateLedConfig(uint8_t ledIndex, char *ledConfigBuffer, size_t bufferSiz
|
|||
sprintf(ledConfigBuffer, "%u,%u:%s:%s", GET_LED_X(ledConfig), GET_LED_Y(ledConfig), directions, functions);
|
||||
}
|
||||
|
||||
// timers
|
||||
uint32_t nextAnimationUpdateAt = 0;
|
||||
uint32_t nextIndicatorFlashAt = 0;
|
||||
uint32_t nextWarningFlashAt = 0;
|
||||
|
||||
#define LED_STRIP_20HZ ((1000 * 1000) / 20)
|
||||
#define LED_STRIP_10HZ ((1000 * 1000) / 10)
|
||||
#define LED_STRIP_5HZ ((1000 * 1000) / 5)
|
||||
|
||||
void applyDirectionalModeColor(const uint8_t ledIndex, const ledConfig_t *ledConfig, const modeColorIndexes_t *modeColors)
|
||||
{
|
||||
// apply up/down colors regardless of quadrant.
|
||||
|
@ -686,6 +691,7 @@ void applyLedThrottleLayer()
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_LED_ANIMATION
|
||||
static uint8_t frameCounter = 0;
|
||||
|
||||
static uint8_t previousRow;
|
||||
|
@ -703,7 +709,6 @@ static void updateLedAnimationState(void)
|
|||
frameCounter = (frameCounter + 1) % animationFrames;
|
||||
}
|
||||
|
||||
#ifdef USE_LED_ANIMATION
|
||||
static void applyLedAnimationLayer(void)
|
||||
{
|
||||
const ledConfig_t *ledConfig;
|
||||
|
@ -738,11 +743,18 @@ void updateLedStrip(void)
|
|||
|
||||
uint32_t now = micros();
|
||||
|
||||
bool animationUpdateNow = (int32_t)(now - nextAnimationUpdateAt) >= 0L;
|
||||
bool indicatorFlashNow = (int32_t)(now - nextIndicatorFlashAt) >= 0L;
|
||||
bool warningFlashNow = (int32_t)(now - nextWarningFlashAt) >= 0L;
|
||||
|
||||
if (!(warningFlashNow || indicatorFlashNow || animationUpdateNow)) {
|
||||
bool indicatorFlashNow = indicatorFlashNow = (int32_t)(now - nextIndicatorFlashAt) >= 0L;
|
||||
bool warningFlashNow =warningFlashNow = (int32_t)(now - nextWarningFlashAt) >= 0L;
|
||||
#ifdef USE_LED_ANIMATION
|
||||
bool animationUpdateNow = animationUpdateNow = (int32_t)(now - nextAnimationUpdateAt) >= 0L;
|
||||
#endif
|
||||
if (!(
|
||||
indicatorFlashNow ||
|
||||
warningFlashNow
|
||||
#ifdef USE_LED_ANIMATION
|
||||
|| animationUpdateNow
|
||||
#endif
|
||||
)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -777,20 +789,21 @@ void updateLedStrip(void)
|
|||
|
||||
applyLedIndicatorLayer(indicatorFlashState);
|
||||
|
||||
#ifdef USE_LED_ANIMATION
|
||||
if (animationUpdateNow) {
|
||||
nextAnimationUpdateAt = now + LED_STRIP_20HZ;
|
||||
updateLedAnimationState();
|
||||
}
|
||||
|
||||
#ifdef USE_LED_ANIMATION
|
||||
applyLedAnimationLayer();
|
||||
#endif
|
||||
|
||||
ws2811UpdateStrip();
|
||||
}
|
||||
|
||||
bool parseColor(uint8_t index, char *colorConfig)
|
||||
bool parseColor(uint8_t index, const char *colorConfig)
|
||||
{
|
||||
char *remainingCharacters = colorConfig;
|
||||
const char *remainingCharacters = colorConfig;
|
||||
|
||||
hsvColor_t *color = &colors[index];
|
||||
|
||||
|
|
|
@ -69,7 +69,7 @@ void updateLedStrip(void);
|
|||
void applyDefaultLedStripConfig(ledConfig_t *ledConfig);
|
||||
void generateLedConfig(uint8_t ledIndex, char *ledConfigBuffer, size_t bufferSize);
|
||||
|
||||
bool parseColor(uint8_t index, char *colorConfig);
|
||||
bool parseColor(uint8_t index, const char *colorConfig);
|
||||
void applyDefaultColors(hsvColor_t *colors, uint8_t colorCount);
|
||||
|
||||
void ledStripEnable(void);
|
||||
|
|
|
@ -517,6 +517,10 @@ void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges)
|
|||
}
|
||||
}
|
||||
|
||||
int32_t getRcStickDeflection(int32_t axis, uint16_t midrc) {
|
||||
return min(abs(rcData[axis] - midrc), 500);
|
||||
}
|
||||
|
||||
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse)
|
||||
{
|
||||
uint8_t index;
|
||||
|
|
|
@ -214,3 +214,5 @@ void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
|
|||
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig);
|
||||
|
||||
bool isUsingSticksForArming(void);
|
||||
|
||||
int32_t getRcStickDeflection(int32_t axis, uint16_t midrc);
|
||||
|
|
|
@ -393,6 +393,7 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
{ "level_horizon", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_level, 0, 10 },
|
||||
{ "level_angle", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.A_level, 0, 10 },
|
||||
{ "sensitivity_horizon", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_sensitivity, 0, 250 },
|
||||
|
||||
{ "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], 0, 200 },
|
||||
{ "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], 0, 200 },
|
||||
|
|
|
@ -846,7 +846,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
if (i == PIDLEVEL) {
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.A_level * 10.0f), 0, 250));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.H_level * 10.0f), 0, 250));
|
||||
serialize8(0);
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.H_sensitivity), 0, 250));
|
||||
} else {
|
||||
serialize8(currentProfile->pidProfile.P8[i]);
|
||||
serialize8(currentProfile->pidProfile.I8[i]);
|
||||
|
@ -1171,7 +1171,7 @@ static bool processInCommand(void)
|
|||
if (i == PIDLEVEL) {
|
||||
currentProfile->pidProfile.A_level = (float)read8() / 10.0f;
|
||||
currentProfile->pidProfile.H_level = (float)read8() / 10.0f;
|
||||
read8();
|
||||
currentProfile->pidProfile.H_sensitivity = read8();
|
||||
} else {
|
||||
currentProfile->pidProfile.P8[i] = read8();
|
||||
currentProfile->pidProfile.I8[i] = read8();
|
||||
|
@ -1442,28 +1442,26 @@ static bool processInCommand(void)
|
|||
|
||||
case MSP_SET_LED_STRIP_CONFIG:
|
||||
{
|
||||
uint8_t ledCount = currentPort->dataSize / 6;
|
||||
if (ledCount != MAX_LED_STRIP_LENGTH) {
|
||||
i = read8();
|
||||
if (i >= MAX_LED_STRIP_LENGTH || currentPort->dataSize != 7) {
|
||||
headSerialError(0);
|
||||
break;
|
||||
}
|
||||
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
|
||||
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
|
||||
uint16_t mask;
|
||||
// currently we're storing directions and functions in a uint16 (flags)
|
||||
// the msp uses 2 x uint16_t to cater for future expansion
|
||||
mask = read16();
|
||||
ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK;
|
||||
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
|
||||
uint16_t mask;
|
||||
// currently we're storing directions and functions in a uint16 (flags)
|
||||
// the msp uses 2 x uint16_t to cater for future expansion
|
||||
mask = read16();
|
||||
ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK;
|
||||
|
||||
mask = read16();
|
||||
ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
|
||||
mask = read16();
|
||||
ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
|
||||
|
||||
mask = read8();
|
||||
ledConfig->xy = CALCULATE_LED_X(mask);
|
||||
mask = read8();
|
||||
ledConfig->xy = CALCULATE_LED_X(mask);
|
||||
|
||||
mask = read8();
|
||||
ledConfig->xy |= CALCULATE_LED_Y(mask);
|
||||
}
|
||||
mask = read8();
|
||||
ledConfig->xy |= CALCULATE_LED_Y(mask);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
|
|
@ -97,7 +97,8 @@ static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the m
|
|||
extern uint8_t dynP8[3], dynI8[3], dynD8[3];
|
||||
extern failsafe_t *failsafe;
|
||||
|
||||
typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination, rollAndPitchTrims_t *accelerometerTrims);
|
||||
typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig); // pid controller function prototype
|
||||
|
||||
extern pidControllerFuncPtr pid_controller;
|
||||
|
||||
|
@ -311,9 +312,6 @@ void mwDisarm(void)
|
|||
#ifdef BLACKBOX
|
||||
if (feature(FEATURE_BLACKBOX)) {
|
||||
finishBlackbox();
|
||||
if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) {
|
||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -712,7 +710,8 @@ void loop(void)
|
|||
¤tProfile->pidProfile,
|
||||
currentControlRateProfile,
|
||||
masterConfig.max_angle_inclination,
|
||||
¤tProfile->accelerometerTrims
|
||||
¤tProfile->accelerometerTrims,
|
||||
&masterConfig.rxConfig
|
||||
);
|
||||
|
||||
mixTable();
|
||||
|
|
|
@ -121,7 +121,7 @@ static void sbusDataReceive(uint16_t c)
|
|||
|
||||
static uint8_t sbusFramePosition = 0;
|
||||
static uint32_t sbusTimeoutAt = 0;
|
||||
uint32_t now = millis();
|
||||
uint32_t now = micros();
|
||||
|
||||
if ((int32_t)(sbusTimeoutAt - now) < 0) {
|
||||
sbusFramePosition = 0;
|
||||
|
|
|
@ -23,13 +23,23 @@ USER_INCLUDE_DIR = $(USER_DIR)
|
|||
|
||||
OBJECT_DIR = ../../obj/test
|
||||
|
||||
# Flags passed to the preprocessor.
|
||||
# Set Google Test's header directory as a system directory, such that
|
||||
# the compiler doesn't generate warnings in Google Test headers.
|
||||
CPPFLAGS += -isystem $(GTEST_DIR)/inc
|
||||
COMMON_FLAGS = \
|
||||
-g \
|
||||
-Wall \
|
||||
-Wextra \
|
||||
-pthread \
|
||||
-ggdb3 \
|
||||
-O0 \
|
||||
-DUNIT_TEST \
|
||||
-isystem $(GTEST_DIR)/inc
|
||||
|
||||
# Flags passed to the C compiler.
|
||||
C_FLAGS = $(COMMON_FLAGS) \
|
||||
-std=gnu99
|
||||
|
||||
# Flags passed to the C++ compiler.
|
||||
CXXFLAGS += -g -Wall -Wextra -pthread -ggdb3 -O0 -DUNIT_TEST
|
||||
CXX_FLAGS = $(COMMON_FLAGS) \
|
||||
-std=gnu++98
|
||||
|
||||
# All tests produced by this Makefile. Remember to add new tests you
|
||||
# created to the list.
|
||||
|
@ -66,12 +76,12 @@ GTEST_SRCS_ = $(GTEST_DIR)/src/*.cc $(GTEST_DIR)/inc/gtest/*.h $(GTEST_HEADERS)
|
|||
# compiles fast and for ordinary users its source rarely changes.
|
||||
$(OBJECT_DIR)/gtest-all.o : $(GTEST_SRCS_)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) -I$(GTEST_DIR) $(CXXFLAGS) -c \
|
||||
$(CXX) $(CXX_FLAGS) -I$(GTEST_DIR) -c \
|
||||
$(GTEST_DIR)/src/gtest-all.cc -o $@
|
||||
|
||||
$(OBJECT_DIR)/gtest_main.o : $(GTEST_SRCS_)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) -I$(GTEST_DIR) $(CXXFLAGS) -c \
|
||||
$(CXX) $(CXX_FLAGS) -I$(GTEST_DIR) -c \
|
||||
$(GTEST_DIR)/src/gtest_main.cc -o $@
|
||||
|
||||
$(OBJECT_DIR)/gtest.a : $(OBJECT_DIR)/gtest-all.o
|
||||
|
@ -88,117 +98,208 @@ $(OBJECT_DIR)/gtest_main.a : $(OBJECT_DIR)/gtest-all.o $(OBJECT_DIR)/gtest_main.
|
|||
TEST_INCLUDE_DIRS := $(TEST_DIR) \
|
||||
$(USER_INCLUDE_DIR)
|
||||
|
||||
|
||||
TEST_CFLAGS = $(addprefix -I,$(TEST_INCLUDE_DIRS))
|
||||
|
||||
$(OBJECT_DIR)/common/maths.o : \
|
||||
$(USER_DIR)/common/maths.c \
|
||||
$(USER_DIR)/common/maths.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/maths.c -o $@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/sensors/battery.o : $(USER_DIR)/sensors/battery.c $(USER_DIR)/sensors/battery.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/battery.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/battery.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/battery_unittest.o : \
|
||||
$(TEST_DIR)/battery_unittest.cc \
|
||||
$(USER_DIR)/sensors/battery.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/battery_unittest.o : $(TEST_DIR)/battery_unittest.cc \
|
||||
$(USER_DIR)/sensors/battery.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/battery_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/battery_unittest.cc -o $@
|
||||
|
||||
battery_unittest : $(OBJECT_DIR)/sensors/battery.o $(OBJECT_DIR)/battery_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
battery_unittest : \
|
||||
$(OBJECT_DIR)/sensors/battery.o \
|
||||
$(OBJECT_DIR)/common/maths.o \
|
||||
$(OBJECT_DIR)/battery_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/flight/imu.o : \
|
||||
$(USER_DIR)/flight/imu.c \
|
||||
$(USER_DIR)/flight/imu.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/flight/imu.o : $(USER_DIR)/flight/imu.c $(USER_DIR)/flight/imu.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/imu.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/imu.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/flight_imu_unittest.o : \
|
||||
$(TEST_DIR)/flight_imu_unittest.cc \
|
||||
$(USER_DIR)/flight/imu.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/flight_imu_unittest.o : $(TEST_DIR)/flight_imu_unittest.cc \
|
||||
$(USER_DIR)/flight/imu.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_imu_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_imu_unittest.cc -o $@
|
||||
|
||||
flight_imu_unittest : $(OBJECT_DIR)/flight/imu.o $(OBJECT_DIR)/flight/altitudehold.o $(OBJECT_DIR)/flight_imu_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
flight_imu_unittest : \
|
||||
$(OBJECT_DIR)/flight/imu.o \
|
||||
$(OBJECT_DIR)/flight/altitudehold.o \
|
||||
$(OBJECT_DIR)/flight_imu_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
$(OBJECT_DIR)/flight/altitudehold.o : $(USER_DIR)/flight/altitudehold.c $(USER_DIR)/flight/altitudehold.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/flight/altitudehold.o : \
|
||||
$(USER_DIR)/flight/altitudehold.c \
|
||||
$(USER_DIR)/flight/altitudehold.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/altitudehold.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/altitudehold.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/altitude_hold_unittest.o : \
|
||||
$(TEST_DIR)/altitude_hold_unittest.cc \
|
||||
$(USER_DIR)/flight/altitudehold.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/altitude_hold_unittest.o : $(TEST_DIR)/altitude_hold_unittest.cc \
|
||||
$(USER_DIR)/flight/altitudehold.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/altitude_hold_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/altitude_hold_unittest.cc -o $@
|
||||
|
||||
altitude_hold_unittest : $(OBJECT_DIR)/flight/altitudehold.o $(OBJECT_DIR)/altitude_hold_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
altitude_hold_unittest : \
|
||||
$(OBJECT_DIR)/flight/altitudehold.o \
|
||||
$(OBJECT_DIR)/altitude_hold_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o : \
|
||||
$(USER_DIR)/flight/gps_conversion.c \
|
||||
$(USER_DIR)/flight/gps_conversion.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o : $(USER_DIR)/flight/gps_conversion.c $(USER_DIR)/flight/gps_conversion.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/gps_conversion.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/gps_conversion.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/gps_conversion_unittest.o : \
|
||||
$(TEST_DIR)/gps_conversion_unittest.cc \
|
||||
$(USER_DIR)/flight/gps_conversion.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/gps_conversion_unittest.o : $(TEST_DIR)/gps_conversion_unittest.cc \
|
||||
$(USER_DIR)/flight/gps_conversion.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@
|
||||
|
||||
gps_conversion_unittest : $(OBJECT_DIR)/flight/gps_conversion.o $(OBJECT_DIR)/gps_conversion_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
gps_conversion_unittest : \
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o \
|
||||
$(OBJECT_DIR)/gps_conversion_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
$(OBJECT_DIR)/telemetry/hott.o : $(USER_DIR)/telemetry/hott.c $(USER_DIR)/telemetry/hott.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/telemetry/hott.o : \
|
||||
$(USER_DIR)/telemetry/hott.c \
|
||||
$(USER_DIR)/telemetry/hott.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/telemetry/hott.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/telemetry/hott.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/telemetry_hott_unittest.o : \
|
||||
$(TEST_DIR)/telemetry_hott_unittest.cc \
|
||||
$(USER_DIR)/telemetry/hott.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/telemetry_hott_unittest.o : $(TEST_DIR)/telemetry_hott_unittest.cc \
|
||||
$(USER_DIR)/telemetry/hott.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/telemetry_hott_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/telemetry_hott_unittest.cc -o $@
|
||||
|
||||
telemetry_hott_unittest :$(OBJECT_DIR)/telemetry/hott.o $(OBJECT_DIR)/telemetry_hott_unittest.o $(OBJECT_DIR)/flight/gps_conversion.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
telemetry_hott_unittest : \
|
||||
$(OBJECT_DIR)/telemetry/hott.o \
|
||||
$(OBJECT_DIR)/telemetry_hott_unittest.o \
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
$(OBJECT_DIR)/io/rc_controls.o : $(USER_DIR)/io/rc_controls.c $(USER_DIR)/io/rc_controls.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/io/rc_controls.o : \
|
||||
$(USER_DIR)/io/rc_controls.c \
|
||||
$(USER_DIR)/io/rc_controls.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/rc_controls.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/rc_controls.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/rc_controls_unittest.o : \
|
||||
$(TEST_DIR)/rc_controls_unittest.cc \
|
||||
$(USER_DIR)/io/rc_controls.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/rc_controls_unittest.o : $(TEST_DIR)/rc_controls_unittest.cc \
|
||||
$(USER_DIR)/io/rc_controls.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rc_controls_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rc_controls_unittest.cc -o $@
|
||||
|
||||
rc_controls_unittest :$(OBJECT_DIR)/io/rc_controls.o $(OBJECT_DIR)/rc_controls_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
rc_controls_unittest : \
|
||||
$(OBJECT_DIR)/io/rc_controls.o \
|
||||
$(OBJECT_DIR)/rc_controls_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/io/ledstrip.o : $(USER_DIR)/io/ledstrip.c $(USER_DIR)/io/ledstrip.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/io/ledstrip.o : \
|
||||
$(USER_DIR)/io/ledstrip.c \
|
||||
$(USER_DIR)/io/ledstrip.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/ledstrip.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/ledstrip.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/ledstrip_unittest.o : \
|
||||
$(TEST_DIR)/ledstrip_unittest.cc \
|
||||
$(USER_DIR)/io/ledstrip.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/ledstrip_unittest.o : $(TEST_DIR)/ledstrip_unittest.cc \
|
||||
$(USER_DIR)/io/ledstrip.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ledstrip_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ledstrip_unittest.cc -o $@
|
||||
|
||||
ledstrip_unittest :$(OBJECT_DIR)/io/ledstrip.o $(OBJECT_DIR)/ledstrip_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
ledstrip_unittest : \
|
||||
$(OBJECT_DIR)/io/ledstrip.o \
|
||||
$(OBJECT_DIR)/ledstrip_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
$(OBJECT_DIR)/drivers/light_ws2811strip.o : $(USER_DIR)/drivers/light_ws2811strip.c $(USER_DIR)/drivers/light_ws2811strip.h $(GTEST_HEADERS)
|
||||
$(OBJECT_DIR)/drivers/light_ws2811strip.o : \
|
||||
$(USER_DIR)/drivers/light_ws2811strip.c \
|
||||
$(USER_DIR)/drivers/light_ws2811strip.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
@mkdir -p $(dir $@)
|
||||
$(CC) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/light_ws2811strip.c -o $@
|
||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/light_ws2811strip.c -o $@
|
||||
|
||||
$(OBJECT_DIR)/ws2811_unittest.o : \
|
||||
$(TEST_DIR)/ws2811_unittest.cc \
|
||||
$(USER_DIR)/drivers/light_ws2811strip.h \
|
||||
$(GTEST_HEADERS)
|
||||
|
||||
$(OBJECT_DIR)/ws2811_unittest.o : $(TEST_DIR)/ws2811_unittest.cc \
|
||||
$(USER_DIR)/drivers/light_ws2811strip.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ws2811_unittest.cc -o $@
|
||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ws2811_unittest.cc -o $@
|
||||
|
||||
ws2811_unittest :$(OBJECT_DIR)/drivers/light_ws2811strip.o $(OBJECT_DIR)/ws2811_unittest.o $(OBJECT_DIR)/gtest_main.a
|
||||
$(CXX) $(CPPFLAGS) $(CXXFLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
ws2811_unittest : \
|
||||
$(OBJECT_DIR)/drivers/light_ws2811strip.o \
|
||||
$(OBJECT_DIR)/ws2811_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
|
|
@ -27,7 +27,9 @@ extern "C" {
|
|||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
|
|
@ -18,7 +18,10 @@
|
|||
#include <stdint.h>
|
||||
|
||||
#include <limits.h>
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
extern "C" {
|
||||
#include "flight/gps_conversion.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
@ -33,7 +36,7 @@ TEST(GpsConversionTest, GPSCoordToDegrees_BadString)
|
|||
}
|
||||
|
||||
typedef struct gpsConversionExpectation_s {
|
||||
char *coord;
|
||||
const char *coord;
|
||||
uint32_t degrees;
|
||||
} gpsConversionExpectation_t;
|
||||
|
||||
|
|
|
@ -19,37 +19,40 @@
|
|||
|
||||
#include <limits.h>
|
||||
|
||||
#include "build_config.h"
|
||||
extern "C" {
|
||||
#include "build_config.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "io/ledstrip.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
extern ledConfig_t *ledConfigs;
|
||||
extern uint8_t highestYValueForNorth;
|
||||
extern uint8_t lowestYValueForSouth;
|
||||
extern uint8_t highestXValueForWest;
|
||||
extern uint8_t lowestXValueForEast;
|
||||
extern uint8_t ledGridWidth;
|
||||
extern uint8_t ledGridHeight;
|
||||
extern "C" {
|
||||
extern ledConfig_t *ledConfigs;
|
||||
extern uint8_t highestYValueForNorth;
|
||||
extern uint8_t lowestYValueForSouth;
|
||||
extern uint8_t highestXValueForWest;
|
||||
extern uint8_t lowestXValueForEast;
|
||||
extern uint8_t ledGridWidth;
|
||||
extern uint8_t ledGridHeight;
|
||||
|
||||
void determineLedStripDimensions(void);
|
||||
void determineOrientationLimits(void);
|
||||
void determineLedStripDimensions(void);
|
||||
void determineOrientationLimits(void);
|
||||
|
||||
ledConfig_t systemLedConfigs[MAX_LED_STRIP_LENGTH];
|
||||
ledConfig_t systemLedConfigs[MAX_LED_STRIP_LENGTH];
|
||||
}
|
||||
|
||||
TEST(LedStripTest, parseLedStripConfig)
|
||||
{
|
||||
|
@ -312,7 +315,7 @@ TEST(ColorTest, parseColor)
|
|||
{ 333, 22, 1 }
|
||||
};
|
||||
|
||||
char *testColors[TEST_COLOR_COUNT] = {
|
||||
const char *testColors[TEST_COLOR_COUNT] = {
|
||||
"0,0,0",
|
||||
"1,1,1",
|
||||
"359,255,255",
|
||||
|
@ -336,12 +339,18 @@ TEST(ColorTest, parseColor)
|
|||
}
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
|
||||
uint8_t armingFlags = 0;
|
||||
uint16_t flightModeFlags = 0;
|
||||
int16_t rcCommand[4];
|
||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
|
||||
batteryState_e calculateBatteryState(void) {
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
void ws2811LedStripInit(void) {}
|
||||
void ws2811UpdateStrip(void) {}
|
||||
|
||||
void setLedValue(uint16_t index, const uint8_t value) {
|
||||
|
@ -399,3 +408,5 @@ int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax) {
|
|||
|
||||
return 0;
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define MAG
|
||||
#define BARO
|
||||
#define GPS
|
||||
#define TELEMETRY
|
||||
|
|
|
@ -19,23 +19,27 @@
|
|||
|
||||
#include <limits.h>
|
||||
|
||||
#include "build_config.h"
|
||||
extern "C" {
|
||||
#include "build_config.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/color.h"
|
||||
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
extern "C" {
|
||||
STATIC_UNIT_TESTED extern uint16_t dmaBufferOffset;
|
||||
|
||||
STATIC_UNIT_TESTED void fastUpdateLEDDMABuffer(rgbColor24bpp_t *color);
|
||||
STATIC_UNIT_TESTED void updateLEDDMABuffer(uint8_t componentValue);
|
||||
}
|
||||
|
||||
TEST(WS2812, updateDMABuffer) {
|
||||
// given
|
||||
rgbColor24bpp_t color1 = {0xFF,0xAA,0x55};
|
||||
rgbColor24bpp_t color1 = { .raw = {0xFF,0xAA,0x55} };
|
||||
|
||||
// and
|
||||
dmaBufferOffset = 0;
|
||||
|
@ -86,6 +90,7 @@ TEST(WS2812, updateDMABuffer) {
|
|||
byteIndex++;
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
rgbColor24bpp_t* hsvToRgb24(const hsvColor_t *c) {
|
||||
UNUSED(c);
|
||||
return NULL;
|
||||
|
@ -93,3 +98,4 @@ rgbColor24bpp_t* hsvToRgb24(const hsvColor_t *c) {
|
|||
|
||||
void ws2811LedStripHardwareInit(void) {}
|
||||
void ws2811LedStripDMAEnable(void) {}
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue