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

Firmware version 0.1.4

Add ability to reduce recorded data rate
Update struct names to conform to code style guidelines
This commit is contained in:
Nicholas Sherlock 2014-12-17 17:16:17 +13:00
parent e47a82add8
commit ce5d64f653
6 changed files with 5709 additions and 5646 deletions

File diff suppressed because it is too large Load diff

View file

@ -77,11 +77,7 @@
#define BLACKBOX_BAUDRATE 115200 #define BLACKBOX_BAUDRATE 115200
#define BLACKBOX_INITIAL_PORT_MODE MODE_TX #define BLACKBOX_INITIAL_PORT_MODE MODE_TX
#define BLACKBOX_I_INTERVAL 32
static const char blackboxHeader[] =
"H Product:Blackbox flight data recorder by Nicholas Sherlock\n"
"H Blackbox version:1\n"
"H Data version:1\n";
// Some macros to make writing FLIGHT_LOG_FIELD_PREDICTOR_* constants shorter: // Some macros to make writing FLIGHT_LOG_FIELD_PREDICTOR_* constants shorter:
#define STR_HELPER(x) #x #define STR_HELPER(x) #x
@ -93,6 +89,12 @@ static const char blackboxHeader[] =
#define PREDICT(x) STR(CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)) #define PREDICT(x) STR(CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x))
#define ENCODING(x) STR(CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)) #define ENCODING(x) STR(CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x))
static const char blackboxHeader[] =
"H Product:Blackbox flight data recorder by Nicholas Sherlock\n"
"H Blackbox version:1\n"
"H Data version:1\n"
"H I interval:" STR(BLACKBOX_I_INTERVAL) "\n";
/* These headers have info for all 8 motors on them, we'll trim the final fields off to match the number of motors in the mixer: */ /* These headers have info for all 8 motors on them, we'll trim the final fields off to match the number of motors in the mixer: */
static const char * const blackboxHeaderFields[] = { static const char * const blackboxHeaderFields[] = {
"H Field I name:" "H Field I name:"
@ -288,10 +290,10 @@ static uint32_t previousBaudRate;
static gpsState_t gpsHistory; static gpsState_t gpsHistory;
// Keep a history of length 2, plus a buffer for MW to store the new values into // Keep a history of length 2, plus a buffer for MW to store the new values into
static blackbox_values_t blackboxHistoryRing[3]; static blackboxValues_t blackboxHistoryRing[3];
// These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old) // These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old)
static blackbox_values_t* blackboxHistory[3]; static blackboxValues_t* blackboxHistory[3];
static int isTricopter() static int isTricopter()
{ {
@ -536,7 +538,7 @@ static void writeTag8_4S16(int32_t *values) {
static void writeIntraframe(void) static void writeIntraframe(void)
{ {
blackbox_values_t *blackboxCurrent = blackboxHistory[0]; blackboxValues_t *blackboxCurrent = blackboxHistory[0];
int x; int x;
blackboxWrite('I'); blackboxWrite('I');
@ -589,8 +591,8 @@ static void writeInterframe(void)
int x; int x;
int32_t deltas[4]; int32_t deltas[4];
blackbox_values_t *blackboxCurrent = blackboxHistory[0]; blackboxValues_t *blackboxCurrent = blackboxHistory[0];
blackbox_values_t *blackboxLast = blackboxHistory[1]; blackboxValues_t *blackboxLast = blackboxHistory[1];
blackboxWrite('P'); blackboxWrite('P');
@ -645,6 +647,28 @@ static void writeInterframe(void)
blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing; blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
} }
static int gcd(int num, int denom)
{
if (denom == 0)
return num;
return gcd(denom, num % denom);
}
static void validateBlackboxConfig()
{
int div;
if (masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) {
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
} else {
div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
masterConfig.blackbox_rate_num /= div;
masterConfig.blackbox_rate_denom /= div;
}
}
static void configureBlackboxPort(void) static void configureBlackboxPort(void)
{ {
blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX); blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX);
@ -676,6 +700,8 @@ static void releaseBlackboxPort(void)
void startBlackbox(void) void startBlackbox(void)
{ {
if (blackboxState == BLACKBOX_STATE_STOPPED) { if (blackboxState == BLACKBOX_STATE_STOPPED) {
validateBlackboxConfig();
configureBlackboxPort(); configureBlackboxPort();
if (!blackboxPort) { if (!blackboxPort) {
@ -739,7 +765,7 @@ static void writeGPSFrame()
*/ */
static void loadBlackboxState(void) static void loadBlackboxState(void)
{ {
blackbox_values_t *blackboxCurrent = blackboxHistory[0]; blackboxValues_t *blackboxCurrent = blackboxHistory[0];
int i; int i;
blackboxCurrent->time = currentTime; blackboxCurrent->time = currentTime;
@ -774,6 +800,8 @@ void handleBlackbox(void)
const int SERIAL_CHUNK_SIZE = 16; const int SERIAL_CHUNK_SIZE = 16;
static int charXmitIndex = 0; static int charXmitIndex = 0;
int motorsToRemove, endIndex; int motorsToRemove, endIndex;
int blackboxIntercycleIndex, blackboxIntracycleIndex;
union floatConvert_t { union floatConvert_t {
float f; float f;
uint32_t u; uint32_t u;
@ -894,17 +922,19 @@ void handleBlackbox(void)
headerXmitIndex++; headerXmitIndex++;
break; break;
case BLACKBOX_STATE_RUNNING: case BLACKBOX_STATE_RUNNING:
// Copy current system values into the blackbox
loadBlackboxState();
// Write a keyframe every 32 frames so we can resynchronise upon missing frames // Write a keyframe every 32 frames so we can resynchronise upon missing frames
int blackboxIntercycleIndex = blackboxIteration % 32; blackboxIntercycleIndex = blackboxIteration % BLACKBOX_I_INTERVAL;
int blackboxIntracycleIndex = blackboxIteration / 32; blackboxIntracycleIndex = blackboxIteration / BLACKBOX_I_INTERVAL;
if (blackboxIntercycleIndex == 0) if (blackboxIntercycleIndex == 0) {
// Copy current system values into the blackbox
loadBlackboxState();
writeIntraframe(); writeIntraframe();
else { } else {
writeInterframe(); if ((blackboxIntercycleIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num) {
loadBlackboxState();
writeInterframe();
}
if (feature(FEATURE_GPS)) { if (feature(FEATURE_GPS)) {
/* /*
@ -915,7 +945,7 @@ void handleBlackbox(void)
* still be interpreted correctly. * still be interpreted correctly.
*/ */
if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1] if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1]
|| (blackboxIntercycleIndex == 15 && blackboxIntracycleIndex % 128 == 0)) { || (blackboxIntercycleIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIntracycleIndex % 128 == 0)) {
writeGPSHomeFrame(); writeGPSHomeFrame();
writeGPSFrame(); writeGPSFrame();
@ -934,7 +964,7 @@ void handleBlackbox(void)
} }
} }
bool canUseBlackboxWithCurrentConfiguration(void) static bool canUseBlackboxWithCurrentConfiguration(void)
{ {
if (!feature(FEATURE_BLACKBOX)) if (!feature(FEATURE_BLACKBOX))
return false; return false;

View file

@ -19,7 +19,7 @@
#include <stdint.h> #include <stdint.h>
typedef struct blackbox_values_t { typedef struct blackboxValues_t {
uint32_t time; uint32_t time;
int32_t axisP[3], axisI[3], axisD[3]; int32_t axisP[3], axisI[3], axisD[3];
@ -29,7 +29,7 @@ typedef struct blackbox_values_t {
int16_t accSmooth[3]; int16_t accSmooth[3];
int16_t motor[MAX_SUPPORTED_MOTORS]; int16_t motor[MAX_SUPPORTED_MOTORS];
int16_t servo[MAX_SUPPORTED_SERVOS]; int16_t servo[MAX_SUPPORTED_SERVOS];
} blackbox_values_t; } blackboxValues_t;
void initBlackbox(void); void initBlackbox(void);
void handleBlackbox(void); void handleBlackbox(void);

View file

@ -435,6 +435,11 @@ static void resetConf(void)
applyDefaultLedStripConfig(masterConfig.ledConfigs); applyDefaultLedStripConfig(masterConfig.ledConfigs);
#endif #endif
#ifdef BLACKBOX
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
#endif
// copy first profile into remaining profile // copy first profile into remaining profile
for (i = 1; i < MAX_PROFILE_COUNT; i++) { for (i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));

View file

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

View file

@ -386,6 +386,9 @@ const clivalue_t valueTable[] = {
{ "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], 0, 200 }, { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], 0, 200 },
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 }, { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 }, { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
}; };
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))