mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 17:25:18 +03:00
Moved blackbox related parameters into structs
This commit is contained in:
parent
2f78d63a6a
commit
3e726f247a
7 changed files with 48 additions and 42 deletions
|
@ -440,7 +440,7 @@ bool blackboxMayEditConfig(void)
|
|||
|
||||
static bool blackboxIsOnlyLoggingIntraframes()
|
||||
{
|
||||
return masterConfig.blackbox_rate_num == 1 && masterConfig.blackbox_rate_denom == 32;
|
||||
return masterConfig.blackboxConfig.rate_num == 1 && masterConfig.blackboxConfig.rate_denom == 32;
|
||||
}
|
||||
|
||||
static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||
|
@ -505,7 +505,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
return masterConfig.rxConfig.rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
|
||||
return masterConfig.blackbox_rate_num < masterConfig.blackbox_rate_denom;
|
||||
return masterConfig.blackboxConfig.rate_num < masterConfig.blackboxConfig.rate_denom;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
|
||||
return false;
|
||||
|
@ -942,22 +942,22 @@ static void validateBlackboxConfig()
|
|||
{
|
||||
int div;
|
||||
|
||||
if (masterConfig.blackbox_rate_num == 0 || masterConfig.blackbox_rate_denom == 0
|
||||
|| masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) {
|
||||
masterConfig.blackbox_rate_num = 1;
|
||||
masterConfig.blackbox_rate_denom = 1;
|
||||
if (masterConfig.blackboxConfig.rate_num == 0 || masterConfig.blackboxConfig.rate_denom == 0
|
||||
|| masterConfig.blackboxConfig.rate_num >= masterConfig.blackboxConfig.rate_denom) {
|
||||
masterConfig.blackboxConfig.rate_num = 1;
|
||||
masterConfig.blackboxConfig.rate_denom = 1;
|
||||
} else {
|
||||
/* Reduce the fraction the user entered as much as possible (makes the recorded/skipped frame pattern repeat
|
||||
* itself more frequently)
|
||||
*/
|
||||
div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
div = gcd(masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
|
||||
|
||||
masterConfig.blackbox_rate_num /= div;
|
||||
masterConfig.blackbox_rate_denom /= div;
|
||||
masterConfig.blackboxConfig.rate_num /= div;
|
||||
masterConfig.blackboxConfig.rate_denom /= div;
|
||||
}
|
||||
|
||||
// If we've chosen an unsupported device, change the device to serial
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
#endif
|
||||
|
@ -969,7 +969,7 @@ static void validateBlackboxConfig()
|
|||
break;
|
||||
|
||||
default:
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
||||
masterConfig.blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1309,7 +1309,7 @@ static bool blackboxWriteSysinfo()
|
|||
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:INAV %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName);
|
||||
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackboxConfig.rate_num, masterConfig.blackboxConfig.rate_denom);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rcRate:%d", 100); //For compatibility reasons write rc_rate 100
|
||||
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.motorConfig.minthrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.motorConfig.maxthrottle);
|
||||
|
@ -1455,10 +1455,10 @@ static void blackboxCheckAndLogArmingBeep()
|
|||
*/
|
||||
static bool blackboxShouldLogPFrame(uint32_t pFrameIndex)
|
||||
{
|
||||
/* Adding a magic shift of "masterConfig.blackbox_rate_num - 1" in here creates a better spread of
|
||||
/* Adding a magic shift of "masterConfig.blackboxConfig.rate_num - 1" in here creates a better spread of
|
||||
* recorded / skipped frames when the I frame's position is considered:
|
||||
*/
|
||||
return (pFrameIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num;
|
||||
return (pFrameIndex + masterConfig.blackboxConfig.rate_num - 1) % masterConfig.blackboxConfig.rate_denom < masterConfig.blackboxConfig.rate_num;
|
||||
}
|
||||
|
||||
static bool blackboxShouldLogIFrame() {
|
||||
|
|
|
@ -19,10 +19,16 @@
|
|||
|
||||
#include "blackbox/blackbox_fielddefs.h"
|
||||
|
||||
typedef struct blackboxConfig_s {
|
||||
uint8_t rate_num;
|
||||
uint8_t rate_denom;
|
||||
uint8_t device;
|
||||
} blackboxConfig_t;
|
||||
|
||||
void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data);
|
||||
|
||||
void initBlackbox(void);
|
||||
void handleBlackbox(uint32_t currentTime);
|
||||
void startBlackbox(void);
|
||||
void finishBlackbox(void);
|
||||
bool blackboxMayEditConfig(void);
|
||||
bool blackboxMayEditConfig(void);
|
||||
|
|
|
@ -119,7 +119,7 @@ static struct {
|
|||
|
||||
void blackboxWrite(uint8_t value)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
flashfsWriteByte(value); // Write byte asynchronously
|
||||
|
@ -191,7 +191,7 @@ int blackboxPrint(const char *s)
|
|||
int length;
|
||||
const uint8_t *pos;
|
||||
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
case BLACKBOX_DEVICE_FLASH:
|
||||
|
@ -535,7 +535,7 @@ void blackboxWriteFloat(float value)
|
|||
*/
|
||||
void blackboxDeviceFlush(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_FLASHFS
|
||||
/*
|
||||
* This is our only output device which requires us to call flush() in order for it to write anything. The other
|
||||
|
@ -558,7 +558,7 @@ void blackboxDeviceFlush(void)
|
|||
*/
|
||||
bool blackboxDeviceFlushForce(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
// Nothing to speed up flushing on serial, as serial is continuously being drained out of its buffer
|
||||
return isSerialTransmitBufferEmpty(blackboxPort);
|
||||
|
@ -586,7 +586,7 @@ bool blackboxDeviceFlushForce(void)
|
|||
*/
|
||||
bool blackboxDeviceOpen(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
{
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX);
|
||||
|
@ -660,7 +660,7 @@ bool blackboxDeviceOpen(void)
|
|||
*/
|
||||
void blackboxDeviceClose(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
// Since the serial port could be shared with other processes, we have to give it back here
|
||||
closeSerialPort(blackboxPort);
|
||||
|
@ -816,7 +816,7 @@ static bool blackboxSDCardBeginLog()
|
|||
*/
|
||||
bool blackboxDeviceBeginLog(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_SDCARD
|
||||
case BLACKBOX_DEVICE_SDCARD:
|
||||
return blackboxSDCardBeginLog();
|
||||
|
@ -840,7 +840,7 @@ bool blackboxDeviceEndLog(bool retainLog)
|
|||
(void) retainLog;
|
||||
#endif
|
||||
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
#ifdef USE_SDCARD
|
||||
case BLACKBOX_DEVICE_SDCARD:
|
||||
// Keep retrying until the close operation queues
|
||||
|
@ -862,7 +862,7 @@ bool blackboxDeviceEndLog(bool retainLog)
|
|||
|
||||
bool isBlackboxDeviceFull(void)
|
||||
{
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
return false;
|
||||
|
||||
|
@ -889,7 +889,7 @@ void blackboxReplenishHeaderBudget()
|
|||
{
|
||||
int32_t freeSpace;
|
||||
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
freeSpace = serialTxBytesFree(blackboxPort);
|
||||
break;
|
||||
|
@ -935,7 +935,7 @@ blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
|
|||
}
|
||||
|
||||
// Handle failure:
|
||||
switch (masterConfig.blackbox_device) {
|
||||
switch (masterConfig.blackboxConfig.device) {
|
||||
case BLACKBOX_DEVICE_SERIAL:
|
||||
/*
|
||||
* One byte of the tx buffer isn't available for user data (due to its circular list implementation),
|
||||
|
|
|
@ -646,12 +646,12 @@ static void resetConf(void)
|
|||
#ifdef BLACKBOX
|
||||
#ifdef ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
featureSet(FEATURE_BLACKBOX);
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH;
|
||||
masterConfig.blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
|
||||
#else
|
||||
masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
|
||||
masterConfig.blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
|
||||
#endif
|
||||
masterConfig.blackbox_rate_num = 1;
|
||||
masterConfig.blackbox_rate_denom = 1;
|
||||
masterConfig.blackboxConfig.rate_num = 1;
|
||||
masterConfig.blackboxConfig.rate_denom = 1;
|
||||
#endif
|
||||
|
||||
// alternative defaults settings for COLIBRI RACE targets
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -163,9 +165,7 @@ typedef struct master_s {
|
|||
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
|
||||
|
||||
#ifdef BLACKBOX
|
||||
uint8_t blackbox_rate_num;
|
||||
uint8_t blackbox_rate_denom;
|
||||
uint8_t blackbox_device;
|
||||
blackboxConfig_t blackboxConfig;
|
||||
#endif
|
||||
|
||||
uint32_t beeper_off_flags;
|
||||
|
|
|
@ -941,9 +941,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
case MSP_BLACKBOX_CONFIG:
|
||||
#ifdef BLACKBOX
|
||||
sbufWriteU8(dst, 1); //Blackbox supported
|
||||
sbufWriteU8(dst, masterConfig.blackbox_device);
|
||||
sbufWriteU8(dst, masterConfig.blackbox_rate_num);
|
||||
sbufWriteU8(dst, masterConfig.blackbox_rate_denom);
|
||||
sbufWriteU8(dst, masterConfig.blackboxConfig.device);
|
||||
sbufWriteU8(dst, masterConfig.blackboxConfig.rate_num);
|
||||
sbufWriteU8(dst, masterConfig.blackboxConfig.rate_denom);
|
||||
#else
|
||||
sbufWriteU8(dst, 0); // Blackbox not supported
|
||||
sbufWriteU8(dst, 0);
|
||||
|
@ -1456,9 +1456,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
// Don't allow config to be updated while Blackbox is logging
|
||||
if (!blackboxMayEditConfig())
|
||||
return false;
|
||||
masterConfig.blackbox_device = sbufReadU8(src);
|
||||
masterConfig.blackbox_rate_num = sbufReadU8(src);
|
||||
masterConfig.blackbox_rate_denom = sbufReadU8(src);
|
||||
masterConfig.blackboxConfig.device = sbufReadU8(src);
|
||||
masterConfig.blackboxConfig.rate_num = sbufReadU8(src);
|
||||
masterConfig.blackboxConfig.rate_denom = sbufReadU8(src);
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
|
|
@ -889,9 +889,9 @@ const clivalue_t valueTable[] = {
|
|||
{ "rate_accel_limit_yaw", VAR_UINT32 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.axisAccelerationLimitYaw, .config.minmax = {0, 500000 } },
|
||||
|
||||
#ifdef BLACKBOX
|
||||
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 }, 0 },
|
||||
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 }, 0 },
|
||||
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE }, 0 },
|
||||
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackboxConfig.rate_num, .config.minmax = { 1, 32 }, 0 },
|
||||
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackboxConfig.rate_denom, .config.minmax = { 1, 32 }, 0 },
|
||||
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackboxConfig.device, .config.lookup = { TABLE_BLACKBOX_DEVICE }, 0 },
|
||||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue