mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
Merge branch 'lock_active_features' of https://github.com/ProDrone/cleanflight into ProDrone-lock_active_features
Conflicts: src/test/unit/rc_controls_unittest.cc
This commit is contained in:
commit
0c1a6c5c2f
12 changed files with 79 additions and 10 deletions
|
@ -134,6 +134,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
|||
|
||||
master_t masterConfig; // master config struct with data independent from profiles
|
||||
profile_t *currentProfile;
|
||||
static uint32_t activeFeaturesLatch = 0;
|
||||
|
||||
static uint8_t currentControlRateProfileIndex = 0;
|
||||
controlRateConfig_t *currentControlRateProfile;
|
||||
|
@ -725,26 +726,26 @@ void activateConfig(void)
|
|||
|
||||
void validateAndFixConfig(void)
|
||||
{
|
||||
if (!(feature(FEATURE_RX_PARALLEL_PWM) || feature(FEATURE_RX_PPM) || feature(FEATURE_RX_SERIAL) || feature(FEATURE_RX_MSP))) {
|
||||
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) {
|
||||
featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM
|
||||
}
|
||||
|
||||
if (feature(FEATURE_RX_PPM)) {
|
||||
if (featureConfigured(FEATURE_RX_PPM)) {
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
if (featureConfigured(FEATURE_RX_MSP)) {
|
||||
featureClear(FEATURE_RX_SERIAL);
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
featureClear(FEATURE_RX_PPM);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_RX_SERIAL)) {
|
||||
if (featureConfigured(FEATURE_RX_SERIAL)) {
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
featureClear(FEATURE_RX_PPM);
|
||||
}
|
||||
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
|
||||
#if defined(STM32F10X)
|
||||
// rssi adc needs the same ports
|
||||
featureClear(FEATURE_RSSI_ADC);
|
||||
|
@ -765,7 +766,7 @@ void validateAndFixConfig(void)
|
|||
|
||||
|
||||
#if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
|
||||
if (feature(FEATURE_SOFTSERIAL) && (
|
||||
if (featureConfigured(FEATURE_SOFTSERIAL) && (
|
||||
0
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
|| (LED_STRIP_TIMER == SOFTSERIAL_1_TIMER)
|
||||
|
@ -780,7 +781,7 @@ void validateAndFixConfig(void)
|
|||
#endif
|
||||
|
||||
#if defined(NAZE) && defined(SONAR)
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM) && feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
}
|
||||
#endif
|
||||
|
@ -944,11 +945,32 @@ void changeControlRateProfile(uint8_t profileIndex)
|
|||
activateControlRateConfig();
|
||||
}
|
||||
|
||||
bool feature(uint32_t mask)
|
||||
void handleOneshotFeatureChangeOnRestart(void)
|
||||
{
|
||||
// Shutdown PWM on all motors prior to soft restart
|
||||
StopPwmAllMotors();
|
||||
delay(50);
|
||||
// Apply additional delay when OneShot125 feature changed from on to off state
|
||||
if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) {
|
||||
delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS);
|
||||
}
|
||||
}
|
||||
|
||||
void latchActiveFeatures()
|
||||
{
|
||||
activeFeaturesLatch = masterConfig.enabledFeatures;
|
||||
}
|
||||
|
||||
bool featureConfigured(uint32_t mask)
|
||||
{
|
||||
return masterConfig.enabledFeatures & mask;
|
||||
}
|
||||
|
||||
bool feature(uint32_t mask)
|
||||
{
|
||||
return activeFeaturesLatch & mask;
|
||||
}
|
||||
|
||||
void featureSet(uint32_t mask)
|
||||
{
|
||||
masterConfig.enabledFeatures |= mask;
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
|
||||
#define MAX_PROFILE_COUNT 3
|
||||
#define MAX_CONTROL_RATE_PROFILE_COUNT 3
|
||||
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
|
||||
|
||||
|
||||
typedef enum {
|
||||
|
@ -44,6 +45,9 @@ typedef enum {
|
|||
FEATURE_BLACKBOX = 1 << 19
|
||||
} features_e;
|
||||
|
||||
void handleOneshotFeatureChangeOnRestart(void);
|
||||
void latchActiveFeatures(void);
|
||||
bool featureConfigured(uint32_t mask);
|
||||
bool feature(uint32_t mask);
|
||||
void featureSet(uint32_t mask);
|
||||
void featureClear(uint32_t mask);
|
||||
|
|
|
@ -543,7 +543,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
channelIndex++;
|
||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||
if (init->useOneshot) {
|
||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->idlePulse);
|
||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, 0);
|
||||
} else if (init->motorPwmRate > 500) {
|
||||
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
||||
} else {
|
||||
|
|
|
@ -142,6 +142,16 @@ void pwmWriteMotor(uint8_t index, uint16_t value)
|
|||
motors[index]->pwmWritePtr(index, value);
|
||||
}
|
||||
|
||||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
|
||||
{
|
||||
uint8_t index;
|
||||
|
||||
for(index = 0; index < motorCount; index++){
|
||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
||||
*motors[index]->ccr = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
|
||||
{
|
||||
uint8_t index;
|
||||
|
|
|
@ -18,6 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
void pwmWriteMotor(uint8_t index, uint16_t value);
|
||||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
|
||||
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount);
|
||||
|
||||
void pwmWriteServo(uint8_t index, uint16_t value);
|
||||
|
|
|
@ -513,6 +513,11 @@ void stopMotors(void)
|
|||
delay(50); // give the timers and ESCs a chance to react.
|
||||
}
|
||||
|
||||
void StopPwmAllMotors()
|
||||
{
|
||||
pwmShutdownPulsesForAllMotors(motorCount);
|
||||
}
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
static void airplaneMixer(void)
|
||||
{
|
||||
|
|
|
@ -115,3 +115,4 @@ void mixerResetMotors(void);
|
|||
void mixTable(void);
|
||||
void writeMotors(void);
|
||||
void stopMotors(void);
|
||||
void StopPwmAllMotors(void);
|
||||
|
|
|
@ -1410,6 +1410,7 @@ static void cliReboot(void) {
|
|||
cliPrint("\r\nRebooting");
|
||||
waitForSerialPortToFinishTransmitting(cliPort);
|
||||
stopMotors();
|
||||
handleOneshotFeatureChangeOnRestart();
|
||||
systemReset();
|
||||
}
|
||||
|
||||
|
|
|
@ -1748,6 +1748,7 @@ void mspProcess(void)
|
|||
delay(50);
|
||||
}
|
||||
stopMotors();
|
||||
handleOneshotFeatureChangeOnRestart();
|
||||
systemReset();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -91,6 +91,7 @@
|
|||
#include "debug.h"
|
||||
|
||||
extern uint32_t previousTime;
|
||||
extern uint8_t motorControlEnable;
|
||||
|
||||
#ifdef SOFTSERIAL_LOOPBACK
|
||||
serialPort_t *loopbackPort;
|
||||
|
@ -171,6 +172,9 @@ void init(void)
|
|||
|
||||
systemInit();
|
||||
|
||||
// Latch active features to be used for feature() in the remainder of init().
|
||||
latchActiveFeatures();
|
||||
|
||||
ledInit();
|
||||
|
||||
#ifdef SPEKTRUM_BIND
|
||||
|
@ -256,6 +260,9 @@ void init(void)
|
|||
|
||||
mixerUsePWMOutputConfiguration(pwmOutputConfiguration);
|
||||
|
||||
if (!feature(FEATURE_ONESHOT125))
|
||||
motorControlEnable = true;
|
||||
|
||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||
|
||||
#ifdef BEEPER
|
||||
|
@ -481,6 +488,10 @@ void init(void)
|
|||
LED2_ON;
|
||||
#endif
|
||||
|
||||
// Latch active features AGAIN since some may be modified by init().
|
||||
latchActiveFeatures();
|
||||
motorControlEnable = true;
|
||||
|
||||
systemState |= SYSTEM_STATE_READY;
|
||||
}
|
||||
|
||||
|
|
|
@ -97,6 +97,8 @@ uint16_t cycleTime = 0; // this is the number in micro second to achieve
|
|||
int16_t magHold;
|
||||
int16_t headFreeModeHold;
|
||||
|
||||
uint8_t motorControlEnable = false;
|
||||
|
||||
int16_t telemTemperature1; // gyro sensor temperature
|
||||
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||
|
||||
|
@ -801,7 +803,9 @@ void loop(void)
|
|||
writeServos();
|
||||
#endif
|
||||
|
||||
if (motorControlEnable) {
|
||||
writeMotors();
|
||||
}
|
||||
|
||||
#ifdef BLACKBOX
|
||||
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
||||
|
|
|
@ -315,6 +315,15 @@ void pwmWriteMotor(uint8_t index, uint16_t value) {
|
|||
motors[index].value = value;
|
||||
}
|
||||
|
||||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
|
||||
{
|
||||
uint8_t index;
|
||||
|
||||
for(index = 0; index < motorCount; index++){
|
||||
motors[index].value = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) {
|
||||
lastOneShotUpdateMotorCount = motorCount;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue