mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Merge remote-tracking branch 'upstream/master'
This commit is contained in:
commit
cf37c5247f
22 changed files with 630 additions and 187 deletions
|
@ -214,7 +214,8 @@ static const blackboxGPSFieldDefinition_t blackboxGpsGFields[] = {
|
|||
{"GPS_coord[0]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)},
|
||||
{"GPS_coord[1]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)},
|
||||
{"GPS_altitude", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"GPS_speed", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}
|
||||
{"GPS_speed", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"GPS_ground_course",UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}
|
||||
};
|
||||
|
||||
// GPS home frame
|
||||
|
@ -247,13 +248,25 @@ extern uint8_t motorCount;
|
|||
//From mw.c:
|
||||
extern uint32_t currentTime;
|
||||
|
||||
static const int SERIAL_CHUNK_SIZE = 16;
|
||||
// How many bytes should we transmit per loop iteration?
|
||||
static uint8_t serialChunkSize = 16;
|
||||
|
||||
static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
|
||||
|
||||
static uint32_t startTime;
|
||||
static unsigned int headerXmitIndex;
|
||||
static int fieldXmitIndex;
|
||||
static struct {
|
||||
uint32_t headerIndex;
|
||||
|
||||
/* Since these fields are used during different blackbox states (never simultaneously) we can
|
||||
* overlap them to save on RAM
|
||||
*/
|
||||
union {
|
||||
int fieldIndex;
|
||||
int serialBudget;
|
||||
uint32_t startTime;
|
||||
} u;
|
||||
} xmitState;
|
||||
|
||||
static uint32_t blackboxConditionCache;
|
||||
|
||||
static uint32_t blackboxIteration;
|
||||
static uint32_t blackboxPFrameIndex, blackboxIFrameIndex;
|
||||
|
@ -570,7 +583,7 @@ static void writeTag8_8SVB(int32_t *values, int valueCount)
|
|||
}
|
||||
}
|
||||
|
||||
static bool testBlackboxCondition(FlightLogFieldCondition condition)
|
||||
static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||
{
|
||||
switch (condition) {
|
||||
case FLIGHT_LOG_FIELD_CONDITION_ALWAYS:
|
||||
|
@ -585,19 +598,10 @@ static bool testBlackboxCondition(FlightLogFieldCondition condition)
|
|||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8:
|
||||
return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
|
||||
return masterConfig.mixerMode == MIXER_TRI;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2:
|
||||
return currentProfile->pidProfile.P8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0] != 0;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2:
|
||||
return currentProfile->pidProfile.I8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0] != 0;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
|
||||
|
@ -627,22 +631,39 @@ static bool testBlackboxCondition(FlightLogFieldCondition condition)
|
|||
}
|
||||
}
|
||||
|
||||
static void blackboxBuildConditionCache()
|
||||
{
|
||||
FlightLogFieldCondition cond;
|
||||
|
||||
blackboxConditionCache = 0;
|
||||
|
||||
for (cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) {
|
||||
if (testBlackboxConditionUncached(cond))
|
||||
blackboxConditionCache |= 1 << cond;
|
||||
}
|
||||
}
|
||||
|
||||
static bool testBlackboxCondition(FlightLogFieldCondition condition)
|
||||
{
|
||||
return (blackboxConditionCache & (1 << condition)) != 0;
|
||||
}
|
||||
|
||||
static void blackboxSetState(BlackboxState newState)
|
||||
{
|
||||
//Perform initial setup required for the new state
|
||||
switch (newState) {
|
||||
case BLACKBOX_STATE_SEND_HEADER:
|
||||
startTime = millis();
|
||||
headerXmitIndex = 0;
|
||||
xmitState.headerIndex = 0;
|
||||
xmitState.u.startTime = millis();
|
||||
break;
|
||||
case BLACKBOX_STATE_SEND_FIELDINFO:
|
||||
case BLACKBOX_STATE_SEND_GPS_G_HEADERS:
|
||||
case BLACKBOX_STATE_SEND_GPS_H_HEADERS:
|
||||
headerXmitIndex = 0;
|
||||
fieldXmitIndex = -1;
|
||||
xmitState.headerIndex = 0;
|
||||
xmitState.u.fieldIndex = -1;
|
||||
break;
|
||||
case BLACKBOX_STATE_SEND_SYSINFO:
|
||||
headerXmitIndex = 0;
|
||||
xmitState.headerIndex = 0;
|
||||
break;
|
||||
case BLACKBOX_STATE_RUNNING:
|
||||
blackboxIteration = 0;
|
||||
|
@ -855,6 +876,15 @@ static void configureBlackboxPort(void)
|
|||
previousBaudRate = blackboxPort->baudRate;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* We want to write at about 7200 bytes per second to give the OpenLog a good chance to save to disk. If
|
||||
* about looptime microseconds elapse between our writes, this is the budget of how many bytes we should
|
||||
* transmit with each write.
|
||||
*
|
||||
* 9 / 1250 = 7200 / 1000000
|
||||
*/
|
||||
serialChunkSize = max((masterConfig.looptime * 9) / 1250, 4);
|
||||
}
|
||||
|
||||
static void releaseBlackboxPort(void)
|
||||
|
@ -887,6 +917,13 @@ 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.
|
||||
*/
|
||||
blackboxBuildConditionCache();
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
|
||||
}
|
||||
}
|
||||
|
@ -922,6 +959,7 @@ static void writeGPSFrame()
|
|||
writeSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]);
|
||||
writeUnsignedVB(GPS_altitude);
|
||||
writeUnsignedVB(GPS_speed);
|
||||
writeUnsignedVB(GPS_ground_course);
|
||||
|
||||
gpsHistory.GPS_numSat = GPS_numSat;
|
||||
gpsHistory.GPS_coord[0] = GPS_coord[0];
|
||||
|
@ -982,7 +1020,7 @@ static void loadBlackboxState(void)
|
|||
* Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field
|
||||
* should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition.
|
||||
*
|
||||
* Set headerXmitIndex to 0 and fieldXmitIndex to -1 before calling for the first time.
|
||||
* Set xmitState.headerIndex to 0 and xmitState.u.fieldIndex to -1 before calling for the first time.
|
||||
*
|
||||
* secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the
|
||||
* fieldDefinition and secondCondition arrays.
|
||||
|
@ -1002,23 +1040,23 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he
|
|||
* We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit
|
||||
* the whole header.
|
||||
*/
|
||||
if (fieldXmitIndex == -1) {
|
||||
if (headerXmitIndex >= headerCount)
|
||||
if (xmitState.u.fieldIndex == -1) {
|
||||
if (xmitState.headerIndex >= headerCount)
|
||||
return false; //Someone probably called us again after we had already completed transmission
|
||||
|
||||
charsWritten = blackboxPrint("H Field ");
|
||||
charsWritten += blackboxPrint(headerNames[headerXmitIndex]);
|
||||
charsWritten += blackboxPrint(headerNames[xmitState.headerIndex]);
|
||||
charsWritten += blackboxPrint(":");
|
||||
|
||||
fieldXmitIndex++;
|
||||
xmitState.u.fieldIndex++;
|
||||
needComma = false;
|
||||
} else
|
||||
charsWritten = 0;
|
||||
|
||||
for (; fieldXmitIndex < fieldCount && charsWritten < SERIAL_CHUNK_SIZE; fieldXmitIndex++) {
|
||||
def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * fieldXmitIndex);
|
||||
for (; xmitState.u.fieldIndex < fieldCount && charsWritten < serialChunkSize; xmitState.u.fieldIndex++) {
|
||||
def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex);
|
||||
|
||||
if (!conditions || testBlackboxCondition(conditions[conditionsStride * fieldXmitIndex])) {
|
||||
if (!conditions || testBlackboxCondition(conditions[conditionsStride * xmitState.u.fieldIndex])) {
|
||||
if (needComma) {
|
||||
blackboxWrite(',');
|
||||
charsWritten++;
|
||||
|
@ -1026,16 +1064,16 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he
|
|||
needComma = true;
|
||||
|
||||
// The first header is a field name
|
||||
if (headerXmitIndex == 0) {
|
||||
if (xmitState.headerIndex == 0) {
|
||||
charsWritten += blackboxPrint(def->name);
|
||||
} else {
|
||||
//The other headers are integers
|
||||
if (def->arr[headerXmitIndex - 1] >= 10) {
|
||||
blackboxWrite(def->arr[headerXmitIndex - 1] / 10 + '0');
|
||||
blackboxWrite(def->arr[headerXmitIndex - 1] % 10 + '0');
|
||||
if (def->arr[xmitState.headerIndex - 1] >= 10) {
|
||||
blackboxWrite(def->arr[xmitState.headerIndex - 1] / 10 + '0');
|
||||
blackboxWrite(def->arr[xmitState.headerIndex - 1] % 10 + '0');
|
||||
charsWritten += 2;
|
||||
} else {
|
||||
blackboxWrite(def->arr[headerXmitIndex - 1] + '0');
|
||||
blackboxWrite(def->arr[xmitState.headerIndex - 1] + '0');
|
||||
charsWritten++;
|
||||
}
|
||||
}
|
||||
|
@ -1043,85 +1081,115 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he
|
|||
}
|
||||
|
||||
// Did we complete this line?
|
||||
if (fieldXmitIndex == fieldCount) {
|
||||
if (xmitState.u.fieldIndex == fieldCount) {
|
||||
blackboxWrite('\n');
|
||||
headerXmitIndex++;
|
||||
fieldXmitIndex = -1;
|
||||
xmitState.headerIndex++;
|
||||
xmitState.u.fieldIndex = -1;
|
||||
}
|
||||
|
||||
return headerXmitIndex < headerCount;
|
||||
return xmitState.headerIndex < headerCount;
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmit a portion of the system information headers. Begin with a xmitIndex of 0. Returns the next xmitIndex to
|
||||
* call with, or -1 if transmission is complete.
|
||||
* 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 int blackboxWriteSysinfo(int xmitIndex)
|
||||
static bool blackboxWriteSysinfo()
|
||||
{
|
||||
union floatConvert_t {
|
||||
float f;
|
||||
uint32_t u;
|
||||
} floatConvert;
|
||||
|
||||
switch (xmitIndex) {
|
||||
if (xmitState.headerIndex == 0) {
|
||||
xmitState.u.serialBudget = 0;
|
||||
xmitState.headerIndex = 1;
|
||||
}
|
||||
|
||||
// How many bytes can we afford to transmit this loop?
|
||||
xmitState.u.serialBudget = min(xmitState.u.serialBudget + serialChunkSize, 64);
|
||||
|
||||
// Most headers will consume at least 20 bytes so wait until we've built up that much link budget
|
||||
if (xmitState.u.serialBudget < 20) {
|
||||
return false;
|
||||
}
|
||||
|
||||
switch (xmitState.headerIndex) {
|
||||
case 0:
|
||||
blackboxPrintf("H Firmware type:Cleanflight\n");
|
||||
//Shouldn't ever get here
|
||||
break;
|
||||
case 1:
|
||||
// Pause to allow more time for previous to transmit (it exceeds our chunk size)
|
||||
blackboxPrintf("H Firmware type:Cleanflight\n");
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H Firmware type:Cleanflight\n");
|
||||
break;
|
||||
case 2:
|
||||
blackboxPrintf("H Firmware revision:%s\n", shortGitRevision);
|
||||
|
||||
/* Don't need to be super exact about the budget so don't mind the fact that we're including the length of
|
||||
* the placeholder "%s"
|
||||
*/
|
||||
xmitState.u.serialBudget -= strlen("H Firmware revision:%s\n") + strlen(shortGitRevision);
|
||||
break;
|
||||
case 3:
|
||||
// Pause to allow more time for previous to transmit
|
||||
blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H Firmware date:%s %s\n") + strlen(buildDate) + strlen(buildTime);
|
||||
break;
|
||||
case 4:
|
||||
blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime);
|
||||
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:
|
||||
// Pause to allow more time for previous to transmit
|
||||
blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H rcRate:%d\n");
|
||||
break;
|
||||
case 6:
|
||||
blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H minthrottle:%d\n");
|
||||
break;
|
||||
case 7:
|
||||
blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
||||
blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H maxthrottle:%d\n");
|
||||
break;
|
||||
case 8:
|
||||
blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle);
|
||||
break;
|
||||
case 9:
|
||||
blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle);
|
||||
break;
|
||||
case 10:
|
||||
floatConvert.f = gyro.scale;
|
||||
blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H gyro.scale:0x%x\n") + 6;
|
||||
break;
|
||||
case 9:
|
||||
blackboxPrintf("H acc_1G:%u\n", acc_1G);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H acc_1G:%u\n");
|
||||
break;
|
||||
case 10:
|
||||
blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H vbatscale:%u\n");
|
||||
break;
|
||||
case 11:
|
||||
blackboxPrintf("H acc_1G:%u\n", acc_1G);
|
||||
break;
|
||||
case 12:
|
||||
blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale);
|
||||
break;
|
||||
case 13:
|
||||
blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage,
|
||||
masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage);
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H vbatcellvoltage:%u,%u,%u\n");
|
||||
break;
|
||||
case 14:
|
||||
//Pause
|
||||
break;
|
||||
case 15:
|
||||
case 12:
|
||||
blackboxPrintf("H vbatref:%u\n", vbatReference);
|
||||
break;
|
||||
case 16:
|
||||
// One more pause for good luck
|
||||
|
||||
xmitState.u.serialBudget -= strlen("H vbatref:%u\n");
|
||||
break;
|
||||
default:
|
||||
return -1;
|
||||
return true;
|
||||
}
|
||||
|
||||
return xmitIndex + 1;
|
||||
xmitState.headerIndex++;
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -1182,26 +1250,26 @@ static void blackboxPlaySyncBeep()
|
|||
|
||||
void handleBlackbox(void)
|
||||
{
|
||||
int i, result;
|
||||
int i;
|
||||
|
||||
switch (blackboxState) {
|
||||
case BLACKBOX_STATE_SEND_HEADER:
|
||||
//On entry of this state, headerXmitIndex is 0 and startTime is intialised
|
||||
//On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
|
||||
|
||||
/*
|
||||
* Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit
|
||||
* buffer.
|
||||
*/
|
||||
if (millis() > startTime + 100) {
|
||||
for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++)
|
||||
blackboxWrite(blackboxHeader[headerXmitIndex]);
|
||||
if (millis() > xmitState.u.startTime + 100) {
|
||||
for (i = 0; i < serialChunkSize && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++)
|
||||
blackboxWrite(blackboxHeader[xmitState.headerIndex]);
|
||||
|
||||
if (blackboxHeader[headerXmitIndex] == '\0')
|
||||
if (blackboxHeader[xmitState.headerIndex] == '\0')
|
||||
blackboxSetState(BLACKBOX_STATE_SEND_FIELDINFO);
|
||||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_SEND_FIELDINFO:
|
||||
//On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1
|
||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||
if (!sendFieldDefinition(blackboxMainHeaderNames, ARRAY_LENGTH(blackboxMainHeaderNames), blackboxMainFields, blackboxMainFields + 1,
|
||||
ARRAY_LENGTH(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
|
||||
#ifdef GPS
|
||||
|
@ -1214,28 +1282,26 @@ void handleBlackbox(void)
|
|||
break;
|
||||
#ifdef GPS
|
||||
case BLACKBOX_STATE_SEND_GPS_H_HEADERS:
|
||||
//On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1
|
||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||
if (!sendFieldDefinition(blackboxGPSHHeaderNames, ARRAY_LENGTH(blackboxGPSHHeaderNames), blackboxGpsHFields, blackboxGpsHFields + 1,
|
||||
ARRAY_LENGTH(blackboxGpsHFields), NULL, 0)) {
|
||||
ARRAY_LENGTH(blackboxGpsHFields), NULL, NULL)) {
|
||||
blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADERS);
|
||||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_SEND_GPS_G_HEADERS:
|
||||
//On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1
|
||||
//On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
|
||||
if (!sendFieldDefinition(blackboxGPSGHeaderNames, ARRAY_LENGTH(blackboxGPSGHeaderNames), blackboxGpsGFields, blackboxGpsGFields + 1,
|
||||
ARRAY_LENGTH(blackboxGpsGFields), NULL, 0)) {
|
||||
ARRAY_LENGTH(blackboxGpsGFields), NULL, NULL)) {
|
||||
blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case BLACKBOX_STATE_SEND_SYSINFO:
|
||||
//On entry of this state, headerXmitIndex is 0
|
||||
result = blackboxWriteSysinfo(headerXmitIndex);
|
||||
//On entry of this state, xmitState.headerIndex is 0
|
||||
|
||||
if (result == -1)
|
||||
//Keep writing chunks of the system info headers until it returns true to signal completion
|
||||
if (blackboxWriteSysinfo())
|
||||
blackboxSetState(BLACKBOX_STATE_PRERUN);
|
||||
else
|
||||
headerXmitIndex = result;
|
||||
break;
|
||||
case BLACKBOX_STATE_PRERUN:
|
||||
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
||||
|
|
|
@ -29,21 +29,18 @@ typedef enum FlightLogFieldCondition {
|
|||
FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8,
|
||||
FLIGHT_LOG_FIELD_CONDITION_TRICOPTER,
|
||||
|
||||
FLIGHT_LOG_FIELD_CONDITION_MAG = 20,
|
||||
FLIGHT_LOG_FIELD_CONDITION_MAG,
|
||||
FLIGHT_LOG_FIELD_CONDITION_BARO,
|
||||
FLIGHT_LOG_FIELD_CONDITION_VBAT,
|
||||
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0 = 40,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2,
|
||||
|
||||
FLIGHT_LOG_FIELD_CONDITION_NEVER = 255,
|
||||
FLIGHT_LOG_FIELD_CONDITION_NEVER,
|
||||
|
||||
FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS,
|
||||
FLIGHT_LOG_FIELD_CONDITION_LAST = FLIGHT_LOG_FIELD_CONDITION_NEVER
|
||||
} FlightLogFieldCondition;
|
||||
|
||||
typedef enum FlightLogFieldPredictor {
|
||||
|
|
|
@ -35,13 +35,16 @@ void ws2811LedStripHardwareInit(void)
|
|||
|
||||
#ifdef CC3D
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
#else
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||
|
||||
/* GPIOA Configuration: TIM3 Channel 1 as alternate function push-pull */
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
|
@ -52,6 +55,7 @@ void ws2811LedStripHardwareInit(void)
|
|||
/* Compute the prescaler value */
|
||||
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
|
@ -59,6 +63,7 @@ void ws2811LedStripHardwareInit(void)
|
|||
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
|
||||
|
||||
/* PWM1 Mode configuration: Channel1 */
|
||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||
|
@ -75,6 +80,7 @@ void ws2811LedStripHardwareInit(void)
|
|||
/* DMA1 Channel6 Config */
|
||||
DMA_DeInit(DMA1_Channel6);
|
||||
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM3->CCR1;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
|
|
|
@ -26,10 +26,18 @@
|
|||
#include "common/color.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
|
||||
#define WS2811_GPIO GPIOB
|
||||
#define WS2811_PIN Pin_8 // TIM16_CH1
|
||||
#define WS2811_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
|
||||
#ifndef WS2811_GPIO
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
|
||||
#define WS2811_GPIO GPIOB
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define WS2811_GPIO_AF GPIO_AF_1
|
||||
#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource8
|
||||
#define WS2811_TIMER TIM16
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel3
|
||||
#define WS2811_IRQ DMA1_Channel3_IRQn
|
||||
#endif
|
||||
|
||||
void ws2811LedStripHardwareInit(void)
|
||||
{
|
||||
|
@ -40,47 +48,53 @@ void ws2811LedStripHardwareInit(void)
|
|||
|
||||
uint16_t prescalerValue;
|
||||
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(WS2811_GPIO_AHB_PERIPHERAL, ENABLE);
|
||||
|
||||
GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_1);
|
||||
GPIO_PinAFConfig(WS2811_GPIO, WS2811_PIN_SOURCE, WS2811_GPIO_AF);
|
||||
|
||||
/* GPIOA Configuration: TIM16 Channel 1 as alternate function push-pull */
|
||||
/* Configuration alternate function push-pull */
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = WS2811_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_Init(WS2811_GPIO, &GPIO_InitStructure);
|
||||
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM16, ENABLE);
|
||||
RCC_APB2PeriphClockCmd(WS2811_TIMER_APB2_PERIPHERAL, ENABLE);
|
||||
|
||||
/* Compute the prescaler value */
|
||||
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(TIM16, &TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure);
|
||||
|
||||
/* PWM1 Mode configuration: Channel1 */
|
||||
/* PWM1 Mode configuration */
|
||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
|
||||
TIM_OC1Init(TIM16, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
|
||||
TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure);
|
||||
TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
|
||||
|
||||
|
||||
TIM_CtrlPWMOutputs(TIM16, ENABLE);
|
||||
TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
|
||||
|
||||
/* configure DMA */
|
||||
/* DMA clock enable */
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
|
||||
/* DMA1 Channel Config */
|
||||
DMA_DeInit(DMA1_Channel3);
|
||||
DMA_DeInit(WS2811_DMA_CHANNEL);
|
||||
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM16->CCR1;
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&WS2811_TIMER->CCR1;
|
||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
||||
|
@ -92,16 +106,15 @@ void ws2811LedStripHardwareInit(void)
|
|||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||
|
||||
DMA_Init(DMA1_Channel3, &DMA_InitStructure);
|
||||
DMA_Init(WS2811_DMA_CHANNEL, &DMA_InitStructure);
|
||||
|
||||
/* TIM16 CC1 DMA Request enable */
|
||||
TIM_DMACmd(TIM16, TIM_DMA_CC1, ENABLE);
|
||||
TIM_DMACmd(WS2811_TIMER, TIM_DMA_CC1, ENABLE);
|
||||
|
||||
DMA_ITConfig(DMA1_Channel3, DMA_IT_TC, ENABLE);
|
||||
DMA_ITConfig(WS2811_DMA_CHANNEL, DMA_IT_TC, ENABLE);
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel3_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannel = WS2811_IRQ;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA);
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA);
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
|
@ -111,21 +124,45 @@ void ws2811LedStripHardwareInit(void)
|
|||
ws2811UpdateStrip();
|
||||
}
|
||||
|
||||
#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL3
|
||||
void DMA1_Channel3_IRQHandler(void)
|
||||
{
|
||||
if (DMA_GetFlagStatus(DMA1_FLAG_TC3)) {
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
DMA_Cmd(DMA1_Channel3, DISABLE); // disable DMA channel 6
|
||||
DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel 6 transfer complete flag
|
||||
DMA_Cmd(DMA1_Channel3, DISABLE); // disable DMA channel
|
||||
DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel transfer complete flag
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
void DMA1_Channel2_IRQHandler(void)
|
||||
{
|
||||
if (DMA_GetFlagStatus(DMA1_FLAG_TC2)) {
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
DMA_Cmd(DMA1_Channel2, DISABLE); // disable DMA channel
|
||||
DMA_ClearFlag(DMA1_FLAG_TC2); // clear DMA1 Channel transfer complete flag
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL7
|
||||
void DMA1_Channel7_IRQHandler(void)
|
||||
{
|
||||
if (DMA_GetFlagStatus(DMA1_FLAG_TC7)) {
|
||||
ws2811LedDataTransferInProgress = 0;
|
||||
DMA_Cmd(DMA1_Channel7, DISABLE); // disable DMA channel
|
||||
DMA_ClearFlag(DMA1_FLAG_TC7); // clear DMA1 Channel transfer complete flag
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void ws2811LedStripDMAEnable(void)
|
||||
{
|
||||
DMA_SetCurrDataCounter(DMA1_Channel3, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||
TIM_SetCounter(TIM16, 0);
|
||||
TIM_Cmd(TIM16, ENABLE);
|
||||
DMA_Cmd(DMA1_Channel3, ENABLE);
|
||||
DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||
TIM_SetCounter(WS2811_TIMER, 0);
|
||||
TIM_Cmd(WS2811_TIMER, ENABLE);
|
||||
DMA_Cmd(WS2811_DMA_CHANNEL, ENABLE);
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -334,8 +334,15 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
|
||||
#ifdef LED_STRIP_TIMER
|
||||
// skip LED Strip output
|
||||
if (init->useLEDStrip && timerHardwarePtr->tim == LED_STRIP_TIMER)
|
||||
continue;
|
||||
if (init->useLEDStrip) {
|
||||
if (timerHardwarePtr->tim == LED_STRIP_TIMER)
|
||||
continue;
|
||||
#if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE)
|
||||
if (timerHardwarePtr->gpio == WS2811_GPIO && timerHardwarePtr->gpioPinSource == WS2811_PIN_SOURCE)
|
||||
continue;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X
|
||||
|
|
|
@ -326,6 +326,7 @@ void DMA1_Channel4_IRQHandler(void)
|
|||
handleUsartTxDma(s);
|
||||
}
|
||||
|
||||
#ifdef USE_USART2_TX_DMA
|
||||
// USART2 Tx DMA Handler
|
||||
void DMA1_Channel7_IRQHandler(void)
|
||||
{
|
||||
|
@ -334,8 +335,10 @@ void DMA1_Channel7_IRQHandler(void)
|
|||
DMA_Cmd(DMA1_Channel7, DISABLE);
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
// USART3 Tx DMA Handler
|
||||
#ifdef USE_USART2_TX_DMA
|
||||
void DMA1_Channel2_IRQHandler(void)
|
||||
{
|
||||
uartPort_t *s = &uartPort3;
|
||||
|
@ -343,6 +346,8 @@ void DMA1_Channel2_IRQHandler(void)
|
|||
DMA_Cmd(DMA1_Channel2, DISABLE);
|
||||
handleUsartTxDma(s);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
void usartIrqHandler(uartPort_t *s)
|
||||
{
|
||||
|
|
|
@ -121,7 +121,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
|||
#define MSP_PROTOCOL_VERSION 0
|
||||
|
||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||
#define API_VERSION_MINOR 1 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
#define API_VERSION_MINOR 2 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
|
||||
#define API_VERSION_LENGTH 2
|
||||
|
||||
|
@ -1097,7 +1097,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
break;
|
||||
|
||||
case MSP_LED_STRIP_CONFIG:
|
||||
headSerialReply(MAX_LED_STRIP_LENGTH * 4);
|
||||
headSerialReply(MAX_LED_STRIP_LENGTH * 6);
|
||||
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
|
||||
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
|
||||
serialize16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET);
|
||||
|
@ -1441,22 +1441,29 @@ static bool processInCommand(void)
|
|||
break;
|
||||
|
||||
case MSP_SET_LED_STRIP_CONFIG:
|
||||
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
|
||||
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
|
||||
uint16_t mask;
|
||||
// currently we're storing directions and functions in a uint16 (flags)
|
||||
// the msp uses 2 x uint16_t to cater for future expansion
|
||||
mask = read16();
|
||||
ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK;
|
||||
{
|
||||
uint8_t ledCount = currentPort->dataSize / 6;
|
||||
if (ledCount != MAX_LED_STRIP_LENGTH) {
|
||||
headSerialError(0);
|
||||
break;
|
||||
}
|
||||
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
|
||||
ledConfig_t *ledConfig = &masterConfig.ledConfigs[i];
|
||||
uint16_t mask;
|
||||
// currently we're storing directions and functions in a uint16 (flags)
|
||||
// the msp uses 2 x uint16_t to cater for future expansion
|
||||
mask = read16();
|
||||
ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK;
|
||||
|
||||
mask = read16();
|
||||
ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
|
||||
mask = read16();
|
||||
ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK;
|
||||
|
||||
mask = read8();
|
||||
ledConfig->xy = CALCULATE_LED_X(mask);
|
||||
mask = read8();
|
||||
ledConfig->xy = CALCULATE_LED_X(mask);
|
||||
|
||||
mask = read8();
|
||||
ledConfig->xy |= CALCULATE_LED_Y(mask);
|
||||
mask = read8();
|
||||
ledConfig->xy |= CALCULATE_LED_Y(mask);
|
||||
}
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
|
|
@ -345,7 +345,7 @@ void parseRcChannels(const char *input, rxConfig_t *rxConfig)
|
|||
|
||||
for (c = input; *c; c++) {
|
||||
s = strchr(rcChannelLetters, *c);
|
||||
if (s)
|
||||
if (s && (s < rcChannelLetters + MAX_MAPPABLE_RX_INPUTS))
|
||||
rxConfig->rcmap[s - rcChannelLetters] = c - input;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -69,7 +69,23 @@
|
|||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#if 1
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
#else
|
||||
// alternative LED strip configuration, tested working.
|
||||
#define LED_STRIP_TIMER TIM1
|
||||
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define WS2811_GPIO_AF GPIO_AF_6
|
||||
#define WS2811_PIN GPIO_Pin_8
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource8
|
||||
#define WS2811_TIMER TIM1
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
#define WS2811_IRQ DMA1_Channel2_IRQn
|
||||
#endif
|
||||
|
||||
#define BLACKBOX
|
||||
#define TELEMETRY
|
||||
|
|
|
@ -92,6 +92,41 @@
|
|||
#define GPS
|
||||
#define DISPLAY
|
||||
|
||||
#define LED_STRIP
|
||||
#if 1
|
||||
// LED strip configuration using PWM motor output pin 5.
|
||||
#define LED_STRIP_TIMER TIM16
|
||||
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define WS2811_GPIO_AF GPIO_AF_1
|
||||
#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource6
|
||||
#define WS2811_TIMER TIM16
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel3
|
||||
#define WS2811_IRQ DMA1_Channel3_IRQn
|
||||
#endif
|
||||
|
||||
#if 0
|
||||
// Alternate LED strip pin
|
||||
// FIXME DMA IRQ Transfer Complete is never called because the TIM17_DMA_RMP needs to be set in SYSCFG_CFGR1
|
||||
#define LED_STRIP_TIMER TIM17
|
||||
|
||||
#define USE_LED_STRIP_ON_DMA1_CHANNEL7
|
||||
#define WS2811_GPIO GPIOA
|
||||
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define WS2811_GPIO_AF GPIO_AF_1
|
||||
#define WS2811_PIN GPIO_Pin_7 // TIM17_CH1
|
||||
#define WS2811_PIN_SOURCE GPIO_PinSource7
|
||||
#define WS2811_TIMER TIM17
|
||||
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM17
|
||||
#define WS2811_DMA_CHANNEL DMA1_Channel7
|
||||
#define WS2811_IRQ DMA1_Channel7_IRQn
|
||||
#endif
|
||||
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART2, PA3
|
||||
#define BIND_PORT GPIOA
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue