Merge branch 'master' into development
This commit is contained in:
commit
17df76e63b
|
@ -896,6 +896,61 @@ void finishBlackbox(void)
|
|||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Test Motors Blackbox Logging
|
||||
*/
|
||||
bool startedLoggingInTestMode = false;
|
||||
|
||||
void startInTestMode(void)
|
||||
{
|
||||
if(!startedLoggingInTestMode) {
|
||||
if (masterConfig.blackbox_device == BLACKBOX_DEVICE_SERIAL) {
|
||||
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
|
||||
if (sharedBlackboxAndMspPort) {
|
||||
return; // When in test mode, we cannot share the MSP and serial logger port!
|
||||
}
|
||||
}
|
||||
startBlackbox();
|
||||
startedLoggingInTestMode = true;
|
||||
}
|
||||
}
|
||||
void stopInTestMode(void)
|
||||
{
|
||||
if(startedLoggingInTestMode) {
|
||||
finishBlackbox();
|
||||
startedLoggingInTestMode = false;
|
||||
}
|
||||
}
|
||||
/**
|
||||
* We are going to monitor the MSP_SET_MOTOR target variables motor_disarmed[] for values other than minthrottle
|
||||
* on reading a value (i.e. the user is testing the motors), then we enable test mode logging;
|
||||
* we monitor when the values return to minthrottle and start a delay timer (5 seconds); if
|
||||
* the test motors are left at minimum throttle for this delay timer, then we assume we are done testing and
|
||||
* shutdown the logger.
|
||||
*
|
||||
* Of course, after the 5 seconds and shutdown of the logger, the system will be re-enabled to allow the
|
||||
* test mode to trigger again; its just that the data will be in a second, third, fourth etc log file.
|
||||
*/
|
||||
bool inMotorTestMode(void) {
|
||||
static uint32_t resetTime = 0;
|
||||
uint16_t inactiveMotorCommand = (feature(FEATURE_3D) ? masterConfig.flight3DConfig.neutral3d : masterConfig.escAndServoConfig.mincommand);
|
||||
int i;
|
||||
bool atLeastOneMotorActivated = false;
|
||||
|
||||
// set disarmed motor values
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
|
||||
atLeastOneMotorActivated |= (motor_disarmed[i] != inactiveMotorCommand);
|
||||
|
||||
if(atLeastOneMotorActivated) {
|
||||
resetTime = millis() + 5000; // add 5 seconds
|
||||
return true;
|
||||
} else {
|
||||
// Monitor the duration at minimum
|
||||
return (millis() < resetTime);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#ifdef GPS
|
||||
static void writeGPSHomeFrame()
|
||||
{
|
||||
|
@ -1536,7 +1591,8 @@ void handleBlackbox(void)
|
|||
break;
|
||||
case BLACKBOX_STATE_RUNNING:
|
||||
// On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
|
||||
if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX)) {
|
||||
// Prevent the Pausing of the log on the mode switch if in Motor Test Mode
|
||||
if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX) && !startedLoggingInTestMode) {
|
||||
blackboxSetState(BLACKBOX_STATE_PAUSED);
|
||||
} else {
|
||||
blackboxLogIteration();
|
||||
|
@ -1565,6 +1621,20 @@ void handleBlackbox(void)
|
|||
// Did we run out of room on the device? Stop!
|
||||
if (isBlackboxDeviceFull()) {
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
// ensure we reset the test mode flag if we stop due to full memory card
|
||||
if (startedLoggingInTestMode) startedLoggingInTestMode = false;
|
||||
} else { // Only log in test mode if there is room!
|
||||
|
||||
if(masterConfig.blackbox_on_motor_test) {
|
||||
// Handle Motor Test Mode
|
||||
if(inMotorTestMode()) {
|
||||
if(blackboxState==BLACKBOX_STATE_STOPPED)
|
||||
startInTestMode();
|
||||
} else {
|
||||
if(blackboxState!=BLACKBOX_STATE_STOPPED)
|
||||
stopInTestMode();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -102,7 +102,6 @@ static uint32_t activeFeaturesLatch = 0;
|
|||
static uint8_t currentControlRateProfileIndex = 0;
|
||||
controlRateConfig_t *currentControlRateProfile;
|
||||
|
||||
|
||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||
{
|
||||
accelerometerTrims->values.pitch = 0;
|
||||
|
@ -609,6 +608,7 @@ void createDefaultConfig(master_t *config)
|
|||
|
||||
config->blackbox_rate_num = 1;
|
||||
config->blackbox_rate_denom = 1;
|
||||
config->blackbox_on_motor_test = 0; // default off
|
||||
#endif // BLACKBOX
|
||||
|
||||
#ifdef SERIALRX_UART
|
||||
|
|
|
@ -159,6 +159,7 @@ typedef struct master_t {
|
|||
uint8_t blackbox_rate_num;
|
||||
uint8_t blackbox_rate_denom;
|
||||
uint8_t blackbox_device;
|
||||
uint8_t blackbox_on_motor_test;
|
||||
#endif
|
||||
|
||||
uint32_t beeper_off_flags;
|
||||
|
|
|
@ -803,11 +803,13 @@ void mixTable(void *pidProfilePtr)
|
|||
if ((rcCommand[THROTTLE] <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Out of band handling
|
||||
throttleMax = flight3DConfig->deadband3d_low;
|
||||
throttleMin = escAndServoConfig->minthrottle;
|
||||
throttlePrevious = throttle = rcCommand[THROTTLE];
|
||||
throttlePrevious = rcCommand[THROTTLE];
|
||||
throttle = rcCommand[THROTTLE] + flight3DConfig->deadband3d_throttle;
|
||||
} else if (rcCommand[THROTTLE] >= (rxConfig->midrc + flight3DConfig->deadband3d_throttle)) { // Positive handling
|
||||
throttleMax = escAndServoConfig->maxthrottle;
|
||||
throttleMin = flight3DConfig->deadband3d_high;
|
||||
throttlePrevious = throttle = rcCommand[THROTTLE];
|
||||
throttlePrevious = rcCommand[THROTTLE];
|
||||
throttle = rcCommand[THROTTLE] - flight3DConfig->deadband3d_throttle;
|
||||
} else if ((throttlePrevious <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Deadband handling from negative to positive
|
||||
throttle = throttleMax = flight3DConfig->deadband3d_low;
|
||||
throttleMin = escAndServoConfig->minthrottle;
|
||||
|
|
|
@ -326,13 +326,11 @@ bool parseLedStripConfig(int ledIndex, const char *config)
|
|||
return true;
|
||||
}
|
||||
|
||||
void generateLedConfig(int ledIndex, char *ledConfigBuffer, size_t bufferSize)
|
||||
void generateLedConfig(ledConfig_t *ledConfig, char *ledConfigBuffer, size_t bufferSize)
|
||||
{
|
||||
char directions[LED_DIRECTION_COUNT + 1];
|
||||
char baseFunctionOverlays[LED_OVERLAY_COUNT + 2];
|
||||
|
||||
ledConfig_t *ledConfig = &masterConfig.ledConfigs[ledIndex];
|
||||
|
||||
memset(ledConfigBuffer, 0, bufferSize);
|
||||
|
||||
char *dptr = directions;
|
||||
|
|
|
@ -160,7 +160,7 @@ PG_DECLARE(specialColorIndexes_t, specialColors);
|
|||
bool parseColor(int index, const char *colorConfig);
|
||||
|
||||
bool parseLedStripConfig(int ledIndex, const char *config);
|
||||
void generateLedConfig(int ledIndex, char *ledConfigBuffer, size_t bufferSize);
|
||||
void generateLedConfig(ledConfig_t *ledConfig, char *ledConfigBuffer, size_t bufferSize);
|
||||
void reevaluateLedConfig(void);
|
||||
|
||||
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, modeColorIndexes_t *modeColorsToUse, specialColorIndexes_t *specialColorsToUse);
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -91,7 +91,7 @@
|
|||
#define VBAT_ADC_PIN PA0
|
||||
#define RSSI_ADC_PIN PB0
|
||||
|
||||
//#define LED_STRIP
|
||||
#define LED_STRIP
|
||||
#define WS2811_PIN PB4
|
||||
#define WS2811_TIMER TIM3
|
||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
||||
|
@ -108,15 +108,16 @@
|
|||
//#define SONAR_TRIGGER_PIN PB5
|
||||
|
||||
#undef GPS
|
||||
#define CLI_MINIMAL_VERBOSITY
|
||||
#undef MAG
|
||||
|
||||
#ifdef CC3D_OPBL
|
||||
#undef LED_STRIP
|
||||
#define SKIP_CLI_COMMAND_HELP
|
||||
#define SKIP_PID_FLOAT
|
||||
#undef BARO
|
||||
#undef MAG
|
||||
#undef SONAR
|
||||
#undef USE_SOFTSERIAL1
|
||||
#undef LED_STRIP
|
||||
#endif
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
|
|
|
@ -143,7 +143,6 @@
|
|||
#define RSSI_ADC_PIN PA1
|
||||
#define EXTERNAL1_ADC_PIN PA5
|
||||
|
||||
|
||||
#define LED_STRIP
|
||||
#define WS2811_TIMER TIM3
|
||||
#define WS2811_PIN PA6
|
||||
|
|
Loading…
Reference in New Issue