mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 11:59:58 +03:00
trailing whitespace removal (#14026)
trailing space removal Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
This commit is contained in:
parent
0de6278433
commit
493b9bf819
78 changed files with 371 additions and 371 deletions
|
@ -732,7 +732,7 @@ static void writeIntraframe(void)
|
|||
for (unsigned x = 0; x < ARRAYLEN(servo); ++x) {
|
||||
out[x] = blackboxCurrent->servo[x] - 1500;
|
||||
}
|
||||
|
||||
|
||||
blackboxWriteTag8_8SVB(out, ARRAYLEN(out));
|
||||
}
|
||||
#endif
|
||||
|
@ -890,12 +890,12 @@ static void writeInterframe(void)
|
|||
|
||||
#ifdef USE_SERVOS
|
||||
if (testBlackboxCondition(CONDITION(SERVOS))) {
|
||||
STATIC_ASSERT(ARRAYLEN(servo) <= 8, "TAG8_8SVB supports at most 8 values");
|
||||
STATIC_ASSERT(ARRAYLEN(servo) <= 8, "TAG8_8SVB supports at most 8 values");
|
||||
int32_t out[ARRAYLEN(servo)];
|
||||
for (unsigned x = 0; x < ARRAYLEN(servo); ++x) {
|
||||
out[x] = blackboxCurrent->servo[x] - blackboxLast->servo[x];
|
||||
}
|
||||
|
||||
|
||||
blackboxWriteTag8_8SVB(out, ARRAYLEN(out));
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -752,10 +752,10 @@ blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes)
|
|||
}
|
||||
|
||||
int8_t blackboxGetLogFileNo(void)
|
||||
{
|
||||
{
|
||||
#ifdef USE_BLACKBOX
|
||||
#ifdef USE_SDCARD
|
||||
// return current file number or -1
|
||||
// return current file number or -1
|
||||
if (blackboxSDCard.state == BLACKBOX_SDCARD_READY_TO_LOG) {
|
||||
return blackboxSDCard.largestLogFileNumber;
|
||||
} else {
|
||||
|
@ -765,6 +765,6 @@ int8_t blackboxGetLogFileNo(void)
|
|||
// will be implemented later for flash based storage
|
||||
return -1;
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif // BLACKBOX
|
||||
|
|
|
@ -5019,7 +5019,7 @@ static void cliRcSmoothing(const char *cmdName, char *cmdline)
|
|||
if (getRxRateValid()) {
|
||||
cliPrintLinef("%dHz", lrintf(rcSmoothingData->smoothedRxRateHz));
|
||||
} else {
|
||||
cliPrintLine("NO SIGNAL");
|
||||
cliPrintLine("NO SIGNAL");
|
||||
}
|
||||
}
|
||||
cliPrintf("# Active setpoint cutoff: %dhz ", rcSmoothingData->setpointCutoffFrequency);
|
||||
|
|
|
@ -692,7 +692,7 @@ static bool rowIsSkippable(const OSD_Entry *row)
|
|||
if (type == OME_String) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
if ((type == OME_UINT8 || type == OME_INT8 ||
|
||||
type == OME_UINT16 || type == OME_INT16) &&
|
||||
((row->flags == DYNAMIC) || rowSliderOverride(row->flags))) {
|
||||
|
|
|
@ -45,11 +45,11 @@ float pwlInterpolate(const pwl_t *pwl, float x)
|
|||
if (x <= pwl->xMin) {
|
||||
return pwl->yValues[0];
|
||||
}
|
||||
|
||||
|
||||
if (x >= pwl->xMax) {
|
||||
return pwl->yValues[pwl->numPoints - 1];
|
||||
}
|
||||
|
||||
|
||||
const int index = (int)((x - pwl->xMin) / pwl->dx);
|
||||
if (index >= pwl->numPoints - 1) {
|
||||
return pwl->yValues[pwl->numPoints - 1];
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/sdft.h"
|
||||
|
||||
#define SDFT_R 0.9999f // damping factor for guaranteed SDFT stability (r < 1.0f)
|
||||
#define SDFT_R 0.9999f // damping factor for guaranteed SDFT stability (r < 1.0f)
|
||||
|
||||
static FAST_DATA_ZERO_INIT float rPowerN; // SDFT_R to the power of SDFT_SAMPLE_SIZE
|
||||
static FAST_DATA_ZERO_INIT bool isInitialized;
|
||||
|
|
|
@ -593,7 +593,7 @@ void validateAndFixGyroConfig(void)
|
|||
*/
|
||||
if (true
|
||||
#ifdef USE_PID_DENOM_OVERCLOCK_LEVEL
|
||||
&& (systemConfig()->cpu_overclock < USE_PID_DENOM_OVERCLOCK_LEVEL)
|
||||
&& (systemConfig()->cpu_overclock < USE_PID_DENOM_OVERCLOCK_LEVEL)
|
||||
#endif
|
||||
&& motorConfig()->dev.useDshotTelemetry
|
||||
) {
|
||||
|
|
|
@ -52,9 +52,9 @@ static void calculateNewPidValues(pidProfile_t *pidProfile)
|
|||
pidProfile->pid[axis].I = constrain(pidDefaults[axis].I * masterMultiplier * piGain * iGain * pitchPiGain, 0, PID_GAIN_MAX);
|
||||
pidProfile->pid[axis].D = constrain(pidDefaults[axis].D * masterMultiplier * dGain * pitchDGain, 0, PID_GAIN_MAX);
|
||||
pidProfile->pid[axis].F = constrain(pidDefaults[axis].F * masterMultiplier * pitchPiGain * feedforwardGain, 0, F_GAIN_MAX);
|
||||
|
||||
|
||||
#ifdef USE_D_MAX
|
||||
const float dMaxGain = (dMaxDefaults[axis] > 0)
|
||||
const float dMaxGain = (dMaxDefaults[axis] > 0)
|
||||
? pidProfile->simplified_d_max_gain / 100.0f + (1 - pidProfile->simplified_d_max_gain / 100.0f) * pidDefaults[axis].D / dMaxDefaults[axis]
|
||||
: 1.0f;
|
||||
pidProfile->d_max[axis] = constrain(dMaxDefaults[axis] * masterMultiplier * dGain * pitchDGain * dMaxGain, 0, PID_GAIN_MAX);
|
||||
|
|
|
@ -122,7 +122,7 @@ typedef enum {
|
|||
|
||||
BMI270_VAL_INT_MAP_DATA_DRDY_INT1 = 0x04,// enable the data ready interrupt pin 1
|
||||
BMI270_VAL_INT_MAP_FIFO_WM_INT1 = 0x02, // enable the FIFO watermark interrupt pin 1
|
||||
BMI270_VAL_INT1_IO_CTRL_PINMODE = 0x0A, // active high, push-pull, output enabled, input disabled
|
||||
BMI270_VAL_INT1_IO_CTRL_PINMODE = 0x0A, // active high, push-pull, output enabled, input disabled
|
||||
BMI270_VAL_FIFO_CONFIG_0 = 0x00, // don't stop when full, disable sensortime frame
|
||||
BMI270_VAL_FIFO_CONFIG_1 = 0x80, // only gyro data in FIFO, use headerless mode
|
||||
BMI270_VAL_FIFO_DOWNS = 0x00, // select unfiltered gyro data with no downsampling (6.4KHz samples)
|
||||
|
|
|
@ -91,7 +91,7 @@
|
|||
#define ICM426XX_RA_ACCEL_CONFIG_STATIC4 0x05 // User Bank 2
|
||||
// --- Register & setting for gyro and acc UI Filter --------
|
||||
#define ICM426XX_RA_GYRO_ACCEL_CONFIG0 0x52 // User Bank 0
|
||||
#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (15 << 4)
|
||||
#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (15 << 4)
|
||||
#define ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY (15 << 0)
|
||||
// ----------------------------------------------------------
|
||||
|
||||
|
|
|
@ -144,7 +144,7 @@ uint8_t l3gd20Detect(const extDevice_t *dev)
|
|||
|
||||
return L3GD20_SPI; // blindly assume it's present, for now.
|
||||
}
|
||||
|
||||
|
||||
bool l3gd20GyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
gyro->initFn = l3gd20GyroInit;
|
||||
|
|
|
@ -132,16 +132,16 @@ int32_t adcTSSlopeK;
|
|||
|
||||
/**
|
||||
* Use a measurement of the fixed internal vref to calculate the external Vref+
|
||||
*
|
||||
*
|
||||
* The ADC full range reading equates to Vref+ on the channel. Vref+ is typically
|
||||
* fed from Vcc at 3.3V, but since Vcc isn't a critical value it may be off
|
||||
* by a little due to variation in the regulator. Some chips are provided with a
|
||||
* by a little due to variation in the regulator. Some chips are provided with a
|
||||
* known internal voltage reference, typically around 1.2V. By measuring this
|
||||
* reference with an internally connected ADC channel we can then calculate a more
|
||||
* reference with an internally connected ADC channel we can then calculate a more
|
||||
* accurate value for Vref+ instead of assuming that it is 3.3V
|
||||
*
|
||||
*
|
||||
* @param intVRefAdcValue reading from the internal calibration voltage
|
||||
*
|
||||
*
|
||||
* @return the calculated value of Vref+
|
||||
*/
|
||||
uint16_t adcInternalCompensateVref(uint16_t intVRefAdcValue)
|
||||
|
|
|
@ -223,7 +223,7 @@ static bool deviceConfigure(const extDevice_t *dev)
|
|||
baroState.calib.c40 = getTwosComplement((((uint32_t)coef[19] & 0x0F) << 8) | (uint32_t)coef[20], 12);
|
||||
} else {
|
||||
baroState.calib.c31 = 0;
|
||||
baroState.calib.c40 = 0;
|
||||
baroState.calib.c40 = 0;
|
||||
}
|
||||
|
||||
// PRS_CFG: pressure measurement rate (32 Hz) and oversampling (16 time standard)
|
||||
|
@ -306,7 +306,7 @@ static bool dps310GetUP(baroDev_t *baro)
|
|||
static void deviceCalculate(int32_t *pressure, int32_t *temperature)
|
||||
{
|
||||
if (pressure) {
|
||||
*pressure = baroState.pressure;
|
||||
*pressure = baroState.pressure;
|
||||
}
|
||||
|
||||
if (temperature) {
|
||||
|
|
|
@ -124,7 +124,7 @@ static bool ist8310Init(magDev_t *magDev)
|
|||
bool ack = busWriteRegister(dev, IST8310_REG_AVERAGE, IST8310_AVG_16);
|
||||
delay(6);
|
||||
ack = ack && busWriteRegister(dev, IST8310_REG_PDCNTL, IST8310_PULSE_DURATION_NORMAL);
|
||||
delay(6);
|
||||
delay(6);
|
||||
ack = ack && busWriteRegister(dev, IST8310_REG_CNTRL1, IST8310_ODR_SINGLE);
|
||||
|
||||
magDev->magOdrHz = 100;
|
||||
|
|
|
@ -255,7 +255,7 @@ typedef enum {
|
|||
// Missing __HAL_DMA_SET_COUNTER in FW library V1.0.0
|
||||
#define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNDTR = (uint16_t)(__COUNTER__))
|
||||
#elif defined(AT32F4)
|
||||
#define DMA_CCR_EN 1
|
||||
#define DMA_CCR_EN 1
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->ctrl_bit.chen & DMA_CCR_EN)
|
||||
#elif defined(APM32F4)
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->SCFG & DMA_SCFGx_EN)
|
||||
|
|
|
@ -74,7 +74,7 @@ motorDevice_t *dshotPwmDevInit(const struct motorDevConfig_s *motorConfig, uint1
|
|||
#define DSHOT_DMA_BUFFER_ATTRIBUTE // None
|
||||
#endif
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F435) || defined(APM32F4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F435) || defined(APM32F4)
|
||||
#define DSHOT_DMA_BUFFER_UNIT uint32_t
|
||||
#else
|
||||
#define DSHOT_DMA_BUFFER_UNIT uint8_t
|
||||
|
|
|
@ -358,7 +358,7 @@ MMFLASH_CODE static void w25q128fv_eraseSector(flashDevice_t *fdevice, uint32_t
|
|||
w25q128fv_writeEnable(fdevice);
|
||||
|
||||
w25q128fv_performCommandWithAddress(&fdevice->io, W25Q128FV_INSTRUCTION_BLOCK_ERASE_64KB, address);
|
||||
|
||||
|
||||
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_BLOCK_ERASE_64KB_MS);
|
||||
}
|
||||
|
||||
|
|
|
@ -82,11 +82,11 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
|
|||
|
||||
/**
|
||||
* Prepare to send dshot data for one motor
|
||||
*
|
||||
*
|
||||
* Formats the value into the appropriate dma buffer and enables the dma channel.
|
||||
* The packet won't start transmitting until later since the dma requests from the timer
|
||||
* are disabled when this function is called.
|
||||
*
|
||||
*
|
||||
* @param index index of the motor that the data is to be sent to
|
||||
* @param value the dshot value to be sent
|
||||
*/
|
||||
|
@ -197,7 +197,7 @@ static uint32_t decodeTelemetryPacket(const uint32_t buffer[], uint32_t count)
|
|||
#ifdef USE_DSHOT_TELEMETRY
|
||||
/**
|
||||
* Process dshot telemetry packets before switching the channels back to outputs
|
||||
*
|
||||
*
|
||||
*/
|
||||
FAST_CODE_NOINLINE bool pwmTelemetryDecode(void)
|
||||
{
|
||||
|
|
|
@ -71,7 +71,7 @@ static int32_t mtRangefinderGetDistance(rangefinderDev_t * dev) {
|
|||
}
|
||||
}
|
||||
|
||||
bool mtRangefinderDetect(rangefinderDev_t * dev, rangefinderType_e mtRangefinderToUse) {
|
||||
bool mtRangefinderDetect(rangefinderDev_t * dev, rangefinderType_e mtRangefinderToUse) {
|
||||
const MTRangefinderConfig* deviceConf = getMTRangefinderDeviceConf(mtRangefinderToUse);
|
||||
if (!deviceConf) {
|
||||
return false;
|
||||
|
@ -89,7 +89,7 @@ bool mtRangefinderDetect(rangefinderDev_t * dev, rangefinderType_e mtRangefinder
|
|||
return true;
|
||||
}
|
||||
|
||||
void mtRangefinderReceiveNewData(const uint8_t * bufferPtr) {
|
||||
void mtRangefinderReceiveNewData(const uint8_t * bufferPtr) {
|
||||
const mspSensorRangefinderLidarMtDataMessage_t * pkt = (const mspSensorRangefinderLidarMtDataMessage_t *)bufferPtr;
|
||||
|
||||
sensorData = pkt->distanceMm / 10;
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
#include "drivers/rangefinder/rangefinder.h"
|
||||
#include "sensors/rangefinder.h"
|
||||
|
||||
#define RANGEFINDER_MT_DETECTION_CONE_DECIDEGREES 900
|
||||
#define RANGEFINDER_MT_DETECTION_CONE_DECIDEGREES 900
|
||||
|
||||
typedef struct {
|
||||
rangefinderType_e deviceType;
|
||||
|
|
|
@ -68,7 +68,7 @@ enum rcc_reg {
|
|||
|
||||
#define RCC_ENCODE(reg, mask) (((reg) << 5) | LOG2_32BIT(mask))
|
||||
|
||||
#if defined(STM32F4)
|
||||
#if defined(STM32F4)
|
||||
#define RCC_AHB(periph) RCC_ENCODE(RCC_AHB, RCC_AHBENR_ ## periph ## EN)
|
||||
#define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN)
|
||||
#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN)
|
||||
|
|
|
@ -161,7 +161,7 @@ static void expressLrsOnTimerUpdate(timerOvrHandlerRec_t *cbRec, captureCompare_
|
|||
#endif
|
||||
|
||||
timerState.phaseShiftUs = 0;
|
||||
|
||||
|
||||
expressLrsOnTimerTockISR();
|
||||
|
||||
timerState.tickTock = TICK;
|
||||
|
|
|
@ -106,7 +106,7 @@ bool sx127xInit(IO_t resetPin, IO_t busyPin)
|
|||
IOLo(resetPin);
|
||||
delay(50);
|
||||
IOConfigGPIO(resetPin, IOCFG_IN_FLOATING); // leave floating
|
||||
|
||||
|
||||
return sx127xDetectChip();
|
||||
}
|
||||
|
||||
|
|
|
@ -294,7 +294,7 @@ typedef enum {
|
|||
|
||||
#define SX127x_FREQ_STEP 61.03515625
|
||||
|
||||
#define SX127x_FREQ_CORRECTION_MAX ((int32_t)(100000 / SX127x_FREQ_STEP))
|
||||
#define SX127x_FREQ_CORRECTION_MAX ((int32_t)(100000 / SX127x_FREQ_STEP))
|
||||
#define SX127x_FREQ_CORRECTION_MIN ((int32_t)(-100000 / SX127x_FREQ_STEP))
|
||||
|
||||
bool sx127xInit(IO_t resetPin, IO_t busyPin);
|
||||
|
|
|
@ -186,7 +186,7 @@ bool sx1280HandleFromTick(void)
|
|||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -822,7 +822,7 @@ static void sx1280GetPacketStats(extiCallbackRec_t *cb)
|
|||
spiSequence(dev, segments);
|
||||
}
|
||||
|
||||
// Process and decode the RF packet
|
||||
// Process and decode the RF packet
|
||||
static busStatus_e sx1280GetStatsCmdComplete(uint32_t arg)
|
||||
{
|
||||
extDevice_t *dev = (extDevice_t *)arg;
|
||||
|
@ -856,7 +856,7 @@ static busStatus_e sx1280IsFhssReq(uint32_t arg)
|
|||
UNUSED(arg);
|
||||
|
||||
if (expressLrsIsFhssReq()) {
|
||||
sx1280SetBusyFn(sx1280SetFrequency);
|
||||
sx1280SetBusyFn(sx1280SetFrequency);
|
||||
} else {
|
||||
sx1280SetFreqComplete(arg);
|
||||
}
|
||||
|
@ -941,7 +941,7 @@ static busStatus_e sx1280EnableIRQs(uint32_t arg)
|
|||
}
|
||||
|
||||
|
||||
// Send telemetry response
|
||||
// Send telemetry response
|
||||
static void sx1280SendTelemetryBuffer(extiCallbackRec_t *cb)
|
||||
{
|
||||
UNUSED(cb);
|
||||
|
|
|
@ -333,7 +333,7 @@ void updateArmingStatus(void)
|
|||
|
||||
// if, while the arm switch is enabled:
|
||||
// - the user switches off crashflip,
|
||||
// - and it was active,
|
||||
// - and it was active,
|
||||
// - and the quad did not flip successfully, or we don't have that information
|
||||
// require an arm-disarm cycle by blocking tryArm()
|
||||
if (crashFlipModeActive && !IS_RC_MODE_ACTIVE(BOXCRASHFLIP) && !crashFlipSuccessful()) {
|
||||
|
@ -552,7 +552,7 @@ void tryArm(void)
|
|||
if (crashFlipModeActive) {
|
||||
// flip was successful, continue into normal flight without need to disarm/rearm
|
||||
// note: preceding disarm will have set motors to normal rotation direction
|
||||
crashFlipModeActive = false;
|
||||
crashFlipModeActive = false;
|
||||
} else {
|
||||
// when arming and not in crashflip mode, block entry to crashflip if delayed by the dshot beeper,
|
||||
// otherwise consider only the switch position
|
||||
|
@ -993,7 +993,7 @@ void processRxModes(timeUs_t currentTimeUs)
|
|||
beeper(BEEPER_CRASHFLIP_MODE);
|
||||
if (!IS_RC_MODE_ACTIVE(BOXCRASHFLIP)) {
|
||||
// permit the option of staying disarmed if the crashflip switch is set to off while armed
|
||||
disarm(DISARM_REASON_SWITCH);
|
||||
disarm(DISARM_REASON_SWITCH);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -1004,7 +1004,7 @@ void processRxModes(timeUs_t currentTimeUs)
|
|||
|
||||
bool canUseHorizonMode = true;
|
||||
if ((IS_RC_MODE_ACTIVE(BOXANGLE)
|
||||
|| failsafeIsActive()
|
||||
|| failsafeIsActive()
|
||||
#ifdef USE_ALT_HOLD_MODE
|
||||
|| FLIGHT_MODE(ALT_HOLD_MODE)
|
||||
#endif
|
||||
|
@ -1021,7 +1021,7 @@ void processRxModes(timeUs_t currentTimeUs)
|
|||
|
||||
#ifdef USE_ALT_HOLD_MODE
|
||||
// only if armed
|
||||
if (ARMING_FLAG(ARMED)
|
||||
if (ARMING_FLAG(ARMED)
|
||||
// and either the alt_hold switch is activated, or are in failsafe
|
||||
&& (IS_RC_MODE_ACTIVE(BOXALTHOLD) || failsafeIsActive())
|
||||
// but not in GPS_RESCUE_MODE, ie if failsafe is active, must be in Landing Mode
|
||||
|
|
|
@ -89,7 +89,7 @@ enum {
|
|||
#ifdef USE_FEEDFORWARD
|
||||
static float feedforwardSmoothed[3];
|
||||
static float feedforwardRaw[3];
|
||||
static uint16_t feedforwardAveraging;
|
||||
static uint16_t feedforwardAveraging;
|
||||
typedef struct laggedMovingAverageCombined_s {
|
||||
laggedMovingAverage_t filter;
|
||||
float buf[4];
|
||||
|
@ -526,7 +526,7 @@ FAST_CODE_NOINLINE void calculateFeedforward(const pidRuntime_t *pid, flight_dyn
|
|||
float rxRate = currentRxRateHz; // 1e6f / currentRxIntervalUs;
|
||||
static float prevRcCommand[3]; // for rcCommandDelta test
|
||||
static float prevRcCommandDeltaAbs[3]; // for duplicate interpolation
|
||||
static float prevSetpoint[3]; // equals raw unless extrapolated forward
|
||||
static float prevSetpoint[3]; // equals raw unless extrapolated forward
|
||||
static float prevSetpointSpeed[3]; // for setpointDelta calculation
|
||||
static float prevSetpointSpeedDelta[3]; // for duplicate extrapolation
|
||||
static bool isPrevPacketDuplicate[3]; // to identify multiple identical packets
|
||||
|
@ -698,7 +698,7 @@ FAST_CODE void processRcCommand(void)
|
|||
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
|
||||
|
||||
float angleRate;
|
||||
|
||||
|
||||
#ifdef USE_GPS_RESCUE
|
||||
if ((axis == FD_YAW) && FLIGHT_MODE(GPS_RESCUE_MODE)) {
|
||||
// If GPS Rescue is active then override the setpointRate used in the
|
||||
|
|
|
@ -107,7 +107,7 @@ void altHoldUpdateTargetAltitude(void)
|
|||
|
||||
const float lowThreshold = 0.5f * (autopilotConfig()->hover_throttle + PWM_RANGE_MIN); // halfway between hover and MIN, e.g. 1150 if hover is 1300
|
||||
const float highThreshold = 0.5f * (autopilotConfig()->hover_throttle + PWM_RANGE_MAX); // halfway between hover and MAX, e.g. 1650 if hover is 1300
|
||||
|
||||
|
||||
float throttleAdjustmentFactor = 0.0f;
|
||||
if (rcThrottle < lowThreshold) {
|
||||
throttleAdjustmentFactor = scaleRangef(rcThrottle, PWM_RANGE_MIN, lowThreshold, -1.0f, 0.0f);
|
||||
|
@ -142,7 +142,7 @@ void altHoldUpdate(void)
|
|||
}
|
||||
|
||||
void updateAltHoldState(timeUs_t currentTimeUs) {
|
||||
UNUSED(currentTimeUs);
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
// check for enabling Alt Hold, otherwise do as little as possible while inactive
|
||||
altHoldProcessTransitions();
|
||||
|
|
|
@ -61,7 +61,7 @@ void altitudeControl(float targetAltitudeCm, float taskIntervalS, float vertical
|
|||
const float itermRelax = (fabsf(altitudeErrorCm) < 200.0f) ? 1.0f : 0.1f;
|
||||
altitudeI += altitudeErrorCm * altitudePidCoeffs.Ki * itermRelax * taskIntervalS;
|
||||
// limit iTerm to not more than 200 throttle units
|
||||
altitudeI = constrainf(altitudeI, -200.0f, 200.0f);
|
||||
altitudeI = constrainf(altitudeI, -200.0f, 200.0f);
|
||||
|
||||
const float altitudeD = verticalVelocity * altitudePidCoeffs.Kd;
|
||||
|
||||
|
|
|
@ -232,7 +232,7 @@ FAST_CODE_NOINLINE void failsafeUpdateState(void)
|
|||
}
|
||||
|
||||
bool receivingRxData = failsafeIsReceivingRxData();
|
||||
// returns state of FAILSAFE_RXLINK_UP, which
|
||||
// returns state of FAILSAFE_RXLINK_UP, which
|
||||
// goes false after the stage 1 delay, whether from signal loss or BOXFAILSAFE switch activation
|
||||
// goes true immediately BOXFAILSAFE switch is reverted, or after recovery delay once signal recovers
|
||||
// essentially means 'should be in failsafe stage 2'
|
||||
|
@ -367,7 +367,7 @@ FAST_CODE_NOINLINE void failsafeUpdateState(void)
|
|||
case FAILSAFE_GPS_RESCUE:
|
||||
if (receivingRxData) {
|
||||
if (areSticksActive(failsafeConfig()->failsafe_stick_threshold) || failsafeState.boxFailsafeSwitchWasOn) {
|
||||
// exits the rescue immediately if failsafe was initiated by switch, otherwise
|
||||
// exits the rescue immediately if failsafe was initiated by switch, otherwise
|
||||
// requires stick input to exit the rescue after a true Rx loss failsafe
|
||||
// NB this test requires stick inputs to be received during GPS Rescue see PR #7936 for rationale
|
||||
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
|
||||
|
|
|
@ -140,7 +140,7 @@ void gpsRescueInit(void)
|
|||
gain = pt1FilterGain(cutoffHz, 1.0f);
|
||||
pt1FilterInit(&velocityDLpf, gain);
|
||||
|
||||
cutoffHz *= 4.0f;
|
||||
cutoffHz *= 4.0f;
|
||||
gain = pt3FilterGain(cutoffHz, taskIntervalSeconds);
|
||||
pt3FilterInit(&velocityUpsampleLpf, gain);
|
||||
}
|
||||
|
@ -509,7 +509,7 @@ static void sensorUpdate(void)
|
|||
rescueState.sensor.errorAngle -= 360;
|
||||
}
|
||||
rescueState.sensor.absErrorAngle = fabsf(rescueState.sensor.errorAngle);
|
||||
|
||||
|
||||
DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING, 4, lrintf(attitude.values.yaw)); // estimated heading of the quad (direction nose is pointing in)
|
||||
DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING, 5, lrintf(rescueState.sensor.directionToHome)); // angle to home derived from GPS location and home position
|
||||
|
||||
|
@ -645,7 +645,7 @@ void descend(void)
|
|||
// consider landing area to be a circle half landing height around home, to avoid overshooting home point
|
||||
const float distanceToLandingAreaM = rescueState.sensor.distanceToHomeM - (0.5f * autopilotConfig()->landing_altitude_m);
|
||||
const float proximityToLandingArea = constrainf(distanceToLandingAreaM / rescueState.intent.descentDistanceM, 0.0f, 1.0f);
|
||||
|
||||
|
||||
// increase the velocity lowpass filter cutoff for more aggressive responses when descending, especially close to home
|
||||
// 1.5x when starting descent, 2.5x (smoother) when almost landed
|
||||
rescueState.intent.velocityPidCutoffModifier = 2.5f - proximityToLandingArea;
|
||||
|
@ -686,7 +686,7 @@ void descend(void)
|
|||
|
||||
// descend faster while the quad is at higher altitudes
|
||||
const float descentRateMultiplier = constrainf(rescueState.intent.targetAltitudeCm / 5000.0f, 0.0f, 1.0f);
|
||||
altitudeStepCm *= 1.0f + (2.0f * descentRateMultiplier);
|
||||
altitudeStepCm *= 1.0f + (2.0f * descentRateMultiplier);
|
||||
// maximum descent rate increase is 3x default above 50m, 2x above 25m, 1.2x at 5m, default by ground level
|
||||
|
||||
// also increase throttle D up to 2x in the descent phase when altitude descent rate is faster, for better control
|
||||
|
@ -821,14 +821,14 @@ void gpsRescueUpdate(void)
|
|||
rescueState.intent.velocityItermRelax += 0.5f * taskIntervalSeconds * (1.0f - rescueState.intent.velocityItermRelax);
|
||||
// there is always a lot of lag at the start, this gradual start avoids excess iTerm accumulation
|
||||
|
||||
rescueState.intent.velocityPidCutoffModifier = 2.0f - rescueState.intent.velocityItermRelax;
|
||||
rescueState.intent.velocityPidCutoffModifier = 2.0f - rescueState.intent.velocityItermRelax;
|
||||
// higher velocity filter cutoff for initial few seconds to improve accuracy; can be smoother later
|
||||
|
||||
if (newGPSData) {
|
||||
// cut back on allowed angle if there is a high groundspeed error
|
||||
rescueState.intent.pitchAngleLimitDeg = gpsRescueConfig()->maxRescueAngle;
|
||||
// introduce roll slowly and limit to half the max pitch angle; earth referenced yaw may add more roll via angle code
|
||||
rescueState.intent.rollAngleLimitDeg = 0.5f * rescueState.intent.pitchAngleLimitDeg * rescueState.intent.velocityItermRelax;
|
||||
rescueState.intent.rollAngleLimitDeg = 0.5f * rescueState.intent.pitchAngleLimitDeg * rescueState.intent.velocityItermRelax;
|
||||
if (rescueState.sensor.distanceToHomeM <= rescueState.intent.descentDistanceM) {
|
||||
rescueState.phase = RESCUE_DESCENT;
|
||||
rescueState.intent.secondsFailing = 0; // reset sanity timer for descent
|
||||
|
@ -907,7 +907,7 @@ bool gpsRescueIsDisabled(void)
|
|||
#ifdef USE_MAG
|
||||
bool gpsRescueDisableMag(void)
|
||||
{
|
||||
// Enable mag on user request, but don't use it during fly home or if force disabled
|
||||
// Enable mag on user request, but don't use it during fly home or if force disabled
|
||||
// Note that while flying home the course over ground from GPS provides a heading that is less affected by wind
|
||||
return !(gpsRescueConfig()->useMag && rescueState.phase != RESCUE_FLY_HOME && !magForceDisable);
|
||||
}
|
||||
|
|
|
@ -439,7 +439,7 @@ static float imuCalcGroundspeedGain(float dt)
|
|||
}
|
||||
|
||||
// NOTE : these suppressions make sense with normal pilot inputs and normal flight
|
||||
// They are not used in GPS Rescue, and probably should be bypassed in position hold, etc,
|
||||
// They are not used in GPS Rescue, and probably should be bypassed in position hold, etc,
|
||||
|
||||
return speedBasedGain * stickSuppression * rollSuppression * pitchSuppression;
|
||||
}
|
||||
|
@ -488,7 +488,7 @@ static void imuDebug_GPS_RESCUE_HEADING(void)
|
|||
// Encapsulate additional operations in a block so that it is only executed when the according debug mode is used
|
||||
// Only re-calculate magYaw when there is a new Mag data reading, to avoid spikes
|
||||
if (debugMode == DEBUG_GPS_RESCUE_HEADING && mag.isNewMagADCFlag) {
|
||||
|
||||
|
||||
vector3_t mag_bf = mag.magADC;
|
||||
vector3_t mag_ef;
|
||||
matrixVectorMul(&mag_ef, &rMat, &mag_bf); // BF->EF true north
|
||||
|
@ -498,7 +498,7 @@ static void imuDebug_GPS_RESCUE_HEADING(void)
|
|||
|
||||
vector3_t mag_ef_yawed;
|
||||
matrixVectorMul(&mag_ef_yawed, &rMatZTrans, &mag_ef); // EF->EF yawed
|
||||
|
||||
|
||||
// Magnetic yaw is the angle between true north and the X axis of the body frame
|
||||
int16_t magYaw = lrintf((atan2_approx(mag_ef_yawed.y, mag_ef_yawed.x) * (1800.0f / M_PIf)));
|
||||
if (magYaw < 0) {
|
||||
|
@ -724,7 +724,7 @@ void imuUpdateAttitude(timeUs_t currentTimeUs)
|
|||
// Update the throttle correction for angle and supply it to the mixer
|
||||
int throttleAngleCorrection = 0;
|
||||
if (throttleAngleValue
|
||||
&& (FLIGHT_MODE(ANGLE_MODE | HORIZON_MODE))
|
||||
&& (FLIGHT_MODE(ANGLE_MODE | HORIZON_MODE))
|
||||
&& ARMING_FLAG(ARMED)) {
|
||||
throttleAngleCorrection = calculateThrottleAngleCorrection();
|
||||
}
|
||||
|
|
|
@ -388,7 +388,7 @@ static bool applyCrashFlipModeToMotors(void)
|
|||
|
||||
// set motors to disarm value when intended increase is less than deadband value
|
||||
motorOutput = (motorOutputNormalised < CRASHFLIP_MOTOR_DEADBAND) ? mixerRuntime.disarmMotorOutput : motorOutput;
|
||||
|
||||
|
||||
motor[i] = motorOutput;
|
||||
}
|
||||
|
||||
|
|
|
@ -389,7 +389,7 @@ void pidUpdateTpaFactor(float throttle)
|
|||
|
||||
DEBUG_SET(DEBUG_TPA, 0, lrintf(tpaFactor * 1000));
|
||||
pidRuntime.tpaFactor = tpaFactor;
|
||||
|
||||
|
||||
#ifdef USE_WING
|
||||
switch (currentPidProfile->yaw_type) {
|
||||
case YAW_TYPE_DIFF_THRUST:
|
||||
|
@ -499,7 +499,7 @@ STATIC_UNIT_TESTED FAST_CODE_NOINLINE float pidLevel(int axis, const pidProfile_
|
|||
|
||||
#ifdef USE_WING
|
||||
if (axis == FD_PITCH) {
|
||||
angleTarget += (float)pidProfile->angle_pitch_offset / 10.0f;
|
||||
angleTarget += (float)pidProfile->angle_pitch_offset / 10.0f;
|
||||
}
|
||||
#endif // USE_WING
|
||||
|
||||
|
@ -997,7 +997,7 @@ NOINLINE static void applySpa(int axis, const pidProfile_t *pidProfile)
|
|||
static float getTpaFactor(const pidProfile_t *pidProfile, int axis, term_e term)
|
||||
{
|
||||
float tpaFactor = pidRuntime.tpaFactor;
|
||||
|
||||
|
||||
#ifdef USE_WING
|
||||
if (axis == FD_YAW) {
|
||||
tpaFactor = pidRuntime.tpaFactorYaw;
|
||||
|
|
|
@ -165,14 +165,14 @@ void calculateEstimatedAltitude(void)
|
|||
}
|
||||
} else {
|
||||
gpsTrust = 0.0f;
|
||||
// TO DO - smoothly reduce GPS trust, rather than immediately dropping to zero for what could be only a very brief loss of 3D fix
|
||||
// TO DO - smoothly reduce GPS trust, rather than immediately dropping to zero for what could be only a very brief loss of 3D fix
|
||||
}
|
||||
DEBUG_SET(DEBUG_ALTITUDE, 2, lrintf(zeroedAltitudeCm / 10.0f)); // Relative altitude above takeoff, to 0.1m, rolls over at 3,276.7m
|
||||
|
||||
|
||||
// Empirical mixing of GPS and Baro altitudes
|
||||
if (useZeroedGpsAltitude && (positionConfig()->altitude_source == DEFAULT || positionConfig()->altitude_source == GPS_ONLY)) {
|
||||
if (haveBaroAlt && positionConfig()->altitude_source == DEFAULT) {
|
||||
// mix zeroed GPS with Baro altitude data, if Baro data exists if are in default altitude control mode
|
||||
// mix zeroed GPS with Baro altitude data, if Baro data exists if are in default altitude control mode
|
||||
const float absDifferenceM = fabsf(zeroedAltitudeCm - baroAltCm) / 100.0f * positionConfig()->altitude_prefer_baro / 100.0f;
|
||||
if (absDifferenceM > 1.0f) { // when there is a large difference, favour Baro
|
||||
gpsTrust /= absDifferenceM;
|
||||
|
@ -202,7 +202,7 @@ void calculateEstimatedAltitude(void)
|
|||
estimatedVario = lrintf(zeroedAltitudeDerivative);
|
||||
estimatedVario = applyDeadband(estimatedVario, 10); // ignore climb rates less than 0.1 m/s
|
||||
#endif
|
||||
|
||||
|
||||
// *** set debugs
|
||||
DEBUG_SET(DEBUG_ALTITUDE, 0, (int32_t)(100 * gpsTrust));
|
||||
DEBUG_SET(DEBUG_ALTITUDE, 1, lrintf(baroAltCm / 10.0f)); // Relative altitude above takeoff, to 0.1m, rolls over at 3,276.7m
|
||||
|
|
|
@ -314,7 +314,7 @@ typedef struct ubxMessage_s {
|
|||
|
||||
typedef enum {
|
||||
UBLOX_DETECT_UNIT, // 0
|
||||
UBLOX_SLOW_NAV_RATE, // 1.
|
||||
UBLOX_SLOW_NAV_RATE, // 1.
|
||||
UBLOX_MSG_DISABLE_NMEA, // 2. Disable NMEA, config message
|
||||
UBLOX_MSG_VGS, // 3. VGS: Course over ground and Ground speed
|
||||
UBLOX_MSG_GSV, // 4. GSV: GNSS Satellites in View
|
||||
|
@ -627,35 +627,35 @@ static void ubloxSendNAV5Message(uint8_t model) {
|
|||
// payload[2] = (uint8_t)(0 >> (8 * 2));
|
||||
// payload[3] = (uint8_t)(0 >> (8 * 3)); // all payloads are zero, the default MSL for 2D fix
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_CONSTR_ALT, payload, offset); // 23
|
||||
//
|
||||
//
|
||||
// payload[0] = (uint8_t)(10000 >> (8 * 0));
|
||||
// payload[1] = (uint8_t)(10000 >> (8 * 1));
|
||||
// payload[2] = (uint8_t)(10000 >> (8 * 2));
|
||||
// payload[3] = (uint8_t)(10000 >> (8 * 3)); // // all payloads are 1000, the default 2D variance factor
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_CONSTR_ALTVAR, payload, offset); // 31
|
||||
//
|
||||
//
|
||||
// payload[0] = 5; // sets the default minimum elevation in degrees to the default of 5
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_INFIL_MINELEV, payload, offset); // 36
|
||||
//
|
||||
//
|
||||
// payload[0] = (uint8_t)(250 >> (8 * 0));
|
||||
// payload[1] = (uint8_t)(250 >> (8 * 1)); // sets the output filter PDOP mask to default of 250
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_OUTFIL_PDOP, payload, offset); // 42
|
||||
//
|
||||
//
|
||||
// payload[0] = (uint8_t)(250 >> (8 * 0));
|
||||
// payload[1] = (uint8_t)(250 >> (8 * 1));
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_OUTFIL_TDOP, payload, offset); // 48
|
||||
//
|
||||
//
|
||||
// payload[0] = (uint8_t)(100 >> (8 * 0));
|
||||
// payload[1] = (uint8_t)(100 >> (8 * 1));
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_OUTFIL_PACC, payload, offset); // 54
|
||||
//
|
||||
//
|
||||
// payload[0] = (uint8_t)(300 >> (8 * 0));
|
||||
// payload[1] = (uint8_t)(300 >> (8 * 1));
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_OUTFIL_TACC, payload, offset); // 60
|
||||
//
|
||||
//
|
||||
// payload[0] = 0;
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_MOT_GNSSSPEED_THRS, payload, offset); // 65
|
||||
//
|
||||
//
|
||||
// payload[0] = (uint8_t)(200 >> (8 * 0));
|
||||
// payload[1] = (uint8_t)(200 >> (8 * 1));
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_MOT_GNSSDIST_THRS, payload, offset); // 71
|
||||
|
@ -665,7 +665,7 @@ static void ubloxSendNAV5Message(uint8_t model) {
|
|||
|
||||
// payload[0] = 0;
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_INFIL_NCNOTHRS, payload, offset); // 81
|
||||
//
|
||||
//
|
||||
// payload[0] = 0;
|
||||
// offset += ubloxAddValSet(&tx_buffer, CFG_NAVSPG_INFIL_CNOTHRS, payload, offset); // 86
|
||||
|
||||
|
@ -697,18 +697,18 @@ static void ubloxSendNAV5Message(uint8_t model) {
|
|||
// *** Assist Now Autonomous temporarily disabled until a subsequent PR either includes, or removes it ***
|
||||
// static void ubloxSendNavX5Message(void) {
|
||||
// ubxMessage_t tx_buffer;
|
||||
//
|
||||
//
|
||||
// if (gpsData.ubloxM9orAbove) {
|
||||
// uint8_t payload[1];
|
||||
// payload[0] = 1;
|
||||
// size_t offset = ubloxValSet(&tx_buffer, CFG_ANA_USE_ANA, payload, UBX_VAL_LAYER_RAM); // 5
|
||||
//
|
||||
//
|
||||
// ubloxSendConfigMessage(&tx_buffer, MSG_CFG_VALSET, offsetof(ubxCfgValSet_t, cfgData) + offset, true);
|
||||
// } else {
|
||||
// memset(&tx_buffer, 0, sizeof(ubxMessage_t));
|
||||
//
|
||||
//
|
||||
// tx_buffer.payload.cfg_nav5x.version = 0x0002;
|
||||
//
|
||||
//
|
||||
// tx_buffer.payload.cfg_nav5x.mask1 = 0x4000;
|
||||
// tx_buffer.payload.cfg_nav5x.mask2 = 0x0;
|
||||
// tx_buffer.payload.cfg_nav5x.minSVs = 0;
|
||||
|
@ -720,11 +720,11 @@ static void ubloxSendNAV5Message(uint8_t model) {
|
|||
// tx_buffer.payload.cfg_nav5x.wknRollover = 0;
|
||||
// tx_buffer.payload.cfg_nav5x.sigAttenCompMode = 0;
|
||||
// tx_buffer.payload.cfg_nav5x.usePPP = 0;
|
||||
//
|
||||
//
|
||||
// tx_buffer.payload.cfg_nav5x.aopCfg = 0x1; //bit 0 = useAOP
|
||||
//
|
||||
//
|
||||
// tx_buffer.payload.cfg_nav5x.useAdr = 0;
|
||||
//
|
||||
//
|
||||
// ubloxSendConfigMessage(&tx_buffer, MSG_CFG_NAVX_SETTINGS, sizeof(ubxCfgNav5x_t), false);
|
||||
// }
|
||||
// }
|
||||
|
@ -952,7 +952,7 @@ static void setSatInfoMessageRate(uint8_t divisor)
|
|||
void gpsConfigureNmea(void)
|
||||
{
|
||||
// minimal support for NMEA, we only:
|
||||
// - set the FC's GPS port to the user's configured rate, and
|
||||
// - set the FC's GPS port to the user's configured rate, and
|
||||
// - send any NMEA custom commands to the GPS Module
|
||||
// the user must configure the power-up baud rate of the module to be fast enough for their data rate
|
||||
// Note: we always parse all incoming NMEA messages
|
||||
|
|
|
@ -356,7 +356,7 @@ static const char directionCodes[LED_DIRECTION_COUNT] = {
|
|||
[LED_DIRECTION_DOWN] = 'D'
|
||||
};
|
||||
static const char baseFunctionCodes[LED_BASEFUNCTION_COUNT] = {
|
||||
[LED_FUNCTION_COLOR] = 'C',
|
||||
[LED_FUNCTION_COLOR] = 'C',
|
||||
[LED_FUNCTION_FLIGHT_MODE] = 'F',
|
||||
[LED_FUNCTION_ARM_STATE] = 'A',
|
||||
[LED_FUNCTION_BATTERY] = 'L',
|
||||
|
@ -622,7 +622,7 @@ static void applyLedFixedLayers(void)
|
|||
} else {
|
||||
color = HSV(RED);
|
||||
hOffset += MAX(scaleRange(gpsSol.numSat, 0, minSats, -30, 120), 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -8,17 +8,17 @@
|
|||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2015 by Sergey Fetisov <fsenok@gmail.com>
|
||||
*
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in all
|
||||
* copies or substantial portions of the Software.
|
||||
*
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
|
||||
#include "msp/msp_build_info.h"
|
||||
|
||||
void sbufWriteBuildInfoFlags(sbuf_t *dst)
|
||||
void sbufWriteBuildInfoFlags(sbuf_t *dst)
|
||||
{
|
||||
static const uint16_t options[] = {
|
||||
#ifdef USE_SERIALRX_CRSF
|
||||
|
|
|
@ -361,7 +361,7 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
|||
#ifdef USE_RC_STATS
|
||||
osdStatSetState(OSD_STAT_FULL_THROTTLE_TIME, true);
|
||||
osdStatSetState(OSD_STAT_FULL_THROTTLE_COUNTER, true);
|
||||
osdStatSetState(OSD_STAT_AVG_THROTTLE, true);
|
||||
osdStatSetState(OSD_STAT_AVG_THROTTLE, true);
|
||||
#endif
|
||||
|
||||
osdConfig->timers[OSD_TIMER_1] = osdTimerDefault[OSD_TIMER_1];
|
||||
|
|
|
@ -323,7 +323,7 @@ int osdConvertTemperatureToSelectedUnit(int tempInDegreesCelcius)
|
|||
static void osdFormatAltitudeString(char * buff, int32_t altitudeCm, osdElementType_e variantType)
|
||||
{
|
||||
static const struct {
|
||||
uint8_t decimals;
|
||||
uint8_t decimals;
|
||||
bool asl;
|
||||
} variantMap[] = {
|
||||
[OSD_ELEMENT_TYPE_1] = { 1, false },
|
||||
|
|
|
@ -311,7 +311,7 @@ bool isValidPacket(const uint8_t *packet)
|
|||
}
|
||||
}
|
||||
|
||||
uint16_t lcrc = calculateCrc(&packet[3], (packetLength - 7));
|
||||
uint16_t lcrc = calculateCrc(&packet[3], (packetLength - 7));
|
||||
|
||||
if ((lcrc >> 8) == packet[packetLength - 4] && (lcrc & 0x00FF) == packet[packetLength - 3] &&
|
||||
(packet[0] == packetLength - 3) &&
|
||||
|
|
|
@ -201,7 +201,7 @@ static uint8_t mspBuffer[ELRS_MSP_BUFFER_SIZE];
|
|||
static void setRssiChannelData(uint16_t *rcData)
|
||||
{
|
||||
rcData[ELRS_LQ_CHANNEL] = scaleRange(receiver.uplinkLQ, 0, 100, 988, 2011);
|
||||
rcData[ELRS_RSSI_CHANNEL] = scaleRange(constrain(receiver.rssiFiltered, receiver.rfPerfParams->sensitivity, -50), receiver.rfPerfParams->sensitivity, -50, 988, 2011);
|
||||
rcData[ELRS_RSSI_CHANNEL] = scaleRange(constrain(receiver.rssiFiltered, receiver.rfPerfParams->sensitivity, -50), receiver.rfPerfParams->sensitivity, -50, 988, 2011);
|
||||
}
|
||||
|
||||
static void unpackAnalogChannelData(uint16_t *rcData, volatile elrsOtaPacket_t const * const otaPktPtr)
|
||||
|
@ -233,7 +233,7 @@ static void unpackAnalogChannelData(uint16_t *rcData, volatile elrsOtaPacket_t c
|
|||
* 2 bits for the low latency switch[0]
|
||||
* 3 bits for the round-robin switch index and 2 bits for the value
|
||||
* 4 analog channels, 1 low latency switch and round robin switch data = 47 bits (1 free)
|
||||
*
|
||||
*
|
||||
* sets telemetry status bit
|
||||
*/
|
||||
static void unpackChannelDataHybridSwitch8(uint16_t *rcData, volatile elrsOtaPacket_t const * const otaPktPtr)
|
||||
|
@ -242,7 +242,7 @@ static void unpackChannelDataHybridSwitch8(uint16_t *rcData, volatile elrsOtaPac
|
|||
|
||||
const uint8_t switchByte = otaPktPtr->rc.switches;
|
||||
|
||||
// The round-robin switch, switchIndex is actually index-1
|
||||
// The round-robin switch, switchIndex is actually index-1
|
||||
// to leave the low bit open for switch 7 (sent as 0b11x)
|
||||
// where x is the high bit of switch 7
|
||||
uint8_t switchIndex = (switchByte & 0x38) >> 3;
|
||||
|
@ -316,7 +316,7 @@ static bool domainIsTeam24(void)
|
|||
#ifdef USE_RX_SX1280
|
||||
const elrsFreqDomain_e domain = rxExpressLrsSpiConfig()->domain;
|
||||
return (domain == ISM2400) || (domain == CE2400);
|
||||
#else
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
@ -420,7 +420,7 @@ static void expressLrsSendTelemResp(void)
|
|||
|
||||
if (nextTelemetryType == ELRS_TELEMETRY_TYPE_LINK || !isTelemetrySenderActive()) {
|
||||
otaPkt.tlm_dl.type = ELRS_TELEMETRY_TYPE_LINK;
|
||||
otaPkt.tlm_dl.ul_link_stats.uplink_RSSI_1 = receiver.rssiFiltered > 0 ? 0 : -receiver.rssiFiltered;
|
||||
otaPkt.tlm_dl.ul_link_stats.uplink_RSSI_1 = receiver.rssiFiltered > 0 ? 0 : -receiver.rssiFiltered;
|
||||
otaPkt.tlm_dl.ul_link_stats.uplink_RSSI_2 = 0; //diversity not supported
|
||||
otaPkt.tlm_dl.ul_link_stats.antenna = 0;
|
||||
otaPkt.tlm_dl.ul_link_stats.modelMatch = connectionHasModelMatch;
|
||||
|
@ -1097,7 +1097,7 @@ static void enterBindingMode(void)
|
|||
receiver.UID = BindingUID;
|
||||
crcInitializer = 0;
|
||||
receiver.inBindingMode = true;
|
||||
|
||||
|
||||
setRfLinkRate(bindingRateIndex);
|
||||
receiver.startReceiving();
|
||||
}
|
||||
|
@ -1106,7 +1106,7 @@ void expressLrsDoTelem(void)
|
|||
{
|
||||
expressLrsHandleTelemetryUpdate();
|
||||
expressLrsSendTelemResp();
|
||||
|
||||
|
||||
if (!expressLrsTelemRespReq() && lqPeriodIsSet()) {
|
||||
// TODO No need to handle this on SX1280, but will on SX127x
|
||||
// TODO this needs to be DMA aswell, SX127x unlikely to work right now
|
||||
|
|
|
@ -335,7 +335,7 @@ uint16_t convertSwitch1b(const uint16_t val)
|
|||
}
|
||||
|
||||
// 3b to decode 7 pos switches
|
||||
uint16_t convertSwitch3b(const uint16_t val)
|
||||
uint16_t convertSwitch3b(const uint16_t val)
|
||||
{
|
||||
switch (val) {
|
||||
case 0: return 1000;
|
||||
|
|
|
@ -95,21 +95,21 @@ static void decode_bind_packet(uint8_t *packet)
|
|||
txid[2] = packet[6];
|
||||
txid[3] = packet[7];
|
||||
txid[4] = 0x4b;
|
||||
|
||||
|
||||
kn_freq_hopping[0] = packet[8];
|
||||
kn_freq_hopping[1] = packet[9];
|
||||
kn_freq_hopping[2] = packet[10];
|
||||
kn_freq_hopping[3] = packet[11];
|
||||
|
||||
|
||||
if (packet[15]==0x01) {
|
||||
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
|
||||
} else {
|
||||
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
|
||||
}
|
||||
|
||||
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, txid, RX_TX_ADDR_LEN);
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, txid, RX_TX_ADDR_LEN);
|
||||
|
||||
|
||||
bind_phase = PHASE_BOUND;
|
||||
rx_timeout = 1000L; // find the channel as fast as possible
|
||||
}
|
||||
|
@ -126,7 +126,7 @@ static rx_spi_received_e decode_packet(uint8_t *packet)
|
|||
// Restore regular interval
|
||||
rx_timeout = 13000L; // 13ms if data received
|
||||
bind_phase = PHASE_RECEIVED;
|
||||
|
||||
|
||||
for (int i = 0; i < 4; ++i) {
|
||||
uint16_t a = packet[i*2];
|
||||
uint16_t b = packet[(i*2)+1];
|
||||
|
|
|
@ -578,7 +578,7 @@ FAST_CODE_NOINLINE void rxFrameCheck(timeUs_t currentTimeUs, timeDelta_t current
|
|||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
DEBUG_SET(DEBUG_FAILSAFE, 1, rxSignalReceived);
|
||||
DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 0, rxSignalReceived);
|
||||
}
|
||||
|
|
|
@ -96,7 +96,7 @@ PG_REGISTER_WITH_RESET_FN(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 4);
|
|||
#define COMPASS_BUS_BUSY_INTERVAL_US 500
|
||||
// If we check for new mag data, and there is none, try again in 1000us
|
||||
#define COMPASS_RECHECK_INTERVAL_US 1000
|
||||
// default compass read interval, for those with no specified ODR, will be TASK_COMPASS_RATE_HZ
|
||||
// default compass read interval, for those with no specified ODR, will be TASK_COMPASS_RATE_HZ
|
||||
static uint32_t compassReadIntervalUs = TASK_PERIOD_HZ(TASK_COMPASS_RATE_HZ);
|
||||
|
||||
void pgResetFn_compassConfig(compassConfig_t *compassConfig)
|
||||
|
@ -502,7 +502,7 @@ uint32_t compassUpdate(timeUs_t currentTimeUs)
|
|||
// there was no movement, and no new calibration values were saved
|
||||
beeper(BEEPER_ACC_CALIBRATION_FAIL); // calibration fail beep
|
||||
}
|
||||
// didMovementStart remains true until next run
|
||||
// didMovementStart remains true until next run
|
||||
// signal that the calibration process is finalised, whether successful or not, by setting end time to zero
|
||||
magCalProcessActive = false;
|
||||
}
|
||||
|
@ -561,7 +561,7 @@ void compassBiasEstimatorInit(compassBiasEstimator_t *cBE, const float lambda_mi
|
|||
cBE->U[i][i] = 1.0f;
|
||||
}
|
||||
|
||||
compassBiasEstimatorUpdate(cBE, lambda_min, p0);
|
||||
compassBiasEstimatorUpdate(cBE, lambda_min, p0);
|
||||
|
||||
cBE->lambda = lambda_min;
|
||||
}
|
||||
|
@ -574,7 +574,7 @@ void compassBiasEstimatorUpdate(compassBiasEstimator_t *cBE, const float lambda_
|
|||
// update diagonal entries for faster convergence
|
||||
for (unsigned i = 0; i < 4; i++) {
|
||||
cBE->D[i] = p0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// apply one estimation step of the compass bias estimator
|
||||
|
|
|
@ -33,7 +33,7 @@ PG_DECLARE(escSensorConfig_t, escSensorConfig);
|
|||
typedef struct {
|
||||
uint8_t dataAge;
|
||||
int8_t temperature; // C degrees
|
||||
uint16_t voltage; // 0.01V
|
||||
uint16_t voltage; // 0.01V
|
||||
int32_t current; // 0.01A
|
||||
int32_t consumption; // mAh
|
||||
int16_t rpm; // 0.01erpm
|
||||
|
|
|
@ -126,7 +126,7 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar
|
|||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
||||
#if defined(USE_RANGEFINDER_MT)
|
||||
case RANGEFINDER_MTF01:
|
||||
case RANGEFINDER_MTF02:
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
|
||||
typedef struct targetSerialPortFunction_s {
|
||||
serialPortIdentifier_e identifier;
|
||||
serialPortFunction_e function;
|
||||
serialPortFunction_e function;
|
||||
} targetSerialPortFunction_t;
|
||||
|
||||
void targetSerialPortFunctionConfig(targetSerialPortFunction_t *config, size_t count);
|
||||
|
|
|
@ -304,7 +304,7 @@ void crsfFrameBatterySensor(sbuf_t *dst)
|
|||
#if defined(USE_BARO) && defined(USE_VARIO)
|
||||
// pack altitude in decimeters into a 16-bit value.
|
||||
// Due to strange OpenTX behavior of count any 0xFFFF value as incorrect, the maximum sending value is limited to 0xFFFE (32766 meters)
|
||||
// in order to have both precision and range in 16-bit
|
||||
// in order to have both precision and range in 16-bit
|
||||
// value of altitude is packed with different precision depending on highest-bit value.
|
||||
// on receiving side:
|
||||
// if MSB==0, altitude is sent in decimeters as uint16 with -1000m base. So, range is -1000..2276m.
|
||||
|
@ -312,7 +312,7 @@ void crsfFrameBatterySensor(sbuf_t *dst)
|
|||
// altitude lower than -1000m is sent as zero (should be displayed as "<-1000m" or something).
|
||||
// altitude higher than 32767m is sent as 0xfffe (should be displayed as ">32766m" or something).
|
||||
// range from 0 to 2276m might be sent with dm- or m-precision. But this function always use dm-precision.
|
||||
static inline uint16_t calcAltitudePacked(int32_t altitude_dm)
|
||||
static inline uint16_t calcAltitudePacked(int32_t altitude_dm)
|
||||
{
|
||||
static const int ALT_DM_OFFSET = 10000;
|
||||
int valDm = altitude_dm + ALT_DM_OFFSET;
|
||||
|
|
|
@ -314,8 +314,8 @@ void initGhstTelemetry(void)
|
|||
#endif
|
||||
|
||||
#if defined(USE_BARO) || defined(USE_MAG) || defined(USE_VARIO)
|
||||
if ((sensors(SENSOR_BARO) && telemetryIsSensorEnabled(SENSOR_ALTITUDE))
|
||||
|| (sensors(SENSOR_MAG) && telemetryIsSensorEnabled(SENSOR_HEADING))
|
||||
if ((sensors(SENSOR_BARO) && telemetryIsSensorEnabled(SENSOR_ALTITUDE))
|
||||
|| (sensors(SENSOR_MAG) && telemetryIsSensorEnabled(SENSOR_HEADING))
|
||||
|| (sensors(SENSOR_VARIO) && telemetryIsSensorEnabled(SENSOR_VARIO))) {
|
||||
ghstSchedule[index++] = BIT(GHST_FRAME_MAGBARO_INDEX);
|
||||
}
|
||||
|
|
|
@ -59,14 +59,14 @@ MSP might be MSPv1 or MSPv2 or MSPv1_Jumbo.
|
|||
MSP_body might be sent in chunks.
|
||||
First (or only) chunk must always set start bit (#4) of status byte.
|
||||
Each next chunk must have increased sequence number in status byte.
|
||||
Size of chunk is recovered from size of CRSF frame.
|
||||
Although last / only CRSF frame might have size bigger than needed for MSP-body.
|
||||
Size of chunk is recovered from size of CRSF frame.
|
||||
Although last / only CRSF frame might have size bigger than needed for MSP-body.
|
||||
Extra bytes must be ignored. So, the real size of MSP-body must be parsed from the MSP-body itself.
|
||||
CRSF frames might be any size until maximum of 64 bytes for a CRSF frame.
|
||||
CRSF frames might be any size until maximum of 64 bytes for a CRSF frame.
|
||||
So, maximum chunk size is 57 bytes. Although, MSP-body might be sent in shorter chunks.
|
||||
Although, first chunk must consist full size any type of the MSP frame.
|
||||
|
||||
MSP-CRC is not sent over CRSF due to ther is already CRC of CRSF frame.
|
||||
MSP-CRC is not sent over CRSF due to ther is already CRC of CRSF frame.
|
||||
So, it must be recalculated of needed for MSP-receiver.
|
||||
|
||||
MSP frame must be returned to the origin address of the request
|
||||
|
@ -95,9 +95,9 @@ enum { // error codes (they are not sent anywhere)
|
|||
|
||||
enum { // minimum length for a frame.
|
||||
MIN_LENGTH_CHUNK = 2, // status + at_least_one_byte
|
||||
MIN_LENGTH_REQUEST_V1 = 3, // status + length + ID
|
||||
MIN_LENGTH_REQUEST_JUMBO = 5, // status + length=FF + ID + length_lo + length_hi
|
||||
MIN_LENGTH_REQUEST_V2 = 6, // status + flag + ID_lo + ID_hi + size_lo + size_hi
|
||||
MIN_LENGTH_REQUEST_V1 = 3, // status + length + ID
|
||||
MIN_LENGTH_REQUEST_JUMBO = 5, // status + length=FF + ID + length_lo + length_hi
|
||||
MIN_LENGTH_REQUEST_V2 = 6, // status + flag + ID_lo + ID_hi + size_lo + size_hi
|
||||
};
|
||||
|
||||
enum { // byte position(index) in msp-over-telemetry request payload
|
||||
|
@ -251,7 +251,7 @@ bool handleMspFrame(uint8_t *const payload, uint8_t const payloadLength, uint8_t
|
|||
sbufWriteData(&requestPacket.buf, sbufInput.ptr, payloadIncoming);
|
||||
sbufAdvance(&sbufInput, payloadIncoming);
|
||||
return false;
|
||||
} else { // this is the last/only chunk
|
||||
} else { // this is the last/only chunk
|
||||
if (payloadExpecting) {
|
||||
sbufWriteData(&requestPacket.buf, sbufInput.ptr, payloadExpecting);
|
||||
sbufAdvance(&sbufInput, payloadExpecting);
|
||||
|
@ -292,11 +292,11 @@ bool sendMspReply(const uint8_t payloadSizeMax, mspResponseFnPtr responseFn)
|
|||
if (size >= 0xff) {
|
||||
// Sending Jumbo-frame
|
||||
sbufWriteU8(payloadBuf, 0xff);
|
||||
sbufWriteU8(payloadBuf, responsePacket.cmd);
|
||||
sbufWriteU8(payloadBuf, responsePacket.cmd);
|
||||
sbufWriteU16(payloadBuf, (uint16_t)size);
|
||||
} else {
|
||||
sbufWriteU8(payloadBuf, size);
|
||||
sbufWriteU8(payloadBuf, responsePacket.cmd);
|
||||
sbufWriteU8(payloadBuf, responsePacket.cmd);
|
||||
}
|
||||
} else { // MSPv2
|
||||
sbufWriteU8 (payloadBuf, responsePacket.flags); // MSPv2 flags
|
||||
|
|
|
@ -99,7 +99,7 @@ const adcTagMap_t adcTagMap[] = {
|
|||
void adcInitDevice(adcDevice_t *adcdev, int channelCount)
|
||||
{
|
||||
ADC_HandleTypeDef *hadc = &adcdev->ADCHandle;
|
||||
|
||||
|
||||
hadc->Instance = adcdev->ADCx;
|
||||
|
||||
hadc->Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV8;
|
||||
|
|
|
@ -81,7 +81,7 @@
|
|||
// #define DAL_MMC_MODULE_ENABLED
|
||||
|
||||
/* Value of the external high speed oscillator in Hz */
|
||||
#if !defined (HSE_VALUE)
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE 8000000U
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
|
@ -96,7 +96,7 @@
|
|||
#endif /* HSI_VALUE */
|
||||
|
||||
/* Value of the internal low speed oscillator in Hz */
|
||||
#if !defined (LSI_VALUE)
|
||||
#if !defined (LSI_VALUE)
|
||||
#define LSI_VALUE 32000U
|
||||
#endif /* LSI_VALUE */
|
||||
|
||||
|
@ -178,7 +178,7 @@
|
|||
#define EXT_PHY_CONFIG_MAX_DELAY 0x00000FFFU
|
||||
|
||||
#define EXT_PHY_READ_TIMEOUT 0x0000FFFFU
|
||||
#define EXT_PHY_WRITE_TIMEOUT 0x0000FFFFU
|
||||
#define EXT_PHY_WRITE_TIMEOUT 0x0000FFFFU
|
||||
|
||||
/* SPI peripheral configuration */
|
||||
|
||||
|
|
|
@ -30,8 +30,8 @@
|
|||
|
||||
/** @addtogroup apm32f4xx_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
*/
|
||||
|
||||
/** @addtogroup APM32F4xx_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
@ -45,7 +45,7 @@
|
|||
#include <string.h>
|
||||
|
||||
/* Value of the external oscillator in Hz */
|
||||
#if !defined (HSE_VALUE)
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE ((uint32_t)8000000U)
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
|
@ -185,7 +185,7 @@ void SystemInit(void)
|
|||
/**
|
||||
* @brief Update SystemCoreClock variable according to clock register values
|
||||
* The SystemCoreClock variable contains the core clock (HCLK)
|
||||
*
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
|
@ -211,7 +211,7 @@ void SystemCoreClockUpdate(void)
|
|||
case 0x08: /* PLL used as system clock source */
|
||||
pllClock = (RCM->PLL1CFG & RCM_PLL1CFG_PLL1CLKS) >> 22;
|
||||
pllb = RCM->PLL1CFG & RCM_PLL1CFG_PLLB;
|
||||
|
||||
|
||||
if (pllClock != 0)
|
||||
{
|
||||
/* HSE used as PLL clock source */
|
||||
|
@ -265,7 +265,7 @@ void DAL_SysClkConfig(void)
|
|||
else {
|
||||
// HSE frequency is given
|
||||
pll_src = RCM_PLLSOURCE_HSE;
|
||||
|
||||
|
||||
pll_m = hse_mhz / 2;
|
||||
if (pll_m * 2 != hse_mhz) {
|
||||
pll_m = hse_mhz;
|
||||
|
@ -302,8 +302,8 @@ void DAL_SysClkConfig(void)
|
|||
RCM_ClkInitStruct.ClockType = (RCM_CLOCKTYPE_SYSCLK | RCM_CLOCKTYPE_HCLK | RCM_CLOCKTYPE_PCLK1 | RCM_CLOCKTYPE_PCLK2);
|
||||
RCM_ClkInitStruct.SYSCLKSource = RCM_SYSCLKSOURCE_PLLCLK;
|
||||
RCM_ClkInitStruct.AHBCLKDivider = RCM_SYSCLK_DIV1;
|
||||
RCM_ClkInitStruct.APB1CLKDivider = RCM_HCLK_DIV4;
|
||||
RCM_ClkInitStruct.APB2CLKDivider = RCM_HCLK_DIV2;
|
||||
RCM_ClkInitStruct.APB1CLKDivider = RCM_HCLK_DIV4;
|
||||
RCM_ClkInitStruct.APB2CLKDivider = RCM_HCLK_DIV2;
|
||||
if(DAL_RCM_ClockConfig(&RCM_ClkInitStruct, FLASH_LATENCY_5) != DAL_OK)
|
||||
{
|
||||
DAL_ErrorHandler();
|
||||
|
@ -335,7 +335,7 @@ void DAL_SysClkConfig(void)
|
|||
*/
|
||||
void DAL_ErrorHandler(void)
|
||||
{
|
||||
/* When the function is needed, this function
|
||||
/* When the function is needed, this function
|
||||
could be implemented in the user file
|
||||
*/
|
||||
while(1)
|
||||
|
@ -344,8 +344,8 @@ void DAL_ErrorHandler(void)
|
|||
}
|
||||
|
||||
void AssertFailedHandler(uint8_t *file, uint32_t line)
|
||||
{
|
||||
/* When the function is needed, this function
|
||||
{
|
||||
/* When the function is needed, this function
|
||||
could be implemented in the user file
|
||||
*/
|
||||
UNUSED(file);
|
||||
|
@ -386,9 +386,9 @@ int SystemPLLSource(void)
|
|||
|
||||
/**
|
||||
* @brief Reboot the system if necessary after changing the overclock level
|
||||
*
|
||||
* @param overclockLevel
|
||||
*
|
||||
*
|
||||
* @param overclockLevel
|
||||
*
|
||||
* @retval None
|
||||
*/
|
||||
void OverclockRebootIfNecessary(uint32_t overclockLevel)
|
||||
|
@ -409,9 +409,9 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel)
|
|||
|
||||
/**
|
||||
* @brief Set the HSE value
|
||||
*
|
||||
* @param frequency
|
||||
*
|
||||
*
|
||||
* @param frequency
|
||||
*
|
||||
* @retval None
|
||||
*/
|
||||
void systemClockSetHSEValue(uint32_t frequency)
|
||||
|
@ -427,11 +427,11 @@ void systemClockSetHSEValue(uint32_t frequency)
|
|||
|
||||
/**
|
||||
* @brief Initialize the PLL parameters
|
||||
*
|
||||
*
|
||||
* @param None
|
||||
*
|
||||
*
|
||||
* @retval None
|
||||
*
|
||||
*
|
||||
*/
|
||||
static void SystemInitPLLParameters(void)
|
||||
{
|
||||
|
@ -457,7 +457,7 @@ static void SystemInitPLLParameters(void)
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
*
|
||||
* @file system_apm32f4xx.h
|
||||
*
|
||||
* @brief CMSIS Cortex-M4 Device System Source File for APM32F4xx devices.
|
||||
* @brief CMSIS Cortex-M4 Device System Source File for APM32F4xx devices.
|
||||
*
|
||||
* @version V1.0.0
|
||||
*
|
||||
|
@ -23,7 +23,7 @@
|
|||
* See the GEEHY SOFTWARE PACKAGE LICENSE for the governing permissions
|
||||
* and limitations under the License.
|
||||
*
|
||||
*/
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
|
@ -31,8 +31,8 @@
|
|||
|
||||
/** @addtogroup apm32f4xx_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Define to prevent recursive inclusion
|
||||
*/
|
||||
|
@ -41,7 +41,7 @@
|
|||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/** @addtogroup APM32F4xx_System_Includes
|
||||
* @{
|
||||
|
@ -83,7 +83,7 @@ extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */
|
|||
/** @addtogroup APM32F4xx_System_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
extern void SystemInit(void);
|
||||
extern void SystemCoreClockUpdate(void);
|
||||
extern void OverclockRebootIfNecessary(uint32_t overclockLevel);
|
||||
|
@ -106,7 +106,7 @@ extern void DAL_SysClkConfig(void);
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
|
|
|
@ -366,7 +366,7 @@ void configTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz)
|
|||
handle->Init.RepetitionCounter = 0x0000;
|
||||
|
||||
DAL_TMR_Base_Init(handle);
|
||||
if (tim == TMR1 || tim == TMR2 || tim == TMR3 || tim == TMR4 || tim == TMR5 || tim == TMR8 || tim == TMR9)
|
||||
if (tim == TMR1 || tim == TMR2 || tim == TMR3 || tim == TMR4 || tim == TMR5 || tim == TMR8 || tim == TMR9)
|
||||
{
|
||||
TMR_ClockConfigTypeDef sClockSourceConfig;
|
||||
memset(&sClockSourceConfig, 0, sizeof(sClockSourceConfig));
|
||||
|
|
|
@ -67,39 +67,39 @@ void OTG_HS1_IRQHandler(void)
|
|||
|
||||
#ifdef USE_USB_FS
|
||||
void OTG_FS_WKUP_IRQHandler(void)
|
||||
#else
|
||||
#else
|
||||
void OTG_HS1_WKUP_IRQHandler(void)
|
||||
#endif /* USE_USB_FS */
|
||||
{
|
||||
if((&husbDevice)->Init.low_power_enable)
|
||||
{
|
||||
/* Reset SLEEPDEEP bit of Cortex System Control Register */
|
||||
SCB->SCR &= (uint32_t)~((uint32_t)(SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk));
|
||||
|
||||
/* Configures system clock after wake-up from STOP: enable HSE, PLL and select
|
||||
SCB->SCR &= (uint32_t)~((uint32_t)(SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk));
|
||||
|
||||
/* Configures system clock after wake-up from STOP: enable HSE, PLL and select
|
||||
PLL as system clock source (HSE and PLL are disabled in STOP mode) */
|
||||
|
||||
|
||||
__DAL_RCM_HSE_CONFIG(RCM_HSE_ON);
|
||||
|
||||
/* Wait till HSE is ready */
|
||||
|
||||
/* Wait till HSE is ready */
|
||||
while(__DAL_RCM_GET_FLAG(RCM_FLAG_HSERDY) == RESET)
|
||||
{}
|
||||
|
||||
|
||||
/* Enable the main PLL. */
|
||||
__DAL_RCM_PLL_ENABLE();
|
||||
|
||||
/* Wait till PLL is ready */
|
||||
|
||||
/* Wait till PLL is ready */
|
||||
while(__DAL_RCM_GET_FLAG(RCM_FLAG_PLLRDY) == RESET)
|
||||
{}
|
||||
|
||||
|
||||
/* Select PLL as SYSCLK */
|
||||
MODIFY_REG(RCM->CFG, RCM_CFG_SCLKSEL, RCM_SYSCLKSOURCE_PLLCLK);
|
||||
|
||||
|
||||
while (__DAL_RCM_GET_SYSCLK_SOURCE() != RCM_CFG_SCLKSEL_PLL)
|
||||
{}
|
||||
|
||||
|
||||
/* ungate PHY clock */
|
||||
__DAL_PCD_UNGATE_PHYCLOCK((&husbDevice));
|
||||
__DAL_PCD_UNGATE_PHYCLOCK((&husbDevice));
|
||||
}
|
||||
#ifdef USE_USB_FS
|
||||
/* Clear EINT pending Bit*/
|
||||
|
@ -108,7 +108,7 @@ void OTG_HS1_WKUP_IRQHandler(void)
|
|||
/* Clear EINT pending Bit*/
|
||||
__DAL_USB_OTG_HS_WAKEUP_EINT_CLEAR_FLAG();
|
||||
#endif
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
@ -450,7 +450,7 @@ void USBD_HardwareInit(USBD_INFO_T* usbInfo)
|
|||
{
|
||||
DAL_ErrorHandler();
|
||||
}
|
||||
|
||||
|
||||
#if (USE_DAL_PCD_REGISTER_CALLBACKS == 1U)
|
||||
/* Register USB PCD CallBacks */
|
||||
DAL_PCD_RegisterCallback(&husbDevice, DAL_PCD_SOF_CB_ID, PCD_SOFCallback);
|
||||
|
|
|
@ -190,7 +190,7 @@ static uint8_t USBD_ConfigDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
0x00,
|
||||
/* bcdCDC: spec release number */
|
||||
0x10, 0x01,
|
||||
|
||||
|
||||
/* CDC Call Management Function Descriptor */
|
||||
/* bFunctionLength */
|
||||
0x05,
|
||||
|
@ -212,7 +212,7 @@ static uint8_t USBD_ConfigDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
0x02,
|
||||
/* bmCapabilities */
|
||||
0x02,
|
||||
|
||||
|
||||
/* CDC Union Function Descriptor */
|
||||
/* bFunctionLength */
|
||||
0x05,
|
||||
|
@ -224,7 +224,7 @@ static uint8_t USBD_ConfigDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
0x00,
|
||||
/* bSlaveInterface0: Data Class Interface */
|
||||
0x01,
|
||||
|
||||
|
||||
/* Endpoint 2 */
|
||||
/* bLength */
|
||||
0x07,
|
||||
|
@ -239,7 +239,7 @@ static uint8_t USBD_ConfigDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
USBD_CDC_CMD_MP_SIZE >> 8,
|
||||
/* bInterval: */
|
||||
USBD_CDC_FS_INTERVAL,
|
||||
|
||||
|
||||
/* CDC Data Interface */
|
||||
/* bLength */
|
||||
0x09,
|
||||
|
@ -259,7 +259,7 @@ static uint8_t USBD_ConfigDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
0x00,
|
||||
/* iInterface */
|
||||
0x00,
|
||||
|
||||
|
||||
/* Endpoint OUT */
|
||||
/* bLength */
|
||||
0x07,
|
||||
|
@ -274,7 +274,7 @@ static uint8_t USBD_ConfigDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
USBD_CDC_FS_MP_SIZE >> 8,
|
||||
/* bInterval: */
|
||||
0x00,
|
||||
|
||||
|
||||
/* Endpoint IN */
|
||||
/* bLength */
|
||||
0x07,
|
||||
|
@ -348,7 +348,7 @@ static uint8_t USBD_OtherSpeedCfgDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
0x00,
|
||||
/* bcdCDC: spec release number */
|
||||
0x10, 0x01,
|
||||
|
||||
|
||||
/* CDC Call Management Function Descriptor */
|
||||
/* bFunctionLength */
|
||||
0x05,
|
||||
|
@ -370,7 +370,7 @@ static uint8_t USBD_OtherSpeedCfgDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
0x02,
|
||||
/* bmCapabilities */
|
||||
0x02,
|
||||
|
||||
|
||||
/* CDC Union Function Descriptor */
|
||||
/* bFunctionLength */
|
||||
0x05,
|
||||
|
@ -382,7 +382,7 @@ static uint8_t USBD_OtherSpeedCfgDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
0x00,
|
||||
/* bSlaveInterface0: Data Class Interface */
|
||||
0x01,
|
||||
|
||||
|
||||
/* Endpoint 2 */
|
||||
/* bLength */
|
||||
0x07,
|
||||
|
@ -397,7 +397,7 @@ static uint8_t USBD_OtherSpeedCfgDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
USBD_CDC_CMD_MP_SIZE >> 8,
|
||||
/* bInterval: */
|
||||
USBD_CDC_FS_INTERVAL,
|
||||
|
||||
|
||||
/* CDC Data Interface */
|
||||
/* bLength */
|
||||
0x09,
|
||||
|
@ -417,7 +417,7 @@ static uint8_t USBD_OtherSpeedCfgDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
0x00,
|
||||
/* iInterface */
|
||||
0x00,
|
||||
|
||||
|
||||
/* Endpoint OUT */
|
||||
/* bLength */
|
||||
0x07,
|
||||
|
@ -432,7 +432,7 @@ static uint8_t USBD_OtherSpeedCfgDesc[USBD_CONFIG_DESCRIPTOR_SIZE] =
|
|||
USBD_CDC_FS_MP_SIZE >> 8,
|
||||
/* bInterval: */
|
||||
0x00,
|
||||
|
||||
|
||||
/* Endpoint IN */
|
||||
/* bLength */
|
||||
0x07,
|
||||
|
|
|
@ -162,7 +162,7 @@ static USBD_STA_T USBD_CDC_ItfCtrl(uint8_t command, uint8_t *buffer, uint16_t le
|
|||
case USBD_CDC_CLEAR_COMM_FEATURE:
|
||||
break;
|
||||
|
||||
/* Line Coding Data Structure
|
||||
/* Line Coding Data Structure
|
||||
* | Offset(Byte) | Field | Length | Desc |
|
||||
* | 0 | dwDTERate | 4 | Data Terminal rate |
|
||||
* | 4 | bCharFormat | 1 | Stop bits |
|
||||
|
@ -238,16 +238,16 @@ static USBD_STA_T USBD_CDC_ItfSend(uint8_t *buffer, uint16_t length)
|
|||
USBD_STA_T usbStatus = USBD_OK;
|
||||
|
||||
USBD_CDC_INFO_T *usbDevCDC = (USBD_CDC_INFO_T*)gUsbDevice.devClass[gUsbDevice.classID]->classData;
|
||||
|
||||
|
||||
if(usbDevCDC->cdcTx.state != USBD_CDC_XFER_IDLE)
|
||||
{
|
||||
return USBD_BUSY;
|
||||
}
|
||||
|
||||
|
||||
USBD_CDC_ConfigTxBuffer(&gUsbDevice, buffer, length);
|
||||
|
||||
|
||||
usbStatus = USBD_CDC_TxPacket(&gUsbDevice);
|
||||
|
||||
|
||||
return usbStatus;
|
||||
}
|
||||
|
||||
|
@ -285,7 +285,7 @@ static USBD_STA_T USBD_CDC_ItfSendEnd(uint8_t epNum, uint8_t *buffer, uint32_t *
|
|||
static USBD_STA_T USBD_CDC_ItfReceive(uint8_t *buffer, uint32_t *length)
|
||||
{
|
||||
USBD_STA_T usbStatus = USBD_OK;
|
||||
|
||||
|
||||
// USBD_CDC_ConfigRxBuffer(&gUsbDevice, &buffer[0]);
|
||||
rxAvailable = *length;
|
||||
rxBuffPtr = buffer;
|
||||
|
@ -295,7 +295,7 @@ static USBD_STA_T USBD_CDC_ItfReceive(uint8_t *buffer, uint32_t *length)
|
|||
// The USB protocol requires that an empty (0 byte) packet immediately follow.
|
||||
USBD_CDC_RxPacket(&gUsbDevice);
|
||||
}
|
||||
|
||||
|
||||
return usbStatus;
|
||||
}
|
||||
|
||||
|
|
|
@ -20,21 +20,21 @@
|
|||
|
||||
/**
|
||||
* Read internal and external analog channels
|
||||
*
|
||||
*
|
||||
* Internal channels provide temperature and the internal voltage reference
|
||||
* External channels are for vbat, rssi, current and a generic 'external' inputs
|
||||
*
|
||||
* The ADC is free running and so doesn't require a timer. Samples are moved from
|
||||
*
|
||||
* The ADC is free running and so doesn't require a timer. Samples are moved from
|
||||
* the ADC output register to a buffer by DMA
|
||||
*
|
||||
*
|
||||
* The sample rate is kept low to reduce impact on the DMA controller, and the lowest
|
||||
* priority is set for the DMA transfer. It's also recommended to use the highest numbered
|
||||
* DMA channel on the dma controller for ADC, since that is the lowest priority channel
|
||||
* for transfers at the same DMA priority.
|
||||
*
|
||||
*
|
||||
* Sample rate is set between 1 and 2kHz by using a long input sampling time and reasonably
|
||||
* high hardware oversampling.
|
||||
*
|
||||
*
|
||||
* Note that only ADC1 is used, although the code contains remnants of support for all
|
||||
* three ADC.
|
||||
*/
|
||||
|
@ -123,12 +123,12 @@ static volatile DMA_DATA uint32_t adcConversionBuffer[ADC_CHANNEL_COUNT];
|
|||
|
||||
/**
|
||||
* Initialise the specified ADC to read multiple channels in repeat mode
|
||||
*
|
||||
*
|
||||
* Sets 12 bit resolution, right aligned
|
||||
*
|
||||
*
|
||||
* @param dev Specifies the ADC device to use
|
||||
* @param channelCount how many channels to repeat over
|
||||
*
|
||||
*
|
||||
*/
|
||||
void adcInitDevice(const adc_type *dev, const int channelCount)
|
||||
{
|
||||
|
@ -146,7 +146,7 @@ void adcInitDevice(const adc_type *dev, const int channelCount)
|
|||
|
||||
/**
|
||||
* Find a given pin (defined by ioTag) in the map
|
||||
*
|
||||
*
|
||||
* @param tag the ioTag to search for
|
||||
* @return the index in adcTagMap corresponding to the given ioTag or -1 if not found
|
||||
*/
|
||||
|
@ -164,12 +164,12 @@ int adcFindTagMapEntry(const ioTag_t tag)
|
|||
* Setup the scaling offsets and factors used in adc.c
|
||||
* @see src/main/drivers/adc.c
|
||||
* @see src/main/drivers/adc_impl.h
|
||||
*
|
||||
*
|
||||
* There are a number of global calibration/scaling factors used in src/main/drivers/adc.c that need to
|
||||
* be set to appropriate values if we want to re-use existing code, e.g. adcInternalComputeTemperature
|
||||
* (the alternative would be to duplicate the code into ST and AT specific versions).
|
||||
* This is made a little confusing since the implementation based on ST datasheets approaches the calculation with
|
||||
* different formula and express the scaling factors in different units compared to the AT datasheets.
|
||||
* different formula and express the scaling factors in different units compared to the AT datasheets.
|
||||
* The constants are defined in src/main/drivers/adc_impl.h. It seems clearest to use the units from
|
||||
* the datasheet when defining those values, so here we have to convert to what's expected in
|
||||
* adcInternalComputeTemperature.
|
||||
|
@ -196,36 +196,36 @@ void setScalingFactors(void)
|
|||
/**
|
||||
* Setup the ADC so that it's running in the background and ready to
|
||||
* provide channel data
|
||||
*
|
||||
*
|
||||
* Notes:
|
||||
* This code only uses ADC1 despite appearances to the contrary, and has not been tested with the other ADCs
|
||||
*
|
||||
*
|
||||
* From the RM:
|
||||
* ADCCLK must be less than 80 MHz, while the ADCCLK frequency must be lower than PCLK2
|
||||
*
|
||||
*
|
||||
* PCLK2 looks like it's running at 144Mhz, but should be confirmed
|
||||
*
|
||||
*
|
||||
* With HCLK of 288, a divider of 4 gives an ADCCLK of 72MHz
|
||||
*
|
||||
* sample time is
|
||||
*
|
||||
* sample time is
|
||||
* ADC_SAMPLE + nbits + 0.5 ADCCLK periods
|
||||
*
|
||||
*
|
||||
* So with 12bit samples and ADC_SAMPLE_92_5 that's 105 clks.
|
||||
*
|
||||
* We're using HCLK/4, so 288/4 = 72MHz, each tick is 14ns. Add 5 clks for the interval between conversions,
|
||||
*
|
||||
* We're using HCLK/4, so 288/4 = 72MHz, each tick is 14ns. Add 5 clks for the interval between conversions,
|
||||
* 110 clks total is 1.54us per channel.
|
||||
*
|
||||
*
|
||||
* Max 6 channels is a total of 9.24us, or a basic sample rate of 108kHz per channel
|
||||
*
|
||||
*
|
||||
* If we use 64x oversampling we'll get an effective rate of 1.7kHz per channel which should still be plenty.
|
||||
*
|
||||
*
|
||||
* (RM and DS mention fast and slow channels, but don't give details on how this affects the above.
|
||||
* It's not relevant to our use case, so ignore the difference for now)
|
||||
*
|
||||
*
|
||||
* Called from fc/init.c
|
||||
*
|
||||
*
|
||||
* @param config - defines the channels to use for each external input (vbat, rssi, current, external) and also has calibration values for the temperature sensor
|
||||
*
|
||||
*
|
||||
*/
|
||||
void adcInit(const adcConfig_t *config)
|
||||
{
|
||||
|
@ -276,7 +276,7 @@ void adcInit(const adcConfig_t *config)
|
|||
|
||||
// Since ADC1 can do all channels this will only ever return adc1 and is unnecessary
|
||||
|
||||
// Find an ADC instance that can be used for the given TagMap index.
|
||||
// Find an ADC instance that can be used for the given TagMap index.
|
||||
// for (dev = 0; dev < ADCDEV_COUNT; dev++) {
|
||||
// #ifndef USE_DMA_SPEC
|
||||
// if (!adcDevice[dev].ADCx || !adcDevice[dev].dmaResource) {
|
||||
|
@ -459,13 +459,13 @@ uint16_t adcInternalRead(int channel)
|
|||
|
||||
/**
|
||||
* Read the internal Vref and return raw value
|
||||
*
|
||||
*
|
||||
* The internal Vref is 1.2V and can be used to calculate the external Vref+
|
||||
* External Vref+ determines the scale for the raw ADC readings but since it
|
||||
* is often directly connected to Vdd (approx 3.3V) it isn't accurately controlled.
|
||||
* Calculating the actual value of Vref+ by using measurements of the known 1.2V
|
||||
* internal reference can improve overall accuracy.
|
||||
*
|
||||
*
|
||||
* @return the raw ADC reading for the internal voltage reference
|
||||
* @see adcInternalCompensateVref in src/main/drivers/adc.c
|
||||
*/
|
||||
|
@ -478,7 +478,7 @@ uint16_t adcInternalReadVrefint(void)
|
|||
|
||||
/**
|
||||
* Read the internal temperature sensor
|
||||
*
|
||||
*
|
||||
* @return the raw ADC reading
|
||||
*/
|
||||
uint16_t adcInternalReadTempsensor(void)
|
||||
|
|
|
@ -84,7 +84,7 @@ void bbTimerChannelInit(bbPort_t *bbPort)
|
|||
TIM_OCInitTypeDef TIM_OCStruct;
|
||||
|
||||
TIM_OCStructInit(&TIM_OCStruct);
|
||||
|
||||
|
||||
TIM_OCStruct.oc_mode = TMR_OUTPUT_CONTROL_PWM_MODE_A;
|
||||
TIM_OCStruct.oc_idle_state = TRUE;
|
||||
TIM_OCStruct.oc_output_state = TRUE;
|
||||
|
@ -106,7 +106,7 @@ void bbTimerChannelInit(bbPort_t *bbPort)
|
|||
if (timhw->tag) {
|
||||
IO_t io = IOGetByTag(timhw->tag);
|
||||
IOConfigGPIOAF(io, IOCFG_AF_PP, timhw->alternateFunction);
|
||||
IOInit(io, OWNER_DSHOT_BITBANG, 0);
|
||||
IOInit(io, OWNER_DSHOT_BITBANG, 0);
|
||||
TIM_CtrlPWMOutputs(timhw->tim, TRUE);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -45,15 +45,15 @@
|
|||
|
||||
/**
|
||||
* Convert from BF channel to AT32 constants for timer output channels
|
||||
*
|
||||
*
|
||||
* The AT and ST apis take a different approach to naming channels, so just passing the bf
|
||||
* channel number to the AT calls doesn't work. This function maps between them.
|
||||
*
|
||||
*
|
||||
* @param bfChannel a channel number as used in timerHardware->channel (1 based)
|
||||
* @param useNChannel indicates that the desired channel should be the complementary output (only available for 1 through 3)
|
||||
* @return an AT32 tmr_channel_select_type constant
|
||||
* XXX what to return for invalid inputs? The tmr_channel_select_type enum doesn't have a suitable value
|
||||
*
|
||||
*
|
||||
* @see TIM_CH_TO_SELCHANNEL macro
|
||||
*/
|
||||
tmr_channel_select_type toCHSelectType(const uint8_t bfChannel, const bool useNChannel)
|
||||
|
@ -110,7 +110,7 @@ tmr_channel_select_type toCHSelectType(const uint8_t bfChannel, const bool useNC
|
|||
|
||||
/**
|
||||
* Enable the timer channels for all motors
|
||||
*
|
||||
*
|
||||
* Called once for every dshot update if telemetry is being used (not just enabled by #def)
|
||||
* Called from pwm_output_dshot_shared.c pwmTelemetryDecode
|
||||
*/
|
||||
|
@ -128,7 +128,7 @@ void dshotEnableChannels(uint8_t motorCount)
|
|||
|
||||
/**
|
||||
* Set the timer and dma of the specified motor for use as an output
|
||||
*
|
||||
*
|
||||
* Called from pwmDshotMotorHardwareConfig in this file and also from
|
||||
* pwmTelemetryDecode in src/main/drivers/pwm_output_dshot_shared.c
|
||||
*/
|
||||
|
@ -199,9 +199,9 @@ FAST_CODE void pwmDshotSetDirectionOutput(
|
|||
tmr_channel_enable(timer, toCHSelectType(channel, useCompOut), TRUE);
|
||||
timerOCPreloadConfig(timer, channel, TRUE);
|
||||
|
||||
pDmaInit->direction = DMA_DIR_MEMORY_TO_PERIPHERAL;
|
||||
pDmaInit->direction = DMA_DIR_MEMORY_TO_PERIPHERAL;
|
||||
xDMA_Init(dmaRef, pDmaInit);
|
||||
|
||||
|
||||
// Generate an interrupt when the transfer is complete
|
||||
xDMA_ITConfig(dmaRef, DMA_FDT_INT, TRUE);
|
||||
|
||||
|
@ -241,7 +241,7 @@ static void pwmDshotSetDirectionInput(motorDmaOutput_t * const motor)
|
|||
|
||||
/**
|
||||
* Start the timers and dma requests to send dshot data to all motors
|
||||
*
|
||||
*
|
||||
* Called after pwm_output_dshot_shared.c has finished setting up the buffers that represent the dshot packets.
|
||||
* Iterates over all the timers needed (note that there may be less timers than motors since a single timer can run
|
||||
* multiple motors) and enables each one.
|
||||
|
@ -298,8 +298,8 @@ void pwmCompleteDshotMotorUpdate(void)
|
|||
|
||||
/**
|
||||
* Interrupt handler called at the end of each packet
|
||||
*
|
||||
* Responsible for switching the dshot direction after sending a dshot command so that we
|
||||
*
|
||||
* Responsible for switching the dshot direction after sending a dshot command so that we
|
||||
* can receive dshot telemetry. If telemetry is not enabled, disables the dma and request generation.
|
||||
*/
|
||||
FAST_CODE static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||
|
@ -360,7 +360,7 @@ FAST_CODE static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
|||
} // if DMA_IT_TCIF
|
||||
}
|
||||
|
||||
bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex,
|
||||
bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex,
|
||||
motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
|
||||
{
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
|
@ -422,7 +422,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
// Boolean configureTimer is always true when different channels of the same timer are processed in sequence,
|
||||
// causing the timer and the associated DMA initialized more than once.
|
||||
// To fix this, getTimerIndex must be expanded to return if a new timer has been requested.
|
||||
// However, since the initialization is idempotent (can be applied multiple times without changing the outcome),
|
||||
// However, since the initialization is idempotent (can be applied multiple times without changing the outcome),
|
||||
// it is left as is in a favor of flash space (for now).
|
||||
const uint8_t timerIndex = getTimerIndex(timer);
|
||||
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
||||
|
@ -571,7 +571,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
|
||||
{ // local scope
|
||||
const tmr_channel_select_type chSel = toCHSelectType(timerHardware->channel, output & TIMER_OUTPUT_N_CHANNEL);
|
||||
tmr_channel_enable(timer, chSel, TRUE);
|
||||
tmr_channel_enable(timer, chSel, TRUE);
|
||||
}
|
||||
|
||||
if (configureTimer) {
|
||||
|
@ -587,7 +587,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
*timerChCCR(timerHardware) = 0xffff;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
motor->configured = true;
|
||||
|
||||
return true;
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -43,7 +43,7 @@ extern "C" {
|
|||
/** @addtogroup AT32F435_437
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @addtogroup Library_configuration_section
|
||||
* @{
|
||||
*/
|
||||
|
@ -376,7 +376,7 @@ typedef __I uint16_t vuc16; /*!< read only */
|
|||
typedef __I uint8_t vuc8; /*!< read only */
|
||||
|
||||
typedef enum {RESET = 0, SET = !RESET} flag_status;
|
||||
typedef enum {FALSE = 0, TRUE = !FALSE} confirm_state;
|
||||
typedef enum {FALSE = 0, TRUE = !FALSE} confirm_state;
|
||||
typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
||||
|
||||
/**
|
||||
|
@ -480,7 +480,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
|||
#define USART1_BASE (APB2PERIPH_BASE + 0x1000)
|
||||
#define TMR8_BASE (APB2PERIPH_BASE + 0x0400)
|
||||
#define TMR1_BASE (APB2PERIPH_BASE + 0x0000)
|
||||
/* ahb bus base address */
|
||||
/* ahb bus base address */
|
||||
#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000)
|
||||
#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400)
|
||||
#define GPIOH_BASE (AHBPERIPH1_BASE + 0x1C00)
|
||||
|
@ -640,7 +640,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
|||
#define USART1_BASE (APB2PERIPH_BASE + 0x1000)
|
||||
#define TMR8_BASE (APB2PERIPH_BASE + 0x0400)
|
||||
#define TMR1_BASE (APB2PERIPH_BASE + 0x0000)
|
||||
/* ahb bus base address */
|
||||
/* ahb bus base address */
|
||||
#define OTGFS2_BASE (AHBPERIPH1_BASE + 0x20000)
|
||||
#define SDIO1_BASE (AHBPERIPH1_BASE + 0xC400)
|
||||
#define EMAC_BASE (AHBPERIPH1_BASE + 0x8000)
|
||||
|
@ -718,7 +718,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
|||
#define EDMA_STREAM6_2D_BASE (EDMA_2D_BASE + 0x002C)
|
||||
#define EDMA_STREAM7_2D_BASE (EDMA_2D_BASE + 0x0034)
|
||||
#define EDMA_STREAM8_2D_BASE (EDMA_2D_BASE + 0x003C)
|
||||
|
||||
|
||||
#define EDMA_LL_BASE (EDMA_BASE + 0x00D0)
|
||||
#define EDMA_STREAM1_LL_BASE (EDMA_LL_BASE + 0x0004)
|
||||
#define EDMA_STREAM2_LL_BASE (EDMA_LL_BASE + 0x0008)
|
||||
|
@ -760,7 +760,7 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} error_status;
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
|
|
@ -5,11 +5,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -51,7 +51,7 @@ void system_clock_config(void)
|
|||
|
||||
/* config ldo voltage */
|
||||
pwc_ldo_output_voltage_set(PWC_LDO_OUTPUT_1V3);
|
||||
|
||||
|
||||
/* set the flash clock divider */
|
||||
flash_clock_divider_set(FLASH_CLOCK_DIV_3);
|
||||
|
||||
|
|
|
@ -5,11 +5,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
|
|
@ -5,11 +5,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -38,7 +38,7 @@ extern "C" {
|
|||
#define NULL ((void *) 0)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* @brief in the following line adjust the value of high speed exernal crystal (hext)
|
||||
* used in your application
|
||||
|
@ -172,7 +172,7 @@ extern "C" {
|
|||
#ifdef USB_MODULE_ENABLED
|
||||
#include "at32f435_437_usb.h"
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -175,7 +175,7 @@ extern void _init(void) {;}
|
|||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -39,7 +39,7 @@ extern "C" {
|
|||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup AT32F435_437_system_exported_variables
|
||||
/** @defgroup AT32F435_437_system_exported_variables
|
||||
* @{
|
||||
*/
|
||||
extern unsigned int system_core_clock; /*!< system clock frequency (core clock) */
|
||||
|
@ -48,10 +48,10 @@ extern unsigned int system_core_clock; /*!< system clock frequency (core clock)
|
|||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup AT32F435_437_system_exported_functions
|
||||
/** @defgroup AT32F435_437_system_exported_functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
extern void SystemInit(void);
|
||||
extern void system_core_clock_update(void);
|
||||
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
**************************************************************************
|
||||
* Copyright notice & Disclaimer
|
||||
*
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* The software Board Support Package (BSP) that is made available to
|
||||
* download from Artery official website is the copyrighted work of Artery.
|
||||
* Artery authorizes customers to use, copy, and distribute the BSP
|
||||
* software and its related documentation for the purpose of design and
|
||||
* development in conjunction with Artery microcontrollers. Use of the
|
||||
* software is governed by this copyright notice and the following disclaimer.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
|
||||
|
@ -23,7 +23,7 @@
|
|||
*
|
||||
**************************************************************************
|
||||
*/
|
||||
|
||||
|
||||
/* define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __USB_CONF_H
|
||||
#define __USB_CONF_H
|
||||
|
@ -31,7 +31,7 @@
|
|||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
#include "at32f435_437_usb.h"
|
||||
#include "at32f435_437.h"
|
||||
//#include "stdio.h"
|
||||
|
@ -39,7 +39,7 @@ extern "C" {
|
|||
/** @addtogroup AT32F437_periph_examples
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @addtogroup 437_USB_device_vcp_loopback
|
||||
* @{
|
||||
*/
|
||||
|
@ -206,11 +206,11 @@ void usb_delay_ms(uint32_t ms);
|
|||
void usb_delay_us(uint32_t us);
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -353,7 +353,7 @@ void adcInit(const adcConfig_t *config)
|
|||
|
||||
adc->ADCHandle.Instance = adc->ADCx;
|
||||
|
||||
if (HAL_ADC_DeInit(&adc->ADCHandle) != HAL_OK) {
|
||||
if (HAL_ADC_DeInit(&adc->ADCHandle) != HAL_OK) {
|
||||
// ADC de-initialization Error
|
||||
handleError();
|
||||
}
|
||||
|
|
|
@ -395,7 +395,7 @@ void adcInit(const adcConfig_t *config)
|
|||
|
||||
adc->ADCHandle.Instance = adc->ADCx;
|
||||
|
||||
if (HAL_ADC_DeInit(&adc->ADCHandle) != HAL_OK) {
|
||||
if (HAL_ADC_DeInit(&adc->ADCHandle) != HAL_OK) {
|
||||
// ADC de-initialization Error
|
||||
errorHandler();
|
||||
}
|
||||
|
|
|
@ -310,7 +310,7 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
|
|||
}
|
||||
initTx->NbData = len;
|
||||
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
if (dev->bus->dmaRx) {
|
||||
#endif
|
||||
uint8_t *rxData = segment->u.buffers.rxData;
|
||||
|
@ -341,7 +341,7 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
|
|||
initRx->MemoryOrM2MDstIncMode = LL_DMA_MEMORY_NOINCREMENT;
|
||||
}
|
||||
initRx->NbData = len;
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -353,7 +353,7 @@ void spiInternalStartDMA(const extDevice_t *dev)
|
|||
dmaChannelDescriptor_t *dmaTx = bus->dmaTx;
|
||||
dmaChannelDescriptor_t *dmaRx = bus->dmaRx;
|
||||
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
if (dmaRx) {
|
||||
#endif
|
||||
// Use the correct callback argument
|
||||
|
@ -421,7 +421,7 @@ void spiInternalStartDMA(const extDevice_t *dev)
|
|||
|
||||
SET_BIT(dev->bus->busType_u.spi.instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
|
||||
#endif
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
} else {
|
||||
DMA_Stream_TypeDef *streamRegsTx = (DMA_Stream_TypeDef *)dmaTx->ref;
|
||||
|
||||
|
@ -485,7 +485,7 @@ void spiInternalStopDMA (const extDevice_t *dev)
|
|||
LL_SPI_ClearFlag_TXTF(dev->bus->busType_u.spi.instance);
|
||||
LL_SPI_Disable(dev->bus->busType_u.spi.instance);
|
||||
#endif
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
} else {
|
||||
SPI_TypeDef *instance = bus->busType_u.spi.instance;
|
||||
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
******************************************************************************
|
||||
* @file stm32h7xx_hal_conf_template.h
|
||||
* @author MCD Application Team
|
||||
* @brief HAL configuration template file.
|
||||
* @brief HAL configuration template file.
|
||||
* This file should be copied to the application folder and renamed
|
||||
* to stm32h7xx_hal_conf.h.
|
||||
******************************************************************************
|
||||
|
@ -33,7 +33,7 @@
|
|||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32H7xx_HAL_CONF_H
|
||||
|
@ -48,15 +48,15 @@
|
|||
|
||||
/* ########################## Module Selection ############################## */
|
||||
/**
|
||||
* @brief This is the list of modules to be used in the HAL driver
|
||||
* @brief This is the list of modules to be used in the HAL driver
|
||||
*/
|
||||
#define HAL_MODULE_ENABLED
|
||||
#define HAL_ADC_MODULE_ENABLED
|
||||
#define HAL_MODULE_ENABLED
|
||||
#define HAL_ADC_MODULE_ENABLED
|
||||
//#define HAL_CEC_MODULE_ENABLED
|
||||
//#define HAL_COMP_MODULE_ENABLED
|
||||
//#define HAL_CORDIC_MODULE_ENABLED
|
||||
#define HAL_CORTEX_MODULE_ENABLED
|
||||
//#define HAL_CRC_MODULE_ENABLED
|
||||
//#define HAL_CRC_MODULE_ENABLED
|
||||
//#define HAL_CRYP_MODULE_ENABLED
|
||||
#define HAL_DAC_MODULE_ENABLED
|
||||
//#define HAL_DCMI_MODULE_ENABLED
|
||||
|
@ -68,7 +68,7 @@
|
|||
//#define HAL_ETH_MODULE_ENABLED
|
||||
//#define HAL_EXTI_MODULE_ENABLED
|
||||
//#define HAL_FDCAN_MODULE_ENABLED
|
||||
#define HAL_FLASH_MODULE_ENABLED
|
||||
#define HAL_FLASH_MODULE_ENABLED
|
||||
//#define HAL_GFXMMU_MODULE_ENABLED
|
||||
//#define HAL_FMAC_MODULE_ENABLED
|
||||
#define HAL_GPIO_MODULE_ENABLED
|
||||
|
@ -78,14 +78,14 @@
|
|||
//#define HAL_HSEM_MODULE_ENABLED
|
||||
#define HAL_I2C_MODULE_ENABLED
|
||||
//#define HAL_I2S_MODULE_ENABLED
|
||||
//#define HAL_IRDA_MODULE_ENABLED
|
||||
//#define HAL_IWDG_MODULE_ENABLED
|
||||
//#define HAL_IRDA_MODULE_ENABLED
|
||||
//#define HAL_IWDG_MODULE_ENABLED
|
||||
//#define HAL_JPEG_MODULE_ENABLED
|
||||
//#define HAL_LPTIM_MODULE_ENABLED
|
||||
//#define HAL_LTDC_MODULE_ENABLED
|
||||
//#define HAL_MDIOS_MODULE_ENABLED
|
||||
#define HAL_MDMA_MODULE_ENABLED
|
||||
//#define HAL_MMC_MODULE_ENABLED
|
||||
#define HAL_MDMA_MODULE_ENABLED
|
||||
//#define HAL_MMC_MODULE_ENABLED
|
||||
//#define HAL_NAND_MODULE_ENABLED
|
||||
//#define HAL_NOR_MODULE_ENABLED
|
||||
//#define HAL_OPAMP_MODULE_ENABLED
|
||||
|
@ -96,30 +96,30 @@
|
|||
//#define HAL_PSSI_MODULE_ENABLED
|
||||
#define HAL_QSPI_MODULE_ENABLED
|
||||
//#define HAL_RAMECC_MODULE_ENABLED
|
||||
#define HAL_RCC_MODULE_ENABLED
|
||||
//#define HAL_RNG_MODULE_ENABLED
|
||||
#define HAL_RCC_MODULE_ENABLED
|
||||
//#define HAL_RNG_MODULE_ENABLED
|
||||
#define HAL_RTC_MODULE_ENABLED
|
||||
//#define HAL_SAI_MODULE_ENABLED
|
||||
#define HAL_SD_MODULE_ENABLED
|
||||
//#define HAL_SAI_MODULE_ENABLED
|
||||
#define HAL_SD_MODULE_ENABLED
|
||||
//#define HAL_SDRAM_MODULE_ENABLED
|
||||
//#define HAL_SMARTCARD_MODULE_ENABLED
|
||||
//#define HAL_SMBUS_MODULE_ENABLED
|
||||
//#define HAL_SPDIFRX_MODULE_ENABLED
|
||||
//#define HAL_SMARTCARD_MODULE_ENABLED
|
||||
//#define HAL_SMBUS_MODULE_ENABLED
|
||||
//#define HAL_SPDIFRX_MODULE_ENABLED
|
||||
//#define HAL_SPI_MODULE_ENABLED
|
||||
//#define HAL_SRAM_MODULE_ENABLED
|
||||
//#define HAL_SWPMI_MODULE_ENABLED
|
||||
#define HAL_TIM_MODULE_ENABLED
|
||||
#define HAL_UART_MODULE_ENABLED
|
||||
#define HAL_USART_MODULE_ENABLED
|
||||
//#define HAL_SWPMI_MODULE_ENABLED
|
||||
#define HAL_TIM_MODULE_ENABLED
|
||||
#define HAL_UART_MODULE_ENABLED
|
||||
#define HAL_USART_MODULE_ENABLED
|
||||
//#define HAL_WWDG_MODULE_ENABLED
|
||||
|
||||
/* ########################## Oscillator Values adaptation ####################*/
|
||||
/**
|
||||
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSE is used as system clock source, directly or through the PLL).
|
||||
* (when HSE is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSE_VALUE)
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE (25000000UL) /*!< Value of the External oscillator in Hz */
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
|
@ -134,11 +134,11 @@
|
|||
#if !defined (CSI_VALUE)
|
||||
#define CSI_VALUE (4000000UL) /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* CSI_VALUE */
|
||||
|
||||
|
||||
/**
|
||||
* @brief Internal High Speed oscillator (HSI) value.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSI is used as system clock source, directly or through the PLL).
|
||||
* (when HSI is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSI_VALUE)
|
||||
#define HSI_VALUE (64000000UL) /*!< Value of the Internal oscillator in Hz*/
|
||||
|
@ -152,7 +152,7 @@
|
|||
#define LSE_VALUE (32768UL) /*!< Value of the External oscillator in Hz*/
|
||||
#endif /* LSE_VALUE */
|
||||
|
||||
|
||||
|
||||
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||
#define LSE_STARTUP_TIMEOUT (5000UL) /*!< Time out for LSE start up, in ms */
|
||||
#endif /* LSE_STARTUP_TIMEOUT */
|
||||
|
@ -165,8 +165,8 @@
|
|||
|
||||
/**
|
||||
* @brief External clock source for I2S peripheral
|
||||
* This value is used by the I2S HAL module to compute the I2S clock source
|
||||
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||
* This value is used by the I2S HAL module to compute the I2S clock source
|
||||
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||
*/
|
||||
#if !defined (EXTERNAL_CLOCK_VALUE)
|
||||
#define EXTERNAL_CLOCK_VALUE 12288000UL /*!< Value of the External clock in Hz*/
|
||||
|
@ -178,7 +178,7 @@
|
|||
/* ########################### System Configuration ######################### */
|
||||
/**
|
||||
* @brief This is the HAL system configuration section
|
||||
*/
|
||||
*/
|
||||
#define VDD_VALUE (3300UL) /*!< Value of VDD in mv */
|
||||
#define TICK_INT_PRIORITY (0x0FUL) /*!< tick interrupt priority */
|
||||
#define USE_RTOS 0
|
||||
|
@ -188,7 +188,7 @@
|
|||
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
|
||||
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
|
||||
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */
|
||||
#define USE_HAL_CORDIC_REGISTER_CALLBACKS 0U /* CORDIC register callback disabled */
|
||||
#define USE_HAL_CORDIC_REGISTER_CALLBACKS 0U /* CORDIC register callback disabled */
|
||||
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
|
||||
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
|
||||
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
|
||||
|
@ -198,7 +198,7 @@
|
|||
#define USE_HAL_DTS_REGISTER_CALLBACKS 0U /* DTS register callback disabled */
|
||||
#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
|
||||
#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0U /* FDCAN register callback disabled */
|
||||
#define USE_HAL_FMAC_REGISTER_CALLBACKS 0U /* FMAC register callback disabled */
|
||||
#define USE_HAL_FMAC_REGISTER_CALLBACKS 0U /* FMAC register callback disabled */
|
||||
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
|
||||
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
|
||||
#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
|
||||
|
@ -247,7 +247,7 @@
|
|||
|
||||
/* ########################## Assert Selection ############################## */
|
||||
/**
|
||||
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||
* HAL drivers code
|
||||
*/
|
||||
/* #define USE_FULL_ASSERT 1 */
|
||||
|
@ -256,7 +256,7 @@
|
|||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Include module's header file
|
||||
* @brief Include module's header file
|
||||
*/
|
||||
|
||||
#ifdef HAL_RCC_MODULE_ENABLED
|
||||
|
@ -336,7 +336,7 @@
|
|||
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRYP_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_cryp.h"
|
||||
#include "stm32h7xx_hal_cryp.h"
|
||||
#endif /* HAL_CRYP_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DAC_MODULE_ENABLED
|
||||
|
@ -374,7 +374,7 @@
|
|||
#ifdef HAL_NAND_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_nand.h"
|
||||
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||
|
||||
|
||||
#ifdef HAL_I2C_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_i2c.h"
|
||||
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||
|
@ -398,7 +398,7 @@
|
|||
#ifdef HAL_MMC_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_mmc.h"
|
||||
#endif /* HAL_MMC_MODULE_ENABLED */
|
||||
|
||||
|
||||
#ifdef HAL_LPTIM_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_lptim.h"
|
||||
#endif /* HAL_LPTIM_MODULE_ENABLED */
|
||||
|
@ -410,7 +410,7 @@
|
|||
#ifdef HAL_OPAMP_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_opamp.h"
|
||||
#endif /* HAL_OPAMP_MODULE_ENABLED */
|
||||
|
||||
|
||||
#ifdef HAL_OSPI_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_ospi.h"
|
||||
#endif /* HAL_OSPI_MODULE_ENABLED */
|
||||
|
@ -430,7 +430,7 @@
|
|||
#ifdef HAL_QSPI_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_qspi.h"
|
||||
#endif /* HAL_QSPI_MODULE_ENABLED */
|
||||
|
||||
|
||||
#ifdef HAL_RAMECC_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_ramecc.h"
|
||||
#endif /* HAL_RAMECC_MODULE_ENABLED */
|
||||
|
@ -454,7 +454,7 @@
|
|||
#ifdef HAL_SDRAM_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_sdram.h"
|
||||
#endif /* HAL_SDRAM_MODULE_ENABLED */
|
||||
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_spi.h"
|
||||
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||
|
@ -494,7 +494,7 @@
|
|||
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_wwdg.h"
|
||||
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||
|
||||
|
||||
#ifdef HAL_PCD_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_pcd.h"
|
||||
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||
|
@ -502,14 +502,14 @@
|
|||
#ifdef HAL_HCD_MODULE_ENABLED
|
||||
#include "stm32h7xx_hal_hcd.h"
|
||||
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
|
@ -525,6 +525,6 @@
|
|||
#endif
|
||||
|
||||
#endif /* __STM32H7xx_HAL_CONF_H */
|
||||
|
||||
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||
|
|
|
@ -176,7 +176,7 @@ int SystemSYSCLKSource(void)
|
|||
case 0: // can't happen, fall through
|
||||
FALLTHROUGH;
|
||||
case 1:
|
||||
src = 0; // HSI
|
||||
src = 0; // HSI
|
||||
break;
|
||||
|
||||
case 2:
|
||||
|
@ -218,7 +218,7 @@ void Error_Handler(void)
|
|||
*
|
||||
* If mhz == 27 then scale it down to 9 with PLL=19 for base 171MHz with PLLN increment of 3 (9 * 3 = 27MHz a part)
|
||||
*
|
||||
* We don't prepare a separate frequency selection for 27MHz series in CLI, so what is set with "cpu_overclock"
|
||||
* We don't prepare a separate frequency selection for 27MHz series in CLI, so what is set with "cpu_overclock"
|
||||
* will result in slightly higher clock when examined with "status" command.
|
||||
*/
|
||||
|
||||
|
@ -307,7 +307,7 @@ void systemClockSetHSEValue(uint32_t frequency)
|
|||
|
||||
if (freqMhz != 27 && (freqMhz / 8) * 8 != freqMhz) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
|
||||
|
||||
|
@ -354,7 +354,7 @@ void OverclockRebootIfNecessary(unsigned requestedOverclockLevel)
|
|||
* @brief System Clock Configuration
|
||||
* @retval None
|
||||
*/
|
||||
// Extracted from MX generated main.c
|
||||
// Extracted from MX generated main.c
|
||||
|
||||
void SystemClock_Config(void)
|
||||
{
|
||||
|
@ -365,11 +365,11 @@ void SystemClock_Config(void)
|
|||
|
||||
systemClock_PLLConfig(persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL));
|
||||
|
||||
// Configure the main internal regulator output voltage
|
||||
// Configure the main internal regulator output voltage
|
||||
|
||||
HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1_BOOST);
|
||||
|
||||
// Initializes the CPU, AHB and APB busses clocks
|
||||
// Initializes the CPU, AHB and APB busses clocks
|
||||
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_HSI48
|
||||
|RCC_OSCILLATORTYPE_LSI|RCC_OSCILLATORTYPE_HSE;
|
||||
|
@ -393,7 +393,7 @@ void SystemClock_Config(void)
|
|||
Error_Handler();
|
||||
}
|
||||
|
||||
// Initializes the CPU, AHB and APB busses clocks
|
||||
// Initializes the CPU, AHB and APB busses clocks
|
||||
|
||||
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|
||||
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
|
||||
|
@ -407,7 +407,7 @@ void SystemClock_Config(void)
|
|||
Error_Handler();
|
||||
}
|
||||
|
||||
// Initializes the peripherals clocks
|
||||
// Initializes the peripherals clocks
|
||||
|
||||
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2
|
||||
|RCC_PERIPHCLK_USART3|RCC_PERIPHCLK_UART4
|
||||
|
@ -440,7 +440,7 @@ void SystemClock_Config(void)
|
|||
Error_Handler();
|
||||
}
|
||||
|
||||
// Configures CRS
|
||||
// Configures CRS
|
||||
|
||||
pInit.Prescaler = RCC_CRS_SYNC_DIV1;
|
||||
pInit.Source = RCC_CRS_SYNC_SOURCE_USB;
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
// This module contains initialization code specific to STM32H7 MCUs.
|
||||
// It configures the RCC peripheral (system clocks) including scalars, and
|
||||
// It configures the RCC peripheral (system clocks) including scalars, and
|
||||
// enables RCC clocks for peripherals.
|
||||
|
||||
/**
|
||||
|
@ -270,7 +270,7 @@ pllConfig_t pll1ConfigRevV = {
|
|||
|
||||
// Nominal max 280MHz with 8MHz HSE
|
||||
// (340 is okay, 360 doesn't work.)
|
||||
//
|
||||
//
|
||||
|
||||
pllConfig_t pll1Config7A3 = {
|
||||
.clockMhz = 280,
|
||||
|
@ -322,7 +322,7 @@ pllConfig_t pll1Config72x73x = {
|
|||
|
||||
#define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
|
||||
|
||||
// RM0468 (Rev.2) Table 16.
|
||||
// RM0468 (Rev.2) Table 16.
|
||||
// 520MHz (AXI Interface clock) at VOS0 is 3WS
|
||||
#define MCU_FLASH_LATENCY FLASH_LATENCY_3
|
||||
|
||||
|
|
|
@ -75,7 +75,7 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = {
|
|||
DEF_TIM(TIM8, CH1N, PA7, 0, 0, 0),
|
||||
|
||||
DEF_TIM(TIM8, CH2, PA14, 0, 0, 0),
|
||||
|
||||
|
||||
DEF_TIM(TIM1, CH1N, PA7, 0, 0, 0),
|
||||
DEF_TIM(TIM1, CH1, PA8, 0, 0, 0),
|
||||
DEF_TIM(TIM1, CH2, PA9, 0, 0, 0),
|
||||
|
@ -126,7 +126,7 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = {
|
|||
DEF_TIM(TIM8, CH1N, PB3, 0, 0, 0),
|
||||
DEF_TIM(TIM8, CH2N, PB4, 0, 0, 0),
|
||||
DEF_TIM(TIM1, CH3N, PB15, 0, 0, 0),
|
||||
|
||||
|
||||
DEF_TIM(TIM8, CH1, PB6, 0, 0, 0),
|
||||
|
||||
DEF_TIM(TIM1, CH2N, PB0, 0, 0, 0),
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue