mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 08:45:36 +03:00
Merge branch 'master' of https://github.com/betaflight/betaflight
This commit is contained in:
commit
8d3c90a87f
14 changed files with 79 additions and 53 deletions
|
@ -92,7 +92,9 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
int i = 0;
|
||||
const uint16_t *setup;
|
||||
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
int channelIndex = 0;
|
||||
#endif
|
||||
|
||||
memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration));
|
||||
|
||||
|
@ -289,15 +291,19 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
#endif
|
||||
|
||||
if (type == MAP_TO_PPM_INPUT) {
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
|
||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
|
||||
}
|
||||
#endif
|
||||
ppmInConfig(timerHardwarePtr);
|
||||
#endif
|
||||
} else if (type == MAP_TO_PWM_INPUT) {
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
pwmInConfig(timerHardwarePtr, channelIndex);
|
||||
channelIndex++;
|
||||
#endif
|
||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||
|
||||
#ifdef CC3D
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
|
||||
#include "build_config.h"
|
||||
#include "debug.h"
|
||||
|
||||
|
@ -419,3 +421,4 @@ uint16_t pwmRead(uint8_t channel)
|
|||
{
|
||||
return captures[channel];
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -477,7 +477,7 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU
|
|||
|
||||
adjustmentState_t adjustmentStates[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT];
|
||||
|
||||
void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adjustmentConfig_t *adjustmentConfig) {
|
||||
static void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adjustmentConfig_t *adjustmentConfig) {
|
||||
adjustmentState_t *adjustmentState = &adjustmentStates[index];
|
||||
|
||||
if (adjustmentState->config == adjustmentConfig) {
|
||||
|
@ -491,7 +491,7 @@ void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adj
|
|||
MARK_ADJUSTMENT_FUNCTION_AS_READY(index);
|
||||
}
|
||||
|
||||
void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustmentFunction, int delta) {
|
||||
static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustmentFunction, int delta) {
|
||||
int newValue;
|
||||
|
||||
if (delta > 0) {
|
||||
|
@ -600,7 +600,7 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm
|
|||
};
|
||||
}
|
||||
|
||||
void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
||||
static void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
||||
{
|
||||
bool applied = false;
|
||||
|
||||
|
|
|
@ -249,7 +249,6 @@ typedef struct adjustmentState_s {
|
|||
bool isAirmodeActive(void);
|
||||
bool isSuperExpoActive(void);
|
||||
void resetAdjustmentStates(void);
|
||||
void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmentConfig_t *adjustmentConfig);
|
||||
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
|
||||
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig);
|
||||
|
||||
|
|
|
@ -469,6 +469,7 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = {
|
|||
"PIDLOOP",
|
||||
"NOTCH",
|
||||
};
|
||||
|
||||
#ifdef OSD
|
||||
static const char * const lookupTableOsdType[] = {
|
||||
"AUTO",
|
||||
|
@ -2964,7 +2965,7 @@ static void cliStatus(char *cmdline)
|
|||
|
||||
cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
|
||||
|
||||
#ifndef CJMCU
|
||||
#if (FLASH_SIZE > 64)
|
||||
uint8_t i;
|
||||
uint32_t mask;
|
||||
uint32_t detectedSensorsMask = sensorsMask();
|
||||
|
@ -3007,45 +3008,45 @@ static void cliStatus(char *cmdline)
|
|||
static void cliTasks(char *cmdline)
|
||||
{
|
||||
UNUSED(cmdline);
|
||||
int maxLoadSum = 0;
|
||||
int averageLoadSum = 0;
|
||||
|
||||
cfTaskId_e taskId;
|
||||
cfTaskInfo_t taskInfo;
|
||||
|
||||
cliPrintf("Task list:\r\n");
|
||||
for (taskId = 0; taskId < TASK_COUNT; taskId++) {
|
||||
cliPrintf("Task list max/us avg/us rate/hz maxload avgload total/ms\r\n");
|
||||
for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; taskId++) {
|
||||
cfTaskInfo_t taskInfo;
|
||||
getTaskInfo(taskId, &taskInfo);
|
||||
if (taskInfo.isEnabled) {
|
||||
uint16_t taskFrequency;
|
||||
uint16_t subTaskFrequency;
|
||||
|
||||
uint32_t taskTotalTime = taskInfo.totalExecutionTime / 1000;
|
||||
int taskFrequency;
|
||||
int subTaskFrequency;
|
||||
|
||||
if (taskId == TASK_GYROPID) {
|
||||
subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f));
|
||||
taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
|
||||
if (masterConfig.pid_process_denom > 1) {
|
||||
taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
|
||||
cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%12s) ", taskId, taskInfo.taskName);
|
||||
} else {
|
||||
taskFrequency = subTaskFrequency;
|
||||
cliPrintf("%02d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%8s/%3s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
|
||||
}
|
||||
} else {
|
||||
taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
|
||||
cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName);
|
||||
cliPrintf("%02d - (%12s) ", taskId, taskInfo.taskName);
|
||||
}
|
||||
|
||||
cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency);
|
||||
|
||||
if (taskTotalTime >= 1000) {
|
||||
cliPrintf("%dsec", taskTotalTime / 1000);
|
||||
} else {
|
||||
cliPrintf("%dms", taskTotalTime);
|
||||
const int maxLoad = (taskInfo.maxExecutionTime * taskFrequency + 5000) / 1000;
|
||||
const int averageLoad = (taskInfo.averageExecutionTime * taskFrequency + 5000) / 1000;
|
||||
if (taskId != TASK_SERIAL) {
|
||||
maxLoadSum += maxLoad;
|
||||
averageLoadSum += averageLoad;
|
||||
}
|
||||
cliPrintf("%6d %5d %5d %4d.%1d%% %4d.%1d%% %8d\r\n",
|
||||
taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency,
|
||||
maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10, taskInfo.totalExecutionTime / 1000);
|
||||
if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) {
|
||||
cliPrintf(" - (%12s) rate: %d\r\n", taskInfo.subTaskName, subTaskFrequency);
|
||||
}
|
||||
|
||||
if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n - - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
|
||||
cliPrintf("\r\n", taskTotalTime);
|
||||
}
|
||||
}
|
||||
cliPrintf("Total (excluding SERIAL) %22d.%1d%% %4d.%1d%%\r\n", maxLoadSum/10, maxLoadSum%10, averageLoadSum/10, averageLoadSum%10);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -517,12 +517,15 @@ void mspInit(serialConfig_t *serialConfig)
|
|||
|
||||
activeBoxIds[activeBoxIdCount++] = BOXOSD;
|
||||
|
||||
#ifdef TELEMETRY
|
||||
if (feature(FEATURE_TELEMETRY) && masterConfig.telemetryConfig.telemetry_switch)
|
||||
activeBoxIds[activeBoxIdCount++] = BOXTELEMETRY;
|
||||
|
||||
#endif
|
||||
#ifdef SONAR
|
||||
if (feature(FEATURE_SONAR)){
|
||||
activeBoxIds[activeBoxIdCount++] = BOXSONAR;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
if (masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE) {
|
||||
|
@ -1296,6 +1299,7 @@ static bool processInCommand(void)
|
|||
magHold = read16();
|
||||
break;
|
||||
case MSP_SET_RAW_RC:
|
||||
#ifndef SKIP_RX_MSP
|
||||
{
|
||||
uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t);
|
||||
if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT) {
|
||||
|
@ -1310,6 +1314,7 @@ static bool processInCommand(void)
|
|||
rxMspFrameReceive(frame, channelCount);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case MSP_SET_ACC_TRIM:
|
||||
masterConfig.accelerometerTrims.values.pitch = read16();
|
||||
|
|
|
@ -327,7 +327,9 @@ void init(void)
|
|||
#ifdef CC3D
|
||||
pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false;
|
||||
#endif
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
pwmRxInit(masterConfig.inputFilteringMode);
|
||||
#endif
|
||||
|
||||
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
|
||||
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
|
||||
|
@ -688,21 +690,21 @@ void main_init(void)
|
|||
rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
|
||||
setTaskEnabled(TASK_GYROPID, true);
|
||||
|
||||
if(sensors(SENSOR_ACC)) {
|
||||
if (sensors(SENSOR_ACC)) {
|
||||
setTaskEnabled(TASK_ACCEL, true);
|
||||
switch(gyro.targetLooptime) { // Switch statement kept in place to change acc rates in the future
|
||||
case(500):
|
||||
case(375):
|
||||
case(250):
|
||||
case(125):
|
||||
accTargetLooptime = 1000;
|
||||
break;
|
||||
default:
|
||||
case(1000):
|
||||
switch (gyro.targetLooptime) { // Switch statement kept in place to change acc rates in the future
|
||||
case 500:
|
||||
case 375:
|
||||
case 250:
|
||||
case 125:
|
||||
accTargetLooptime = 1000;
|
||||
break;
|
||||
default:
|
||||
case 1000:
|
||||
#ifdef STM32F10X
|
||||
accTargetLooptime = 3000;
|
||||
accTargetLooptime = 1000;
|
||||
#else
|
||||
accTargetLooptime = 1000;
|
||||
accTargetLooptime = 1000;
|
||||
#endif
|
||||
}
|
||||
rescheduleTask(TASK_ACCEL, accTargetLooptime);
|
||||
|
|
|
@ -451,7 +451,7 @@ void handleInflightCalibrationStickPosition(void)
|
|||
}
|
||||
}
|
||||
|
||||
void updateInflightCalibrationState(void)
|
||||
static void updateInflightCalibrationState(void)
|
||||
{
|
||||
if (AccInflightCalibrationArmed && ARMING_FLAG(ARMED) && rcData[THROTTLE] > masterConfig.rxConfig.mincheck && !IS_RC_MODE_ACTIVE(BOXARM)) { // Copter is airborne and you are turning it off via boxarm : start measurement
|
||||
InflightcalibratingA = 50;
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifndef SKIP_RX_MSP
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
@ -71,3 +73,4 @@ void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadR
|
|||
if (callback)
|
||||
*callback = rxMspReadRawRC;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -21,10 +21,12 @@
|
|||
|
||||
#include <string.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
|
@ -59,4 +61,5 @@ void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfigPtr, rcReadRawDataPtr *callback
|
|||
*callback = ppmReadRawRC;
|
||||
}
|
||||
}
|
||||
#endif // SKIP_RX_PWM_PPM
|
||||
|
||||
|
|
|
@ -189,14 +189,18 @@ void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationCondi
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifndef SKIP_RX_MSP
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
rxRefreshRate = 20000;
|
||||
rxPwmInit(&rxRuntimeConfig, &rcReadRawFunc);
|
||||
}
|
||||
#endif
|
||||
|
||||
rxRuntimeConfig.auxChannelCount = rxRuntimeConfig.channelCount - STICK_CHANNEL_COUNT;
|
||||
}
|
||||
|
@ -349,16 +353,18 @@ void updateRx(uint32_t currentTime)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifndef SKIP_RX_MSP
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
rxDataReceived = rxMspFrameComplete();
|
||||
|
||||
if (rxDataReceived) {
|
||||
rxSignalReceived = true;
|
||||
rxIsInFailsafeMode = false;
|
||||
needRxSignalBefore = currentTime + DELAY_5_HZ;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
if (feature(FEATURE_RX_PPM)) {
|
||||
if (isPPMDataBeingReceived()) {
|
||||
rxSignalReceivedNotDataDriven = true;
|
||||
|
@ -375,7 +381,7 @@ void updateRx(uint32_t currentTime)
|
|||
needRxSignalBefore = currentTime + DELAY_10_HZ;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
bool shouldProcessRx(uint32_t currentTime)
|
||||
|
|
|
@ -43,7 +43,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
[TASK_ACCEL] = {
|
||||
.taskName = "ACCEL",
|
||||
.taskFunc = taskUpdateAccelerometer,
|
||||
.desiredPeriod = 1000000 / 100, // every 10ms
|
||||
.desiredPeriod = 1000000 / 1000, // every 1ms
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
|
||||
|
|
|
@ -72,12 +72,8 @@
|
|||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART3
|
||||
#ifdef CC3D_OPBL
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
#else
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART1_RX_DMA
|
||||
#undef USE_UART1_RX_DMA
|
||||
|
@ -116,6 +112,7 @@
|
|||
#ifdef CC3D_OPBL
|
||||
//#undef LED_STRIP
|
||||
#define SKIP_CLI_COMMAND_HELP
|
||||
#define SKIP_PID_FLOAT
|
||||
#undef BARO
|
||||
#undef MAG
|
||||
#undef SONAR
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM12 | (MAP_TO_PPM_INPUT << 8),
|
||||
PWM7 | (MAP_TO_PPM_INPUT << 8),
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
|
@ -30,8 +30,10 @@ const uint16_t multiPPM[] = {
|
|||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
@ -42,7 +44,6 @@ const uint16_t multiPWM[] = {
|
|||
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
|
||||
PWM7 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM8 | (MAP_TO_PWM_INPUT << 8),
|
||||
PWM9 | (MAP_TO_PWM_INPUT << 8),
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue