mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Merge branch 'master' into pico_spi
This commit is contained in:
commit
8f4ec7c331
91 changed files with 1746 additions and 1446 deletions
|
@ -34,17 +34,17 @@ CONFIG_REVISION := $(shell git -C $(CONFIG_DIR) log -1 --format="%h")
|
|||
CONFIG_REVISION_DEFINE := -D'__CONFIG_REVISION__="$(CONFIG_REVISION)"'
|
||||
endif
|
||||
|
||||
HSE_VALUE_MHZ := $(shell sed -E -n "/^\s*#\s*define\s+SYSTEM_HSE_MHZ\s+([0-9]+).*/s//\1/p" $(CONFIG_HEADER_FILE))
|
||||
HSE_VALUE_MHZ := $(shell sed -E -n "/^[[:space:]]*\#[[:space:]]*define[[:space:]]+SYSTEM_HSE_MHZ[[:space:]]+([0-9]+).*/s//\1/p" $(CONFIG_HEADER_FILE))
|
||||
ifneq ($(HSE_VALUE_MHZ),)
|
||||
HSE_VALUE := $(shell echo $$(( $(HSE_VALUE_MHZ) * 1000000 )) )
|
||||
endif
|
||||
|
||||
TARGET := $(shell sed -E -n "/^\s*#\s*define\s+FC_TARGET_MCU\s+(\w+).*/s//\1/p" $(CONFIG_HEADER_FILE))
|
||||
TARGET := $(shell sed -E -n "/^[[:space:]]*\#[[:space:]]*define[[:space:]]+FC_TARGET_MCU[[:space:]]+([[:alnum:]_]+).*/s//\1/p" $(CONFIG_HEADER_FILE))
|
||||
ifeq ($(TARGET),)
|
||||
$(error No TARGET identified. Is the $(CONFIG_HEADER_FILE) valid for $(CONFIG)?)
|
||||
endif
|
||||
|
||||
EXST_ADJUST_VMA := $(shell sed -E -n "/^\s*#\s*define\s+FC_VMA_ADDRESS\s+((0[xX])?[[:xdigit:]]+).*/s//\1/p" $(CONFIG_HEADER_FILE))
|
||||
EXST_ADJUST_VMA := $(shell sed -E -n "/^[[:space:]]*\#[[:space:]]*define[[:space:]]+FC_VMA_ADDRESS[[:space:]]+((0[xX])?[[:xdigit:]]+).*/s//\1/p" $(CONFIG_HEADER_FILE))
|
||||
ifneq ($(EXST_ADJUST_VMA),)
|
||||
EXST = yes
|
||||
endif
|
||||
|
|
|
@ -1 +1 @@
|
|||
Subproject commit 5e33fe422e2c1fb095db84508a9e3ebb465a80a4
|
||||
Subproject commit b60600210384d1da4621cc35a0632d9cca8a62b7
|
|
@ -365,7 +365,7 @@ typedef struct blackboxMainState_s {
|
|||
int16_t gyroUnfilt[XYZ_AXIS_COUNT];
|
||||
#ifdef USE_ACC
|
||||
int16_t accADC[XYZ_AXIS_COUNT];
|
||||
int16_t imuAttitudeQuaternion[XYZ_AXIS_COUNT];
|
||||
int16_t imuAttitudeQuaternion3[XYZ_AXIS_COUNT]; // only x,y,z is stored; w is always positive
|
||||
#endif
|
||||
int16_t debug[DEBUG16_VALUE_COUNT];
|
||||
int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||
|
@ -747,7 +747,7 @@ static void writeIntraframe(void)
|
|||
}
|
||||
|
||||
if (testBlackboxCondition(CONDITION(ATTITUDE))) {
|
||||
blackboxWriteSigned16VBArray(blackboxCurrent->imuAttitudeQuaternion, XYZ_AXIS_COUNT);
|
||||
blackboxWriteSigned16VBArray(blackboxCurrent->imuAttitudeQuaternion3, XYZ_AXIS_COUNT);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -932,7 +932,7 @@ static void writeInterframe(void)
|
|||
}
|
||||
|
||||
if (testBlackboxCondition(CONDITION(ATTITUDE))) {
|
||||
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, imuAttitudeQuaternion), XYZ_AXIS_COUNT);
|
||||
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, imuAttitudeQuaternion3), XYZ_AXIS_COUNT);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -1250,14 +1250,22 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
|
||||
#if defined(USE_ACC)
|
||||
blackboxCurrent->accADC[i] = lrintf(acc.accADC.v[i]);
|
||||
STATIC_ASSERT(offsetof(quaternion_t, w) == 0, "Code expects quaternion in w, x, y, z order");
|
||||
blackboxCurrent->imuAttitudeQuaternion[i] = lrintf(imuAttitudeQuaternion.v[i + 1] * 0x7FFF); //Scale to int16 by value 0x7FFF = 2^15 - 1; Use i+1 index for x,y,z components access, [0] - w
|
||||
#endif
|
||||
#ifdef USE_MAG
|
||||
blackboxCurrent->magADC[i] = lrintf(mag.magADC.v[i]);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(USE_ACC) // IMU quaternion
|
||||
{
|
||||
// write x,y,z of IMU quaternion. Make sure that w is always positive
|
||||
STATIC_ASSERT(offsetof(quaternion_t, w) == 0, "Code expects quaternion in w, x, y, z order");
|
||||
const float q_sign = imuAttitudeQuaternion.w < 0 ? -1 : 1; // invert quaternion if w is negative
|
||||
const float q_scale = q_sign * 0x7FFF; // Scale to int16 by value 0x7FFF = 2^15 - 1 (-1 <= x,y,z <= 1)
|
||||
for (int i = 0; i < XYZ_AXIS_COUNT; i++) {
|
||||
blackboxCurrent->imuAttitudeQuaternion3[i] = lrintf(imuAttitudeQuaternion.v[i + 1] * q_scale); // Use i+1 index for x,y,z components access, [0] - w
|
||||
}
|
||||
}
|
||||
#endif
|
||||
for (int i = 0; i < 4; i++) {
|
||||
blackboxCurrent->rcCommand[i] = lrintf(rcCommand[i] * blackboxHighResolutionScale);
|
||||
}
|
||||
|
@ -1441,12 +1449,15 @@ STATIC_UNIT_TESTED char *blackboxGetStartDateTime(char *buf)
|
|||
}
|
||||
|
||||
#ifndef BLACKBOX_PRINT_HEADER_LINE
|
||||
#define BLACKBOX_PRINT_HEADER_LINE(name, format, ...) case __COUNTER__: \
|
||||
blackboxPrintfHeaderLine(name, format, __VA_ARGS__); \
|
||||
break;
|
||||
#define BLACKBOX_PRINT_HEADER_LINE_CUSTOM(...) case __COUNTER__: \
|
||||
{__VA_ARGS__}; \
|
||||
break;
|
||||
#define BLACKBOX_PRINT_HEADER_LINE(name, format, ...) \
|
||||
case __COUNTER__: { \
|
||||
blackboxPrintfHeaderLine(name, format, __VA_ARGS__); \
|
||||
} break // absence of semicolon on this line is what enforces the presence of a semicolon at the end of each input line
|
||||
|
||||
#define BLACKBOX_PRINT_HEADER_LINE_CUSTOM(...) \
|
||||
case __COUNTER__: { \
|
||||
__VA_ARGS__; \
|
||||
} break
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -1707,20 +1718,20 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALTITUDE_D_LPF, "%d", positionConfig()->altitude_d_lpf);
|
||||
|
||||
#ifndef USE_WING
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_LANDING_ALTITUDE, "%d", apConfig()->landing_altitude_m);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_HOVER_THROTTLE, "%d", apConfig()->hover_throttle);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THROTTLE_MIN, "%d", apConfig()->throttle_min);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THROTTLE_MAX, "%d", apConfig()->throttle_max);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALTITUDE_P, "%d", apConfig()->altitude_P);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALTITUDE_I, "%d", apConfig()->altitude_I);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALTITUDE_D, "%d", apConfig()->altitude_D);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALTITUDE_F, "%d", apConfig()->altitude_F);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POSITION_P, "%d", apConfig()->position_P);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POSITION_I, "%d", apConfig()->position_I);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POSITION_D, "%d", apConfig()->position_D);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POSITION_A, "%d", apConfig()->position_A);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POSITION_CUTOFF, "%d", apConfig()->position_cutoff);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_MAX_ANGLE, "%d", apConfig()->max_angle);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_LANDING_ALTITUDE_M, "%d", autopilotConfig()->landingAltitudeM);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_HOVER_THROTTLE, "%d", autopilotConfig()->hoverThrottle);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_THROTTLE_MIN, "%d", autopilotConfig()->throttleMin);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_THROTTLE_MAX, "%d", autopilotConfig()->throttleMax);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_ALTITUDE_P, "%d", autopilotConfig()->altitudeP);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_ALTITUDE_I, "%d", autopilotConfig()->altitudeI);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_ALTITUDE_D, "%d", autopilotConfig()->altitudeD);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_ALTITUDE_F, "%d", autopilotConfig()->altitudeF);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_POSITION_P, "%d", autopilotConfig()->positionP);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_POSITION_I, "%d", autopilotConfig()->positionI);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_POSITION_D, "%d", autopilotConfig()->positionD);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_POSITION_A, "%d", autopilotConfig()->positionA);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_POSITION_CUTOFF, "%d", autopilotConfig()->positionCutoff);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_AP_MAX_ANGLE, "%d", autopilotConfig()->maxAngle);
|
||||
#endif // !USE_WING
|
||||
|
||||
#ifdef USE_MAG
|
||||
|
@ -1793,38 +1804,38 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THRUST_LINEARIZATION, "%d", currentPidProfile->thrustLinearization);
|
||||
|
||||
#ifdef USE_GPS
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_PROVIDER, "%d", gpsConfig()->provider)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_SET_HOME_POINT_ONCE, "%d", gpsConfig()->gps_set_home_point_once)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_USE_3D_SPEED, "%d", gpsConfig()->gps_use_3d_speed)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_PROVIDER, "%d", gpsConfig()->provider);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_SET_HOME_POINT_ONCE, "%d", gpsConfig()->gps_set_home_point_once);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_USE_3D_SPEED, "%d", gpsConfig()->gps_use_3d_speed);
|
||||
|
||||
#ifdef USE_GPS_RESCUE
|
||||
#ifndef USE_WING
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_MIN_START_DIST, "%d", gpsRescueConfig()->minStartDistM)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ALT_MODE, "%d", gpsRescueConfig()->altitudeMode)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_INITIAL_CLIMB, "%d", gpsRescueConfig()->initialClimbM)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ASCEND_RATE, "%d", gpsRescueConfig()->ascendRate)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_MIN_START_DIST, "%d", gpsRescueConfig()->minStartDistM);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ALT_MODE, "%d", gpsRescueConfig()->altitudeMode);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_INITIAL_CLIMB, "%d", gpsRescueConfig()->initialClimbM);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ASCEND_RATE, "%d", gpsRescueConfig()->ascendRate);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_RETURN_ALT, "%d", gpsRescueConfig()->returnAltitudeM)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_GROUND_SPEED, "%d", gpsRescueConfig()->groundSpeedCmS)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_MAX_RESCUE_ANGLE, "%d", gpsRescueConfig()->maxRescueAngle)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ROLL_MIX, "%d", gpsRescueConfig()->rollMix)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_PITCH_CUTOFF, "%d", gpsRescueConfig()->pitchCutoffHz)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_IMU_YAW_GAIN, "%d", gpsRescueConfig()->imuYawGain)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_RETURN_ALT, "%d", gpsRescueConfig()->returnAltitudeM);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_GROUND_SPEED, "%d", gpsRescueConfig()->groundSpeedCmS);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_MAX_RESCUE_ANGLE, "%d", gpsRescueConfig()->maxRescueAngle);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ROLL_MIX, "%d", gpsRescueConfig()->rollMix);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_PITCH_CUTOFF, "%d", gpsRescueConfig()->pitchCutoffHz);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_IMU_YAW_GAIN, "%d", gpsRescueConfig()->imuYawGain);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DESCENT_DIST, "%d", gpsRescueConfig()->descentDistanceM)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DESCEND_RATE, "%d", gpsRescueConfig()->descendRate)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DISARM_THRESHOLD, "%d", gpsRescueConfig()->disarmThreshold)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DESCENT_DIST, "%d", gpsRescueConfig()->descentDistanceM);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DESCEND_RATE, "%d", gpsRescueConfig()->descendRate);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DISARM_THRESHOLD, "%d", gpsRescueConfig()->disarmThreshold);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_SANITY_CHECKS, "%d", gpsRescueConfig()->sanityChecks)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_MIN_SATS, "%d", gpsRescueConfig()->minSats)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ALLOW_ARMING_WITHOUT_FIX, "%d", gpsRescueConfig()->allowArmingWithoutFix)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_SANITY_CHECKS, "%d", gpsRescueConfig()->sanityChecks);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_MIN_SATS, "%d", gpsRescueConfig()->minSats);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ALLOW_ARMING_WITHOUT_FIX, "%d", gpsRescueConfig()->allowArmingWithoutFix);
|
||||
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_VELOCITY_P, "%d", gpsRescueConfig()->velP)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_VELOCITY_I, "%d", gpsRescueConfig()->velI)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_VELOCITY_D, "%d", gpsRescueConfig()->velD)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_YAW_P, "%d", gpsRescueConfig()->yawP)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_VELOCITY_P, "%d", gpsRescueConfig()->velP);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_VELOCITY_I, "%d", gpsRescueConfig()->velI);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_VELOCITY_D, "%d", gpsRescueConfig()->velD);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_YAW_P, "%d", gpsRescueConfig()->yawP);
|
||||
#ifdef USE_MAG
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_USE_MAG, "%d", gpsRescueConfig()->useMag)
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_USE_MAG, "%d", gpsRescueConfig()->useMag);
|
||||
#endif // USE_MAG
|
||||
#endif // !USE_WING
|
||||
#endif // USE_GPS_RESCUE
|
||||
|
@ -1832,15 +1843,15 @@ static bool blackboxWriteSysinfo(void)
|
|||
|
||||
#ifdef USE_ALTITUDE_HOLD
|
||||
#ifndef USE_WING
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALT_HOLD_THROTTLE_RESPONSE, "%d", altHoldConfig()->alt_hold_adjust_rate);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALT_HOLD_DEADBAND, "%d", altHoldConfig()->alt_hold_deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALT_HOLD_CLIMB_RATE, "%d", altHoldConfig()->climbRate);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ALT_HOLD_DEADBAND, "%d", altHoldConfig()->deadband);
|
||||
#endif // !USE_WING
|
||||
#endif // USE_ALTITUDE_HOLD
|
||||
|
||||
#ifdef USE_POSITION_HOLD
|
||||
#ifndef USE_WING
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POS_HOLD_WITHOUT_MAG, "%d", posHoldConfig()->pos_hold_without_mag);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POS_HOLD_DEADBAND, "%d", posHoldConfig()->pos_hold_deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POS_HOLD_WITHOUT_MAG, "%d", posHoldConfig()->posHoldWithoutMag);
|
||||
BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_POS_HOLD_DEADBAND, "%d", posHoldConfig()->deadband);
|
||||
#endif // !USE_WING
|
||||
#endif
|
||||
|
||||
|
|
|
@ -5096,7 +5096,9 @@ const cliResourceValue_t resourceTable[] = {
|
|||
DEFW( OWNER_I2C_SCL, PG_I2C_CONFIG, i2cConfig_t, ioTagScl, I2CDEV_COUNT ),
|
||||
DEFW( OWNER_I2C_SDA, PG_I2C_CONFIG, i2cConfig_t, ioTagSda, I2CDEV_COUNT ),
|
||||
#endif
|
||||
DEFA( OWNER_LED, PG_STATUS_LED_CONFIG, statusLedConfig_t, ioTags[0], STATUS_LED_NUMBER ),
|
||||
#if !defined(USE_VIRTUAL_LED)
|
||||
DEFA( OWNER_LED, PG_STATUS_LED_CONFIG, statusLedConfig_t, ioTags[0], STATUS_LED_COUNT ),
|
||||
#endif
|
||||
#ifdef USE_SPEKTRUM_BIND
|
||||
DEFS( OWNER_RX_BIND, PG_RX_CONFIG, rxConfig_t, spektrum_bind_pin_override_ioTag ),
|
||||
DEFS( OWNER_RX_BIND_PLUG, PG_RX_CONFIG, rxConfig_t, spektrum_bind_plug_ioTag ),
|
||||
|
@ -6896,7 +6898,7 @@ void cliEnter(serialPort_t *serialPort, bool interactive)
|
|||
setPrintfSerialPort(cliPort);
|
||||
}
|
||||
|
||||
bufWriterInit(&cliWriterDesc, cliWriteBuffer, sizeof(cliWriteBuffer), (bufWrite_t)serialWriteBufShim, serialPort);
|
||||
bufWriterInit(&cliWriterDesc, cliWriteBuffer, sizeof(cliWriteBuffer), (bufWrite_t)serialWriteBufBlockingShim, serialPort);
|
||||
cliErrorWriter = cliWriter = &cliWriterDesc;
|
||||
|
||||
if (interactive) {
|
||||
|
|
|
@ -1155,15 +1155,15 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
#ifdef USE_ALTITUDE_HOLD
|
||||
#ifndef USE_WING
|
||||
{ PARAM_NAME_ALT_HOLD_THROTTLE_RESPONSE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_ALTHOLD_CONFIG, offsetof(altHoldConfig_t, alt_hold_adjust_rate) },
|
||||
{ PARAM_NAME_ALT_HOLD_DEADBAND, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 70 }, PG_ALTHOLD_CONFIG, offsetof(altHoldConfig_t, alt_hold_deadband) },
|
||||
{ PARAM_NAME_ALT_HOLD_CLIMB_RATE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_ALTHOLD_CONFIG, offsetof(altHoldConfig_t, climbRate) },
|
||||
{ PARAM_NAME_ALT_HOLD_DEADBAND, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 70 }, PG_ALTHOLD_CONFIG, offsetof(altHoldConfig_t, deadband) },
|
||||
#endif // !USE_WING
|
||||
#endif // USE_ALTITUDE_HOLD
|
||||
|
||||
#ifdef USE_POSITION_HOLD
|
||||
#ifndef USE_WING
|
||||
{ PARAM_NAME_POS_HOLD_WITHOUT_MAG, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_POSHOLD_CONFIG, offsetof(posHoldConfig_t, pos_hold_without_mag) },
|
||||
{ PARAM_NAME_POS_HOLD_DEADBAND, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 50 }, PG_POSHOLD_CONFIG, offsetof(posHoldConfig_t, pos_hold_deadband) },
|
||||
{ PARAM_NAME_POS_HOLD_WITHOUT_MAG, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_POSHOLD_CONFIG, offsetof(posHoldConfig_t, posHoldWithoutMag) },
|
||||
{ PARAM_NAME_POS_HOLD_DEADBAND, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 50 }, PG_POSHOLD_CONFIG, offsetof(posHoldConfig_t, deadband) },
|
||||
#endif // !USE_WING
|
||||
#endif // USE_POSITION_HOLD
|
||||
|
||||
|
@ -1749,7 +1749,9 @@ const clivalue_t valueTable[] = {
|
|||
{ "frsky_spi_a1_source", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RX_FRSKY_SPI_A1_SOURCE }, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, a1Source) },
|
||||
{ "cc2500_spi_chip_detect", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, chipDetectEnabled) },
|
||||
#endif
|
||||
{ "led_inversion", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
|
||||
#if !defined(USE_VIRTUAL_LED)
|
||||
{ "led_inversion", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, ((1 << STATUS_LED_COUNT) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
|
||||
#endif
|
||||
#ifdef USE_DASHBOARD
|
||||
{ "dashboard_i2c_bus", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, I2CDEV_COUNT }, PG_DASHBOARD_CONFIG, offsetof(dashboardConfig_t, device) },
|
||||
{ "dashboard_i2c_addr", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { I2C_ADDR7_MIN, I2C_ADDR7_MAX }, PG_DASHBOARD_CONFIG, offsetof(dashboardConfig_t, address) },
|
||||
|
@ -1918,20 +1920,20 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
// PG_AUTOPILOT
|
||||
#ifndef USE_WING
|
||||
{ PARAM_NAME_LANDING_ALTITUDE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, landing_altitude_m) },
|
||||
{ PARAM_NAME_HOVER_THROTTLE, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1100, 1700 }, PG_AUTOPILOT, offsetof(apConfig_t, hover_throttle) },
|
||||
{ PARAM_NAME_THROTTLE_MIN, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1050, 1400 }, PG_AUTOPILOT, offsetof(apConfig_t, throttle_min) },
|
||||
{ PARAM_NAME_THROTTLE_MAX, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1400, 2000 }, PG_AUTOPILOT, offsetof(apConfig_t, throttle_max) },
|
||||
{ PARAM_NAME_ALTITUDE_P, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, altitude_P) },
|
||||
{ PARAM_NAME_ALTITUDE_I, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, altitude_I) },
|
||||
{ PARAM_NAME_ALTITUDE_D, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, altitude_D) },
|
||||
{ PARAM_NAME_ALTITUDE_F, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, altitude_F) },
|
||||
{ PARAM_NAME_POSITION_P, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, position_P) },
|
||||
{ PARAM_NAME_POSITION_I, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, position_I) },
|
||||
{ PARAM_NAME_POSITION_D, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, position_D) },
|
||||
{ PARAM_NAME_POSITION_A, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(apConfig_t, position_A) },
|
||||
{ PARAM_NAME_POSITION_CUTOFF, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 250 }, PG_AUTOPILOT, offsetof(apConfig_t, position_cutoff) },
|
||||
{ PARAM_NAME_AP_MAX_ANGLE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 70 }, PG_AUTOPILOT, offsetof(apConfig_t, max_angle) },
|
||||
{ PARAM_NAME_AP_LANDING_ALTITUDE_M, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, landingAltitudeM) },
|
||||
{ PARAM_NAME_AP_HOVER_THROTTLE, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1100, 1700 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, hoverThrottle) },
|
||||
{ PARAM_NAME_AP_THROTTLE_MIN, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1050, 1400 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, throttleMin) },
|
||||
{ PARAM_NAME_AP_THROTTLE_MAX, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1400, 2000 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, throttleMax) },
|
||||
{ PARAM_NAME_AP_ALTITUDE_P, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, altitudeP) },
|
||||
{ PARAM_NAME_AP_ALTITUDE_I, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, altitudeI) },
|
||||
{ PARAM_NAME_AP_ALTITUDE_D, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, altitudeD) },
|
||||
{ PARAM_NAME_AP_ALTITUDE_F, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, altitudeF) },
|
||||
{ PARAM_NAME_AP_POSITION_P, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, positionP) },
|
||||
{ PARAM_NAME_AP_POSITION_I, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, positionI) },
|
||||
{ PARAM_NAME_AP_POSITION_D, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, positionD) },
|
||||
{ PARAM_NAME_AP_POSITION_A, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 200 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, positionA) },
|
||||
{ PARAM_NAME_AP_POSITION_CUTOFF, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 250 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, positionCutoff) },
|
||||
{ PARAM_NAME_AP_MAX_ANGLE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 70 }, PG_AUTOPILOT, offsetof(autopilotConfig_t, maxAngle) },
|
||||
#endif // !USE_WING
|
||||
|
||||
// PG_MODE_ACTIVATION_CONFIG
|
||||
|
|
|
@ -55,16 +55,16 @@ static uint8_t gpsRescueConfig_angle; //degrees
|
|||
|
||||
static uint16_t gpsRescueConfig_descentDistanceM; //meters
|
||||
static uint16_t gpsRescueConfig_descendRate;
|
||||
static uint8_t apConfig_landingAltitudeM;
|
||||
static uint8_t autopilotConfig_landingAltitudeM;
|
||||
|
||||
static uint16_t apConfig_throttleMin;
|
||||
static uint16_t apConfig_throttleMax;
|
||||
static uint16_t apConfig_hoverThrottle;
|
||||
static uint16_t autopilotConfig_throttleMin;
|
||||
static uint16_t autopilotConfig_throttleMax;
|
||||
static uint16_t autopilotConfig_hoverThrottle;
|
||||
|
||||
static uint8_t gpsRescueConfig_minSats;
|
||||
static uint8_t gpsRescueConfig_allowArmingWithoutFix;
|
||||
|
||||
static uint8_t apConfig_altitude_P, apConfig_altitude_I, apConfig_altitude_D, apConfig_altitude_F;
|
||||
static uint8_t autopilotConfig_altitude_P, autopilotConfig_altitude_I, autopilotConfig_altitude_D, autopilotConfig_altitude_F;
|
||||
static uint8_t gpsRescueConfig_yawP;
|
||||
static uint8_t gpsRescueConfig_velP, gpsRescueConfig_velI, gpsRescueConfig_velD;
|
||||
|
||||
|
@ -75,10 +75,10 @@ static const void *cms_menuGpsRescuePidOnEnter(displayPort_t *pDisp)
|
|||
{
|
||||
UNUSED(pDisp);
|
||||
|
||||
apConfig_altitude_P = apConfig()->altitude_P;
|
||||
apConfig_altitude_I = apConfig()->altitude_I;
|
||||
apConfig_altitude_D = apConfig()->altitude_D;
|
||||
apConfig_altitude_F = apConfig()->altitude_F;
|
||||
autopilotConfig_altitude_P = autopilotConfig()->altitudeP;
|
||||
autopilotConfig_altitude_I = autopilotConfig()->altitudeI;
|
||||
autopilotConfig_altitude_D = autopilotConfig()->altitudeD;
|
||||
autopilotConfig_altitude_F = autopilotConfig()->altitudeF;
|
||||
|
||||
gpsRescueConfig_yawP = gpsRescueConfig()->yawP;
|
||||
|
||||
|
@ -97,10 +97,10 @@ static const void *cms_menuGpsRescuePidOnExit(displayPort_t *pDisp, const OSD_En
|
|||
UNUSED(pDisp);
|
||||
UNUSED(self);
|
||||
|
||||
apConfigMutable()->altitude_P = apConfig_altitude_P;
|
||||
apConfigMutable()->altitude_I = apConfig_altitude_I;
|
||||
apConfigMutable()->altitude_D = apConfig_altitude_D;
|
||||
apConfigMutable()->altitude_F = apConfig_altitude_F;
|
||||
autopilotConfigMutable()->altitudeP = autopilotConfig_altitude_P;
|
||||
autopilotConfigMutable()->altitudeI = autopilotConfig_altitude_I;
|
||||
autopilotConfigMutable()->altitudeD = autopilotConfig_altitude_D;
|
||||
autopilotConfigMutable()->altitudeF = autopilotConfig_altitude_F;
|
||||
|
||||
gpsRescueConfigMutable()->yawP = gpsRescueConfig_yawP;
|
||||
|
||||
|
@ -118,10 +118,10 @@ const OSD_Entry cms_menuGpsRescuePidEntries[] =
|
|||
{
|
||||
{"--- GPS RESCUE PID---", OME_Label, NULL, NULL},
|
||||
|
||||
{ "ALTITUDE P", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &apConfig_altitude_P, 0, 200, 1 } },
|
||||
{ "ALTITUDE I", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &apConfig_altitude_I, 0, 200, 1 } },
|
||||
{ "ALTITUDE D", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &apConfig_altitude_D, 0, 200, 1 } },
|
||||
{ "ALTITUDE F", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &apConfig_altitude_F, 0, 200, 1 } },
|
||||
{ "ALTITUDE P", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &autopilotConfig_altitude_P, 0, 200, 1 } },
|
||||
{ "ALTITUDE I", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &autopilotConfig_altitude_I, 0, 200, 1 } },
|
||||
{ "ALTITUDE D", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &autopilotConfig_altitude_D, 0, 200, 1 } },
|
||||
{ "ALTITUDE F", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &autopilotConfig_altitude_F, 0, 200, 1 } },
|
||||
|
||||
{ "YAW P", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_yawP, 0, 200, 1 } },
|
||||
|
||||
|
@ -162,11 +162,11 @@ static const void *cmsx_menuGpsRescueOnEnter(displayPort_t *pDisp)
|
|||
|
||||
gpsRescueConfig_descentDistanceM = gpsRescueConfig()->descentDistanceM;
|
||||
gpsRescueConfig_descendRate = gpsRescueConfig()->descendRate;
|
||||
apConfig_landingAltitudeM = apConfig()->landing_altitude_m;
|
||||
autopilotConfig_landingAltitudeM = autopilotConfig()->landingAltitudeM;
|
||||
|
||||
apConfig_throttleMin = apConfig()->throttle_min;
|
||||
apConfig_throttleMax = apConfig()->throttle_max;
|
||||
apConfig_hoverThrottle = apConfig()->hover_throttle;
|
||||
autopilotConfig_throttleMin = autopilotConfig()->throttleMin;
|
||||
autopilotConfig_throttleMax = autopilotConfig()->throttleMax;
|
||||
autopilotConfig_hoverThrottle = autopilotConfig()->hoverThrottle;
|
||||
|
||||
gpsRescueConfig_minSats = gpsRescueConfig()->minSats;
|
||||
gpsRescueConfig_allowArmingWithoutFix = gpsRescueConfig()->allowArmingWithoutFix;
|
||||
|
@ -190,11 +190,11 @@ static const void *cmsx_menuGpsRescueOnExit(displayPort_t *pDisp, const OSD_Entr
|
|||
|
||||
gpsRescueConfigMutable()->descentDistanceM = gpsRescueConfig_descentDistanceM;
|
||||
gpsRescueConfigMutable()->descendRate = gpsRescueConfig_descendRate;
|
||||
apConfigMutable()->landing_altitude_m = apConfig_landingAltitudeM;
|
||||
autopilotConfigMutable()->landingAltitudeM = autopilotConfig_landingAltitudeM;
|
||||
|
||||
apConfigMutable()->throttle_min = apConfig_throttleMin;
|
||||
apConfigMutable()->throttle_max = apConfig_throttleMax;
|
||||
apConfigMutable()->hover_throttle = apConfig_hoverThrottle;
|
||||
autopilotConfigMutable()->throttleMin = autopilotConfig_throttleMin;
|
||||
autopilotConfigMutable()->throttleMax = autopilotConfig_throttleMax;
|
||||
autopilotConfigMutable()->hoverThrottle = autopilotConfig_hoverThrottle;
|
||||
|
||||
gpsRescueConfigMutable()->minSats = gpsRescueConfig_minSats;
|
||||
gpsRescueConfigMutable()->allowArmingWithoutFix = gpsRescueConfig_allowArmingWithoutFix;
|
||||
|
@ -217,11 +217,11 @@ const OSD_Entry cmsx_menuGpsRescueEntries[] =
|
|||
|
||||
{ "DESCENT DIST M", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descentDistanceM, 5, 500, 1 } },
|
||||
{ "DESCENT RATE CM/S", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &gpsRescueConfig_descendRate, 25, 500, 1 } },
|
||||
{ "LANDING ALT M", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t) { &apConfig_landingAltitudeM, 1, 15, 1 } },
|
||||
{ "LANDING ALT M", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t) { &autopilotConfig_landingAltitudeM, 1, 15, 1 } },
|
||||
|
||||
{ "THROTTLE MIN", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &apConfig_throttleMin, 1050, 1400, 1 } },
|
||||
{ "THROTTLE MAX", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &apConfig_throttleMax, 1400, 2000, 1 } },
|
||||
{ "THROTTLE HOV", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &apConfig_hoverThrottle, 1100, 1700, 1 } },
|
||||
{ "THROTTLE MIN", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &autopilotConfig_throttleMin, 1050, 1400, 1 } },
|
||||
{ "THROTTLE MAX", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &autopilotConfig_throttleMax, 1400, 2000, 1 } },
|
||||
{ "THROTTLE HOV", OME_UINT16 | REBOOT_REQUIRED, NULL, &(OSD_UINT16_t){ &autopilotConfig_hoverThrottle, 1100, 1700, 1 } },
|
||||
|
||||
{ "SATS REQUIRED", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_minSats, 5, 50, 1 } },
|
||||
{ "ARM WITHOUT FIX", OME_Bool | REBOOT_REQUIRED, NULL, &gpsRescueConfig_allowArmingWithoutFix },
|
||||
|
|
|
@ -169,7 +169,7 @@ static aafConfig_t aafLUT42688[AAF_CONFIG_COUNT] = { // see table in section 5.
|
|||
[AAF_CONFIG_1962HZ] = { 37, 1376, 4 },
|
||||
};
|
||||
|
||||
// Possible gyro Anti-Alias Filter (AAF) cutoffs for ICM-42688P
|
||||
// Possible gyro Anti-Alias Filter (AAF) cutoffs for ICM-42605
|
||||
// actual cutoff differs slightly from those of the 42688P
|
||||
static aafConfig_t aafLUT42605[AAF_CONFIG_COUNT] = { // see table in section 5.3
|
||||
[AAF_CONFIG_258HZ] = { 21, 440, 6 }, // actually 249 Hz
|
||||
|
|
|
@ -77,20 +77,15 @@ static bool lis2mdlInit(magDev_t *mag)
|
|||
|
||||
static bool lis2mdlRead(magDev_t *mag, int16_t *magData)
|
||||
{
|
||||
uint8_t status = 0;
|
||||
uint8_t buf[6];
|
||||
static uint8_t buf[6];
|
||||
static bool pendingRead = true;
|
||||
|
||||
extDevice_t *dev = &mag->dev;
|
||||
|
||||
if (!busReadRegisterBuffer(dev, LIS2MDL_ADDR_STATUS_REG, &status, sizeof(status))) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!(status & LIS2MDL_STATUS_REG_READY)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!busReadRegisterBuffer(dev, LIS2MDL_ADDR_OUTX_L_REG, (uint8_t *)&buf, sizeof(buf))) {
|
||||
if (pendingRead) {
|
||||
if (busReadRegisterBufferStart(dev, LIS2MDL_ADDR_OUTX_L_REG, (uint8_t *)buf, sizeof(buf))) {
|
||||
pendingRead = false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -107,6 +102,8 @@ static bool lis2mdlRead(magDev_t *mag, int16_t *magData)
|
|||
magData[Y] = y;
|
||||
magData[Z] = z;
|
||||
|
||||
pendingRead = true;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -22,13 +22,7 @@
|
|||
|
||||
#include "drivers/resource.h"
|
||||
|
||||
#if defined(USE_ATBSP_DRIVER)
|
||||
#include "dma_atbsp.h"
|
||||
#endif
|
||||
|
||||
#if defined(APM32F4)
|
||||
#include "dma_apm32.h"
|
||||
#endif
|
||||
#include "platform/dma.h"
|
||||
|
||||
#define CACHE_LINE_SIZE 32
|
||||
#define CACHE_LINE_MASK (CACHE_LINE_SIZE - 1)
|
||||
|
@ -42,26 +36,13 @@
|
|||
|
||||
typedef struct dmaResource_s dmaResource_t;
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
#define DMA_ARCH_TYPE DMA_Stream_TypeDef
|
||||
#elif defined(STM32H7)
|
||||
// H7 has stream based DMA and channel based BDMA, but we ignore BDMA (for now).
|
||||
#define DMA_ARCH_TYPE DMA_Stream_TypeDef
|
||||
#elif defined(AT32F435)
|
||||
#define DMA_ARCH_TYPE dma_channel_type
|
||||
#elif defined(APM32F4)
|
||||
#define DMA_ARCH_TYPE DMA_Stream_TypeDef
|
||||
#else
|
||||
#define DMA_ARCH_TYPE DMA_Channel_TypeDef
|
||||
#endif
|
||||
|
||||
struct dmaChannelDescriptor_s;
|
||||
typedef void (*dmaCallbackHandlerFuncPtr)(struct dmaChannelDescriptor_s *channelDescriptor);
|
||||
|
||||
typedef struct dmaChannelDescriptor_s {
|
||||
DMA_TypeDef* dma;
|
||||
dmaResource_t *ref;
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(APM32F4)
|
||||
#if PLATFORM_TRAIT_DMA_STREAM_REQUIRED
|
||||
uint8_t stream;
|
||||
#endif
|
||||
uint32_t channel;
|
||||
|
@ -72,198 +53,15 @@ typedef struct dmaChannelDescriptor_s {
|
|||
resourceOwner_t owner;
|
||||
uint8_t resourceIndex;
|
||||
uint32_t completeFlag;
|
||||
#if defined(USE_ATBSP_DRIVER)
|
||||
#if PLATFORM_TRAIT_DMA_MUX_REQUIRED
|
||||
dmamux_channel_type *dmamux;
|
||||
#endif
|
||||
} dmaChannelDescriptor_t;
|
||||
|
||||
#define DMA_IDENTIFIER_TO_INDEX(x) ((x) - 1)
|
||||
|
||||
#if defined(USE_ATBSP_DRIVER)
|
||||
|
||||
#elif defined(APM32F4)
|
||||
// dma_apm32.h
|
||||
|
||||
#elif defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA1_ST0_HANDLER = 1,
|
||||
DMA1_ST1_HANDLER,
|
||||
DMA1_ST2_HANDLER,
|
||||
DMA1_ST3_HANDLER,
|
||||
DMA1_ST4_HANDLER,
|
||||
DMA1_ST5_HANDLER,
|
||||
DMA1_ST6_HANDLER,
|
||||
DMA1_ST7_HANDLER,
|
||||
DMA2_ST0_HANDLER,
|
||||
DMA2_ST1_HANDLER,
|
||||
DMA2_ST2_HANDLER,
|
||||
DMA2_ST3_HANDLER,
|
||||
DMA2_ST4_HANDLER,
|
||||
DMA2_ST5_HANDLER,
|
||||
DMA2_ST6_HANDLER,
|
||||
DMA2_ST7_HANDLER,
|
||||
DMA_LAST_HANDLER = DMA2_ST7_HANDLER
|
||||
} dmaIdentifier_e;
|
||||
|
||||
#define DMA_DEVICE_NO(x) ((((x)-1) / 8) + 1)
|
||||
#define DMA_DEVICE_INDEX(x) ((((x)-1) % 8))
|
||||
#define DMA_OUTPUT_INDEX 0
|
||||
#define DMA_OUTPUT_STRING "DMA%d Stream %d:"
|
||||
#define DMA_INPUT_STRING "DMA%d_ST%d"
|
||||
|
||||
#define DEFINE_DMA_CHANNEL(d, s, f) { \
|
||||
.dma = d, \
|
||||
.ref = (dmaResource_t *)d ## _Stream ## s, \
|
||||
.stream = s, \
|
||||
.irqHandlerCallback = NULL, \
|
||||
.flagsShift = f, \
|
||||
.irqN = d ## _Stream ## s ## _IRQn, \
|
||||
.userParam = 0, \
|
||||
.owner.owner = 0, \
|
||||
.owner.resourceIndex = 0 \
|
||||
}
|
||||
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, s, i) FAST_IRQ_HANDLER void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\
|
||||
const uint8_t index = DMA_IDENTIFIER_TO_INDEX(i); \
|
||||
dmaCallbackHandlerFuncPtr handler = dmaDescriptors[index].irqHandlerCallback; \
|
||||
if (handler) \
|
||||
handler(&dmaDescriptors[index]); \
|
||||
}
|
||||
|
||||
#define DMA_CLEAR_FLAG(d, flag) if (d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift)
|
||||
#define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift))
|
||||
|
||||
#define DMA_IT_TCIF ((uint32_t)0x00000020)
|
||||
#define DMA_IT_HTIF ((uint32_t)0x00000010)
|
||||
#define DMA_IT_TEIF ((uint32_t)0x00000008)
|
||||
#define DMA_IT_DMEIF ((uint32_t)0x00000004)
|
||||
#define DMA_IT_FEIF ((uint32_t)0x00000001)
|
||||
|
||||
void dmaMuxEnable(dmaIdentifier_e identifier, uint32_t dmaMuxId);
|
||||
|
||||
#else
|
||||
|
||||
#if defined(STM32G4)
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA1_CH1_HANDLER = 1,
|
||||
DMA1_CH2_HANDLER,
|
||||
DMA1_CH3_HANDLER,
|
||||
DMA1_CH4_HANDLER,
|
||||
DMA1_CH5_HANDLER,
|
||||
DMA1_CH6_HANDLER,
|
||||
DMA1_CH7_HANDLER,
|
||||
DMA1_CH8_HANDLER,
|
||||
DMA2_CH1_HANDLER,
|
||||
DMA2_CH2_HANDLER,
|
||||
DMA2_CH3_HANDLER,
|
||||
DMA2_CH4_HANDLER,
|
||||
DMA2_CH5_HANDLER,
|
||||
DMA2_CH6_HANDLER,
|
||||
DMA2_CH7_HANDLER,
|
||||
DMA2_CH8_HANDLER,
|
||||
DMA_LAST_HANDLER = DMA2_CH8_HANDLER
|
||||
} dmaIdentifier_e;
|
||||
|
||||
#define DMA_DEVICE_NO(x) ((((x)-1) / 8) + 1)
|
||||
#define DMA_DEVICE_INDEX(x) ((((x)-1) % 8) + 1)
|
||||
|
||||
uint32_t dmaGetChannel(const uint8_t channel);
|
||||
|
||||
#else // !STM32G4
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA1_CH1_HANDLER = 1,
|
||||
DMA1_CH2_HANDLER,
|
||||
DMA1_CH3_HANDLER,
|
||||
DMA1_CH4_HANDLER,
|
||||
DMA1_CH5_HANDLER,
|
||||
DMA1_CH6_HANDLER,
|
||||
DMA1_CH7_HANDLER,
|
||||
DMA_LAST_HANDLER = DMA1_CH7_HANDLER
|
||||
} dmaIdentifier_e;
|
||||
|
||||
#define DMA_DEVICE_NO(x) ((((x)-1) / 7) + 1)
|
||||
#define DMA_DEVICE_INDEX(x) ((((x)-1) % 7) + 1)
|
||||
|
||||
#endif // STM32G4
|
||||
|
||||
#define DMA_OUTPUT_INDEX 0
|
||||
#define DMA_OUTPUT_STRING "DMA%d Channel %d:"
|
||||
#define DMA_INPUT_STRING "DMA%d_CH%d"
|
||||
|
||||
#define DEFINE_DMA_CHANNEL(d, c, f) { \
|
||||
.dma = d, \
|
||||
.ref = (dmaResource_t *)d ## _Channel ## c, \
|
||||
.irqHandlerCallback = NULL, \
|
||||
.flagsShift = f, \
|
||||
.irqN = d ## _Channel ## c ## _IRQn, \
|
||||
.userParam = 0, \
|
||||
.owner.owner = 0, \
|
||||
.owner.resourceIndex = 0 \
|
||||
}
|
||||
|
||||
#define DMA_HANDLER_CODE
|
||||
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, c, i) DMA_HANDLER_CODE void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\
|
||||
const uint8_t index = DMA_IDENTIFIER_TO_INDEX(i); \
|
||||
dmaCallbackHandlerFuncPtr handler = dmaDescriptors[index].irqHandlerCallback; \
|
||||
if (handler) \
|
||||
handler(&dmaDescriptors[index]); \
|
||||
}
|
||||
|
||||
#define DMA_CLEAR_FLAG(d, flag) d->dma->IFCR = (flag << d->flagsShift)
|
||||
#define DMA_GET_FLAG_STATUS(d, flag) (d->dma->ISR & (flag << d->flagsShift))
|
||||
|
||||
#define DMA_IT_TCIF ((uint32_t)0x00000002)
|
||||
#define DMA_IT_HTIF ((uint32_t)0x00000004)
|
||||
#define DMA_IT_TEIF ((uint32_t)0x00000008)
|
||||
#endif
|
||||
|
||||
// Macros to avoid direct register and register bit access
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CR & DMA_SxCR_EN)
|
||||
#define REG_NDTR NDTR
|
||||
#elif defined(STM32H7)
|
||||
// For H7, we have to differenciate DMA1/2 and BDMA for access to the control register.
|
||||
// HAL library has a macro for this, but it is extremely inefficient in that it compares
|
||||
// the address against all possible values.
|
||||
// Here, we just compare the address against regions of memory.
|
||||
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
|
||||
// For H7A3, if it's lower than CD_AHB2PERIPH_BASE, then it's DMA1/2 and it's stream based.
|
||||
// If not, it's BDMA and it's channel based.
|
||||
#define IS_DMA_ENABLED(reg) \
|
||||
((uint32_t)(reg) < CD_AHB2PERIPH_BASE) ? \
|
||||
(((DMA_Stream_TypeDef *)(reg))->CR & DMA_SxCR_EN) : \
|
||||
(((BDMA_Channel_TypeDef *)(reg))->CCR & BDMA_CCR_EN)
|
||||
#else
|
||||
// For H743 and H750, if it's not in D3 peripheral area, then it's DMA1/2 and it's stream based.
|
||||
// If not, it's BDMA and it's channel based.
|
||||
#define IS_DMA_ENABLED(reg) \
|
||||
((uint32_t)(reg) < D3_AHB1PERIPH_BASE) ? \
|
||||
(((DMA_Stream_TypeDef *)(reg))->CR & DMA_SxCR_EN) : \
|
||||
(((BDMA_Channel_TypeDef *)(reg))->CCR & BDMA_CCR_EN)
|
||||
#endif
|
||||
#elif defined(STM32G4)
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN)
|
||||
// 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 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)
|
||||
#define REG_NDTR NDATA
|
||||
#else
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN)
|
||||
#define DMAx_SetMemoryAddress(reg, address) ((DMA_ARCH_TYPE *)(reg))->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail]
|
||||
#endif
|
||||
|
||||
dmaIdentifier_e dmaAllocate(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex);
|
||||
void dmaEnable(dmaIdentifier_e identifier);
|
||||
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam);
|
||||
|
@ -273,34 +71,3 @@ const resourceOwner_t *dmaGetOwner(dmaIdentifier_e identifier);
|
|||
dmaChannelDescriptor_t* dmaGetDescriptorByIdentifier(const dmaIdentifier_e identifier);
|
||||
uint32_t dmaGetChannel(const uint8_t channel);
|
||||
|
||||
//
|
||||
// Wrapper macros to cast dmaResource_t back into DMA_ARCH_TYPE
|
||||
//
|
||||
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
|
||||
// We actually need these LL case only
|
||||
|
||||
#define xLL_EX_DMA_DeInit(dmaResource) LL_EX_DMA_DeInit((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_Init(dmaResource, initstruct) LL_EX_DMA_Init((DMA_ARCH_TYPE *)(dmaResource), initstruct)
|
||||
#define xLL_EX_DMA_DisableResource(dmaResource) LL_EX_DMA_DisableResource((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_EnableResource(dmaResource) LL_EX_DMA_EnableResource((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_GetDataLength(dmaResource) LL_EX_DMA_GetDataLength((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_SetDataLength(dmaResource, length) LL_EX_DMA_SetDataLength((DMA_ARCH_TYPE *)(dmaResource), length)
|
||||
#define xLL_EX_DMA_EnableIT_TC(dmaResource) LL_EX_DMA_EnableIT_TC((DMA_ARCH_TYPE *)(dmaResource))
|
||||
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
|
||||
#else
|
||||
|
||||
#define xDMA_Init(dmaResource, initStruct) DMA_Init((DMA_ARCH_TYPE *)(dmaResource), initStruct)
|
||||
#define xDMA_DeInit(dmaResource) DMA_DeInit((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xDMA_Cmd(dmaResource, newState) DMA_Cmd((DMA_ARCH_TYPE *)(dmaResource), newState)
|
||||
#define xDMA_ITConfig(dmaResource, flags, newState) DMA_ITConfig((DMA_ARCH_TYPE *)(dmaResource), flags, newState)
|
||||
#define xDMA_GetCurrDataCounter(dmaResource) DMA_GetCurrDataCounter((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xDMA_SetCurrDataCounter(dmaResource, count) DMA_SetCurrDataCounter((DMA_ARCH_TYPE *)(dmaResource), count)
|
||||
#define xDMA_GetFlagStatus(dmaResource, flags) DMA_GetFlagStatus((DMA_ARCH_TYPE *)(dmaResource), flags)
|
||||
#define xDMA_ClearFlag(dmaResource, flags) DMA_ClearFlag((DMA_ARCH_TYPE *)(dmaResource), flags)
|
||||
#define xDMA_MemoryTargetConfig(dmaResource, address, target) DMA_MemoryTargetConfig((DMA_ARCH_TYPE *)(dmaResource), address, target)
|
||||
|
||||
#endif
|
||||
|
|
|
@ -48,7 +48,7 @@ void ioPreinitByIO(const IO_t io, uint8_t iocfg, ioPreinitPinState_e init)
|
|||
IOHi(io);
|
||||
break;
|
||||
default:
|
||||
// Do nothing
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -27,32 +27,26 @@
|
|||
|
||||
#include "light_led.h"
|
||||
|
||||
#if !(defined(UNIT_TEST) || defined(USE_VIRTUAL_LED))
|
||||
#if !defined(USE_VIRTUAL_LED)
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
|
||||
|
||||
static IO_t leds[STATUS_LED_NUMBER];
|
||||
static IO_t leds[STATUS_LED_COUNT];
|
||||
static uint8_t ledInversion = 0;
|
||||
|
||||
#ifndef LED0_PIN
|
||||
#define LED0_PIN NONE
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(statusLedConfig_t, statusLedConfig,
|
||||
.ioTags = {
|
||||
#if STATUS_LED_COUNT > 0 && defined(LED0_PIN)
|
||||
[0] = IO_TAG(LED0_PIN),
|
||||
#endif
|
||||
|
||||
#ifndef LED1_PIN
|
||||
#define LED1_PIN NONE
|
||||
#if STATUS_LED_COUNT > 1 && defined(LED1_PIN)
|
||||
[1] = IO_TAG(LED1_PIN),
|
||||
#endif
|
||||
|
||||
#ifndef LED2_PIN
|
||||
#define LED2_PIN NONE
|
||||
#if STATUS_LED_COUNT > 2 && defined(LED2_PIN)
|
||||
[2] = IO_TAG(LED2_PIN),
|
||||
#endif
|
||||
|
||||
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
|
||||
{
|
||||
statusLedConfig->ioTags[0] = IO_TAG(LED0_PIN);
|
||||
statusLedConfig->ioTags[1] = IO_TAG(LED1_PIN);
|
||||
statusLedConfig->ioTags[2] = IO_TAG(LED2_PIN);
|
||||
|
||||
statusLedConfig->inversion = 0
|
||||
},
|
||||
.inversion = 0
|
||||
#ifdef LED0_INVERTED
|
||||
| BIT(0)
|
||||
#endif
|
||||
|
@ -62,35 +56,37 @@ void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
|
|||
#ifdef LED2_INVERTED
|
||||
| BIT(2)
|
||||
#endif
|
||||
;
|
||||
}
|
||||
,
|
||||
);
|
||||
|
||||
void ledInit(const statusLedConfig_t *statusLedConfig)
|
||||
{
|
||||
ledInversion = statusLedConfig->inversion;
|
||||
for (int i = 0; i < STATUS_LED_NUMBER; i++) {
|
||||
if (statusLedConfig->ioTags[i]) {
|
||||
leds[i] = IOGetByTag(statusLedConfig->ioTags[i]);
|
||||
for (int i = 0; i < (int)ARRAYLEN(leds); i++) {
|
||||
leds[i] = IOGetByTag(statusLedConfig->ioTags[i]);
|
||||
if (leds[i]) {
|
||||
IOInit(leds[i], OWNER_LED, RESOURCE_INDEX(i));
|
||||
IOConfigGPIO(leds[i], IOCFG_OUT_PP);
|
||||
} else {
|
||||
leds[i] = IO_NONE;
|
||||
}
|
||||
ledSet(i, false);
|
||||
}
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
LED2_OFF;
|
||||
}
|
||||
|
||||
void ledToggle(int led)
|
||||
{
|
||||
if (led < 0 || led >= (int)ARRAYLEN(leds)) {
|
||||
return;
|
||||
}
|
||||
IOToggle(leds[led]);
|
||||
}
|
||||
|
||||
void ledSet(int led, bool on)
|
||||
{
|
||||
const bool inverted = (1 << (led)) & ledInversion;
|
||||
if (led < 0 || led >= (int)ARRAYLEN(leds)) {
|
||||
return;
|
||||
}
|
||||
const bool inverted = ledInversion & (1 << led);
|
||||
IOWrite(leds[led], on ? inverted : !inverted);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -24,31 +24,9 @@
|
|||
#include "drivers/io_types.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#define STATUS_LED_NUMBER 3
|
||||
|
||||
typedef struct statusLedConfig_s {
|
||||
ioTag_t ioTags[STATUS_LED_NUMBER];
|
||||
uint8_t inversion;
|
||||
} statusLedConfig_t;
|
||||
#define STATUS_LED_COUNT 3
|
||||
|
||||
// Helpful macros
|
||||
#if defined(UNIT_TEST) || defined(USE_VIRTUAL_LED)
|
||||
|
||||
#define LED0_TOGGLE NOOP
|
||||
#define LED0_OFF NOOP
|
||||
#define LED0_ON NOOP
|
||||
|
||||
#define LED1_TOGGLE NOOP
|
||||
#define LED1_OFF NOOP
|
||||
#define LED1_ON NOOP
|
||||
|
||||
#define LED2_TOGGLE NOOP
|
||||
#define LED2_OFF NOOP
|
||||
#define LED2_ON NOOP
|
||||
|
||||
#else
|
||||
|
||||
PG_DECLARE(statusLedConfig_t, statusLedConfig);
|
||||
|
||||
#define LED0_TOGGLE ledToggle(0)
|
||||
#define LED0_OFF ledSet(0, false)
|
||||
|
@ -62,6 +40,22 @@ PG_DECLARE(statusLedConfig_t, statusLedConfig);
|
|||
#define LED2_OFF ledSet(2, false)
|
||||
#define LED2_ON ledSet(2, true)
|
||||
|
||||
// use dummy functions for unittest
|
||||
#if defined(USE_VIRTUAL_LED)
|
||||
|
||||
// ledInit is missing intentionally
|
||||
static inline void ledToggle(int led) { UNUSED(led); }
|
||||
static inline void ledSet(int led, bool state) { UNUSED(led); UNUSED(state); }
|
||||
|
||||
#else
|
||||
|
||||
typedef struct statusLedConfig_s {
|
||||
ioTag_t ioTags[STATUS_LED_COUNT];
|
||||
uint8_t inversion;
|
||||
} statusLedConfig_t;
|
||||
|
||||
PG_DECLARE(statusLedConfig_t, statusLedConfig);
|
||||
|
||||
void ledInit(const statusLedConfig_t *statusLedConfig);
|
||||
void ledToggle(int led);
|
||||
void ledSet(int led, bool state);
|
||||
|
|
|
@ -60,7 +60,7 @@
|
|||
#define WS2811_DMA_BUF_CACHE_ALIGN_LENGTH (WS2811_DMA_BUF_CACHE_ALIGN_BYTES / sizeof(uint32_t))
|
||||
DMA_RW_AXI __attribute__((aligned(32))) uint32_t ledStripDMABuffer[WS2811_DMA_BUF_CACHE_ALIGN_LENGTH];
|
||||
#else
|
||||
FAST_DATA_ZERO_INIT uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
DMA_DATA_ZERO_INIT uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
#endif
|
||||
|
||||
static ioTag_t ledStripIoTag;
|
||||
|
|
|
@ -109,7 +109,9 @@ void motorWriteAll(float *values)
|
|||
// Perform the decode of the last data received
|
||||
// New data will be received once the send of motor data, triggered above, completes
|
||||
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
|
||||
motorDevice.vTable->decodeTelemetry();
|
||||
if (motorDevice.vTable->decodeTelemetry) {
|
||||
motorDevice.vTable->decodeTelemetry();
|
||||
}
|
||||
#endif
|
||||
|
||||
// Update the motor data
|
||||
|
@ -184,7 +186,7 @@ bool checkMotorProtocolEnabled(const motorDevConfig_t *motorDevConfig, bool *isP
|
|||
motorProtocolFamily_e motorGetProtocolFamily(void)
|
||||
{
|
||||
switch (motorConfig()->dev.motorProtocol) {
|
||||
#ifdef USE_PWMOUTPUT
|
||||
#ifdef USE_PWM_OUTPUT
|
||||
case MOTOR_PROTOCOL_PWM :
|
||||
case MOTOR_PROTOCOL_ONESHOT125:
|
||||
case MOTOR_PROTOCOL_ONESHOT42:
|
||||
|
@ -362,6 +364,14 @@ timeMs_t motorGetMotorEnableTimeMs(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
IO_t motorGetIo(unsigned index)
|
||||
{
|
||||
if (index >= motorDevice.count) {
|
||||
return IO_NONE;
|
||||
}
|
||||
return motorDevice.vTable->getMotorIO ? motorDevice.vTable->getMotorIO(index) : IO_NONE;
|
||||
}
|
||||
|
||||
/* functions below for empty methods and no active motors */
|
||||
void motorPostInitNull(void)
|
||||
{
|
||||
|
@ -433,6 +443,7 @@ static const motorVTable_t motorNullVTable = {
|
|||
.shutdown = motorShutdownNull,
|
||||
.requestTelemetry = NULL,
|
||||
.isMotorIdle = NULL,
|
||||
.getMotorIO = NULL,
|
||||
};
|
||||
|
||||
void motorNullDevInit(motorDevice_t *device)
|
||||
|
|
|
@ -54,5 +54,7 @@ float motorEstimateMaxRpm(void);
|
|||
bool motorIsEnabled(void);
|
||||
bool motorIsMotorEnabled(unsigned index);
|
||||
bool motorIsMotorIdle(unsigned index);
|
||||
IO_t motorGetIo(unsigned index);
|
||||
|
||||
timeMs_t motorGetMotorEnableTimeMs(void);
|
||||
void motorShutdown(void); // Replaces stopPwmAllMotors
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "common/time.h"
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
#define ALL_MOTORS 255
|
||||
#define MOTOR_OUTPUT_LIMIT_PERCENT_MIN 1
|
||||
|
@ -64,6 +65,7 @@ typedef struct motorVTable_s {
|
|||
void (*updateComplete)(void);
|
||||
void (*shutdown)(void);
|
||||
bool (*isMotorIdle)(unsigned index);
|
||||
IO_t (*getMotorIO)(unsigned index);
|
||||
|
||||
// Digital commands
|
||||
void (*requestTelemetry)(unsigned index);
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
|
||||
#if defined(USE_PWM_OUTPUT) && defined(USE_MOTOR)
|
||||
|
||||
FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
||||
FAST_DATA_ZERO_INIT pwmOutputPort_t pwmMotors[MAX_SUPPORTED_MOTORS];
|
||||
FAST_DATA_ZERO_INIT uint8_t pwmMotorCount;
|
||||
|
||||
void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
||||
|
@ -48,4 +48,23 @@ void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, fl
|
|||
}
|
||||
}
|
||||
|
||||
IO_t pwmGetMotorIO(unsigned index)
|
||||
{
|
||||
if (index >= pwmMotorCount) {
|
||||
return IO_NONE;
|
||||
}
|
||||
return pwmMotors[index].io;
|
||||
}
|
||||
|
||||
bool pwmIsMotorEnabled(unsigned index)
|
||||
{
|
||||
return pwmMotors[index].enabled;
|
||||
}
|
||||
|
||||
bool pwmEnableMotors(void)
|
||||
{
|
||||
/* check motors can be enabled */
|
||||
return pwmMotorCount > 0;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -50,7 +50,7 @@ typedef struct {
|
|||
IO_t io;
|
||||
} pwmOutputPort_t;
|
||||
|
||||
extern FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
||||
extern FAST_DATA_ZERO_INIT pwmOutputPort_t pwmMotors[MAX_SUPPORTED_MOTORS];
|
||||
extern FAST_DATA_ZERO_INIT uint8_t pwmMotorCount;
|
||||
|
||||
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorDevConfig, uint16_t idlePulse);
|
||||
|
|
28
src/main/drivers/pwm_output_impl.h
Normal file
28
src/main/drivers/pwm_output_impl.h
Normal file
|
@ -0,0 +1,28 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the GNU General
|
||||
* Public License as published by the Free Software Foundation,
|
||||
* either version 3 of the License, or (at your option) any later
|
||||
* version.
|
||||
*
|
||||
* Betaflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
*
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public
|
||||
* License along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
IO_t pwmGetMotorIO(unsigned index);
|
||||
bool pwmIsMotorEnabled(unsigned index);
|
||||
bool pwmEnableMotors(void);
|
|
@ -101,13 +101,8 @@ void expressLrsUpdateTimerInterval(uint16_t intervalUs)
|
|||
timerState.intervalUs = intervalUs;
|
||||
expressLrsRecalculatePhaseShiftLimits();
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
timerReconfigureTimeBase(timer, expressLrsCalculateMaximumExpectedPeriod(timerState.intervalUs), MHZ_TO_HZ(1));
|
||||
LL_TIM_SetAutoReload(timer, (timerState.intervalUs / TICK_TOCK_COUNT) - 1);
|
||||
#else
|
||||
configTimeBase(timer, expressLrsCalculateMaximumExpectedPeriod(timerState.intervalUs), MHZ_TO_HZ(1));
|
||||
TIM_SetAutoreload(timer, (timerState.intervalUs / TICK_TOCK_COUNT) - 1);
|
||||
#endif
|
||||
timerSetPeriod(timer, (timerState.intervalUs / TICK_TOCK_COUNT) - 1);
|
||||
}
|
||||
|
||||
void expressLrsUpdatePhaseShift(int32_t newPhaseShift)
|
||||
|
@ -140,11 +135,7 @@ static void expressLrsOnTimerUpdate(timerOvrHandlerRec_t *cbRec, captureCompare_
|
|||
|
||||
uint32_t adjustedPeriod = (timerState.intervalUs / TICK_TOCK_COUNT) + timerState.frequencyOffsetTicks;
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
LL_TIM_SetAutoReload(timer, adjustedPeriod - 1);
|
||||
#else
|
||||
TIM_SetAutoreload(timer, adjustedPeriod - 1);
|
||||
#endif
|
||||
timerSetPeriod(timer, adjustedPeriod - 1);
|
||||
|
||||
expressLrsOnTimerTickISR();
|
||||
|
||||
|
@ -154,11 +145,7 @@ static void expressLrsOnTimerUpdate(timerOvrHandlerRec_t *cbRec, captureCompare_
|
|||
|
||||
uint32_t adjustedPeriod = (timerState.intervalUs / TICK_TOCK_COUNT) + timerState.phaseShiftUs + timerState.frequencyOffsetTicks;
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
LL_TIM_SetAutoReload(timer, adjustedPeriod - 1);
|
||||
#else
|
||||
TIM_SetAutoreload(timer, adjustedPeriod - 1);
|
||||
#endif
|
||||
timerSetPeriod(timer, adjustedPeriod - 1);
|
||||
|
||||
timerState.phaseShiftUs = 0;
|
||||
|
||||
|
@ -175,15 +162,8 @@ bool expressLrsTimerIsRunning(void)
|
|||
|
||||
void expressLrsTimerStop(void)
|
||||
{
|
||||
#ifdef USE_HAL_DRIVER
|
||||
LL_TIM_DisableIT_UPDATE(timer);
|
||||
LL_TIM_DisableCounter(timer);
|
||||
LL_TIM_SetCounter(timer, 0);
|
||||
#else
|
||||
TIM_ITConfig(timer, TIM_IT_Update, DISABLE);
|
||||
TIM_Cmd(timer, DISABLE);
|
||||
TIM_SetCounter(timer, 0);
|
||||
#endif
|
||||
timerDisable(timer);
|
||||
timerSetCounter(timer, 0);
|
||||
timerState.running = false;
|
||||
}
|
||||
|
||||
|
@ -191,29 +171,12 @@ void expressLrsTimerResume(void)
|
|||
{
|
||||
timerState.tickTock = TOCK;
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
LL_TIM_SetAutoReload(timer, (timerState.intervalUs / TICK_TOCK_COUNT));
|
||||
LL_TIM_SetCounter(timer, 0);
|
||||
|
||||
LL_TIM_ClearFlag_UPDATE(timer);
|
||||
LL_TIM_EnableIT_UPDATE(timer);
|
||||
#else
|
||||
TIM_SetAutoreload(timer, (timerState.intervalUs / TICK_TOCK_COUNT));
|
||||
TIM_SetCounter(timer, 0);
|
||||
|
||||
TIM_ClearFlag(timer, TIM_FLAG_Update);
|
||||
TIM_ITConfig(timer, TIM_IT_Update, ENABLE);
|
||||
#endif
|
||||
timerSetPeriod(timer, (timerState.intervalUs / TICK_TOCK_COUNT));
|
||||
timerSetCounter(timer, 0);
|
||||
|
||||
timerEnableInterrupt(timer);
|
||||
timerState.running = true;
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
LL_TIM_EnableCounter(timer);
|
||||
LL_TIM_GenerateEvent_UPDATE(timer);
|
||||
#else
|
||||
TIM_Cmd(timer, ENABLE);
|
||||
TIM_GenerateEvent(timer, TIM_EventSource_Update);
|
||||
#endif
|
||||
timerEnable(timer);
|
||||
}
|
||||
|
||||
void expressLrsInitialiseTimer(TIM_TypeDef *t, timerOvrHandlerRec_t *timerUpdateCb)
|
||||
|
|
|
@ -129,8 +129,20 @@ void serialWriteBuf(serialPort_t *instance, const uint8_t *data, int count)
|
|||
serialEndWrite(instance);
|
||||
}
|
||||
|
||||
void serialWriteBufBlocking(serialPort_t *instance, const uint8_t *data, int count)
|
||||
{
|
||||
while (serialTxBytesFree(instance) < (uint32_t)count) /* NOP */;
|
||||
serialWriteBuf(instance, data, count);
|
||||
}
|
||||
|
||||
void serialWriteBufShim(void *instance, const uint8_t *data, int count)
|
||||
{
|
||||
serialWriteBuf((serialPort_t *)instance, data, count);
|
||||
}
|
||||
|
||||
void serialWriteBufBlockingShim(void *instance, const uint8_t *data, int count)
|
||||
{
|
||||
serialWriteBufBlocking(instance, data, count);
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -150,5 +150,6 @@ uint32_t serialGetBaudRate(serialPort_t *instance);
|
|||
|
||||
// A shim that adapts the bufWriter API to the serialWriteBuf() API.
|
||||
void serialWriteBufShim(void *instance, const uint8_t *data, int count);
|
||||
void serialWriteBufBlockingShim(void *instance, const uint8_t *data, int count);
|
||||
void serialBeginWrite(serialPort_t *instance);
|
||||
void serialEndWrite(serialPort_t *instance);
|
||||
|
|
|
@ -134,13 +134,6 @@ enum {
|
|||
#define STOP_BIT_MASK (1 << 0)
|
||||
#define START_BIT_MASK (1 << (RX_TOTAL_BITS - 1))
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
static void TIM_DeInit(TIM_TypeDef *tim)
|
||||
{
|
||||
LL_TIM_DeInit(tim);
|
||||
}
|
||||
#endif
|
||||
|
||||
static void setTxSignalEsc(escSerial_t *escSerial, uint8_t state)
|
||||
{
|
||||
if (escSerial->mode == PROTOCOL_KISSALL)
|
||||
|
@ -343,7 +336,7 @@ static void serialTimerTxConfigBL(const timerHardware_t *timerHardwarePtr, uint8
|
|||
{
|
||||
uint32_t clock = SystemCoreClock/2;
|
||||
uint32_t timerPeriod;
|
||||
TIM_DeInit(timerHardwarePtr->tim);
|
||||
timerReset(timerHardwarePtr->tim);
|
||||
do {
|
||||
timerPeriod = clock / baud;
|
||||
if (isTimerPeriodTooLarge(timerPeriod)) {
|
||||
|
@ -377,11 +370,8 @@ static void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t c
|
|||
// Adjust the timing so it will interrupt on the middle.
|
||||
// This is clobbers transmission, but it is okay because we are
|
||||
// always half-duplex.
|
||||
#ifdef USE_HAL_DRIVER
|
||||
__HAL_TIM_SetCounter(escSerial->txTimerHandle, __HAL_TIM_GetAutoreload(escSerial->txTimerHandle) / 2);
|
||||
#else
|
||||
TIM_SetCounter(escSerial->txTimerHardware->tim, escSerial->txTimerHardware->tim->ARR / 2);
|
||||
#endif
|
||||
timerSetCounter(escSerial->txTimerHardware->tim, timerGetPeriod(escSerial->txTimerHardware->tim) / 2);
|
||||
|
||||
if (escSerial->isTransmittingData) {
|
||||
escSerial->transmissionErrors++;
|
||||
}
|
||||
|
@ -414,7 +404,7 @@ static void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t c
|
|||
static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8_t reference, portOptions_e options)
|
||||
{
|
||||
// start bit is usually a FALLING signal
|
||||
TIM_DeInit(timerHardwarePtr->tim);
|
||||
timerReset(timerHardwarePtr->tim);
|
||||
timerReconfigureTimeBase(timerHardwarePtr->tim, 0xFFFF, SystemCoreClock / 2);
|
||||
timerChConfigIC(timerHardwarePtr, (options & SERIAL_INVERTED) ? ICPOLARITY_RISING : ICPOLARITY_FALLING, 0);
|
||||
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeBL);
|
||||
|
@ -538,7 +528,7 @@ static void onSerialTimerEsc(timerCCHandlerRec_t *cbRec, captureCompare_t captur
|
|||
static void escSerialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
||||
{
|
||||
uint32_t timerPeriod = 34;
|
||||
TIM_DeInit(timerHardwarePtr->tim);
|
||||
timerReset(timerHardwarePtr->tim);
|
||||
timerReconfigureTimeBase(timerHardwarePtr->tim, timerPeriod, MHZ_TO_HZ(1));
|
||||
timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimerEsc);
|
||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
||||
|
@ -570,12 +560,7 @@ static void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t
|
|||
|
||||
escSerial_t *escSerial = container_of(cbRec, escSerial_t, edgeCb);
|
||||
|
||||
//clear timer
|
||||
#ifdef USE_HAL_DRIVER
|
||||
__HAL_TIM_SetCounter(escSerial->rxTimerHandle, 0);
|
||||
#else
|
||||
TIM_SetCounter(escSerial->rxTimerHardware->tim,0);
|
||||
#endif
|
||||
timerSetCounter(escSerial->rxTimerHardware->tim, 0);
|
||||
|
||||
if (capture > 40 && capture < 90)
|
||||
{
|
||||
|
@ -628,7 +613,7 @@ static void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t
|
|||
static void escSerialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
||||
{
|
||||
// start bit is usually a FALLING signal
|
||||
TIM_DeInit(timerHardwarePtr->tim);
|
||||
timerReset(timerHardwarePtr->tim);
|
||||
timerReconfigureTimeBase(timerHardwarePtr->tim, 0xFFFF, MHZ_TO_HZ(1));
|
||||
timerChConfigIC(timerHardwarePtr, ICPOLARITY_FALLING, 0);
|
||||
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc);
|
||||
|
@ -786,11 +771,11 @@ static void closeEscSerial(escSerialPortIndex_e portIndex, uint8_t mode)
|
|||
if (mode != PROTOCOL_KISSALL) {
|
||||
escSerialInputPortDeConfig(escSerial->rxTimerHardware);
|
||||
timerChConfigCallbacks(escSerial->rxTimerHardware,NULL,NULL);
|
||||
TIM_DeInit(escSerial->rxTimerHardware->tim);
|
||||
timerReset(escSerial->rxTimerHardware->tim);
|
||||
}
|
||||
|
||||
timerChConfigCallbacks(escSerial->txTimerHardware,NULL,NULL);
|
||||
TIM_DeInit(escSerial->txTimerHardware->tim);
|
||||
timerReset(escSerial->txTimerHardware->tim);
|
||||
}
|
||||
|
||||
static uint32_t escSerialTotalBytesWaiting(const serialPort_t *instance)
|
||||
|
|
|
@ -487,11 +487,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
|||
// Synchronize the bit timing so that it will interrupt at the center
|
||||
// of the bit period.
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
__HAL_TIM_SetCounter(self->timerHandle, __HAL_TIM_GetAutoreload(self->timerHandle) / 2);
|
||||
#else
|
||||
TIM_SetCounter(self->timerHardware->tim, self->timerHardware->tim->ARR / 2);
|
||||
#endif
|
||||
timerSetCounter(self->timerHardware->tim, timerGetPeriod(self->timerHardware->tim) / 2);
|
||||
|
||||
// For a mono-timer full duplex configuration, this may clobber the
|
||||
// transmission because the next callback to the onSerialTimerOverflow
|
||||
|
|
|
@ -216,3 +216,12 @@ uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_
|
|||
int8_t timerGetNumberByIndex(uint8_t index);
|
||||
int8_t timerGetTIMNumber(const TIM_TypeDef *tim);
|
||||
uint8_t timerLookupChannelIndex(const uint16_t channel);
|
||||
|
||||
// TODO: replace TIM_TypeDef with alternate
|
||||
void timerReset(TIM_TypeDef *timer);
|
||||
void timerSetPeriod(TIM_TypeDef *timer, uint32_t period);
|
||||
uint32_t timerGetPeriod(TIM_TypeDef *timer);
|
||||
void timerSetCounter(TIM_TypeDef *timer, uint32_t counter);
|
||||
void timerDisable(TIM_TypeDef *timer);
|
||||
void timerEnable(TIM_TypeDef *timer);
|
||||
void timerEnableInterrupt(TIM_TypeDef *timer);
|
||||
|
|
|
@ -485,7 +485,7 @@ void init(void)
|
|||
|
||||
#if defined(STM32F4) || defined(STM32G4) || defined(APM32F4)
|
||||
// F4 has non-8MHz boards
|
||||
// G4 for Betaflight allow 24 or 27MHz oscillator
|
||||
// G4 for Betaflight allow 8, 16, 24, 26 or 27MHz oscillator
|
||||
systemClockSetHSEValue(systemConfig()->hseMhz * 1000000U);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -161,20 +161,20 @@
|
|||
#define PARAM_NAME_ALTITUDE_LPF "altitude_lpf"
|
||||
#define PARAM_NAME_ALTITUDE_D_LPF "altitude_d_lpf"
|
||||
|
||||
#define PARAM_NAME_HOVER_THROTTLE "hover_throttle"
|
||||
#define PARAM_NAME_LANDING_ALTITUDE "landing_altitude_m"
|
||||
#define PARAM_NAME_THROTTLE_MIN "autopilot_throttle_min"
|
||||
#define PARAM_NAME_THROTTLE_MAX "autopilot_throttle_max"
|
||||
#define PARAM_NAME_ALTITUDE_P "autopilot_altitude_P"
|
||||
#define PARAM_NAME_ALTITUDE_I "autopilot_altitude_I"
|
||||
#define PARAM_NAME_ALTITUDE_D "autopilot_altitude_D"
|
||||
#define PARAM_NAME_ALTITUDE_F "autopilot_altitude_F"
|
||||
#define PARAM_NAME_POSITION_P "autopilot_position_P"
|
||||
#define PARAM_NAME_POSITION_I "autopilot_position_I"
|
||||
#define PARAM_NAME_POSITION_D "autopilot_position_D"
|
||||
#define PARAM_NAME_POSITION_A "autopilot_position_A"
|
||||
#define PARAM_NAME_POSITION_CUTOFF "autopilot_position_cutoff"
|
||||
#define PARAM_NAME_AP_MAX_ANGLE "autopilot_max_angle"
|
||||
#define PARAM_NAME_AP_LANDING_ALTITUDE_M "ap_landing_altitude_m"
|
||||
#define PARAM_NAME_AP_HOVER_THROTTLE "ap_hover_throttle"
|
||||
#define PARAM_NAME_AP_THROTTLE_MIN "ap_throttle_min"
|
||||
#define PARAM_NAME_AP_THROTTLE_MAX "ap_throttle_max"
|
||||
#define PARAM_NAME_AP_ALTITUDE_P "ap_altitude_p"
|
||||
#define PARAM_NAME_AP_ALTITUDE_I "ap_altitude_i"
|
||||
#define PARAM_NAME_AP_ALTITUDE_D "ap_altitude_d"
|
||||
#define PARAM_NAME_AP_ALTITUDE_F "ap_altitude_f"
|
||||
#define PARAM_NAME_AP_POSITION_P "ap_position_p"
|
||||
#define PARAM_NAME_AP_POSITION_I "ap_position_i"
|
||||
#define PARAM_NAME_AP_POSITION_D "ap_position_d"
|
||||
#define PARAM_NAME_AP_POSITION_A "ap_position_a"
|
||||
#define PARAM_NAME_AP_POSITION_CUTOFF "ap_position_cutoff"
|
||||
#define PARAM_NAME_AP_MAX_ANGLE "ap_max_angle"
|
||||
|
||||
#define PARAM_NAME_ANGLE_FEEDFORWARD "angle_feedforward"
|
||||
#define PARAM_NAME_ANGLE_FF_SMOOTHING_MS "angle_feedforward_smoothing_ms"
|
||||
|
@ -259,7 +259,7 @@
|
|||
|
||||
#ifdef USE_ALTITUDE_HOLD
|
||||
#define PARAM_NAME_ALT_HOLD_DEADBAND "alt_hold_deadband"
|
||||
#define PARAM_NAME_ALT_HOLD_THROTTLE_RESPONSE "alt_hold_throttle_response"
|
||||
#define PARAM_NAME_ALT_HOLD_CLIMB_RATE "alt_hold_climb_rate"
|
||||
#endif
|
||||
|
||||
#ifdef USE_POSITION_HOLD
|
||||
|
|
|
@ -62,9 +62,9 @@ static void altHoldReset(void)
|
|||
void altHoldInit(void)
|
||||
{
|
||||
altHold.isActive = false;
|
||||
altHold.deadband = altHoldConfig()->alt_hold_deadband / 100.0f;
|
||||
altHold.allowStickAdjustment = altHoldConfig()->alt_hold_deadband;
|
||||
altHold.maxVelocity = altHoldConfig()->alt_hold_adjust_rate * 10.0f; // 50 in CLI means 500cm/s
|
||||
altHold.deadband = altHoldConfig()->deadband / 100.0f;
|
||||
altHold.allowStickAdjustment = altHoldConfig()->deadband;
|
||||
altHold.maxVelocity = altHoldConfig()->climbRate * 10.0f; // 50 in CLI means 500cm/s
|
||||
altHoldReset();
|
||||
}
|
||||
|
||||
|
@ -81,7 +81,7 @@ static void altHoldProcessTransitions(void) {
|
|||
|
||||
// ** the transition out of alt hold (exiting altHold) may be rough. Some notes... **
|
||||
// The original PR had a gradual transition from hold throttle to pilot control throttle
|
||||
// using !(altHoldRequested && altHold.isAltHoldActive) to run an exit function
|
||||
// using !(altHoldRequested && altHold.isActive) to run an exit function
|
||||
// a cross-fade factor was sent to mixer.c based on time since the flight mode request was terminated
|
||||
// it was removed primarily to simplify this PR
|
||||
|
||||
|
@ -101,8 +101,8 @@ static void altHoldUpdateTargetAltitude(void)
|
|||
|
||||
if (altHold.allowStickAdjustment && calculateThrottleStatus() != THROTTLE_LOW) {
|
||||
const float rcThrottle = rcCommand[THROTTLE];
|
||||
const float lowThreshold = apConfig()->hover_throttle - altHold.deadband * (apConfig()->hover_throttle - PWM_RANGE_MIN);
|
||||
const float highThreshold = apConfig()->hover_throttle + altHold.deadband * (PWM_RANGE_MAX - apConfig()->hover_throttle);
|
||||
const float lowThreshold = autopilotConfig()->hoverThrottle - altHold.deadband * (autopilotConfig()->hoverThrottle - PWM_RANGE_MIN);
|
||||
const float highThreshold = autopilotConfig()->hoverThrottle + altHold.deadband * (PWM_RANGE_MAX - autopilotConfig()->hoverThrottle);
|
||||
|
||||
if (rcThrottle < lowThreshold) {
|
||||
stickFactor = scaleRangef(rcThrottle, PWM_RANGE_MIN, lowThreshold, -1.0f, 0.0f);
|
||||
|
@ -136,7 +136,7 @@ static void altHoldUpdateTargetAltitude(void)
|
|||
static void altHoldUpdate(void)
|
||||
{
|
||||
// check if the user has changed the target altitude using sticks
|
||||
if (altHoldConfig()->alt_hold_adjust_rate) {
|
||||
if (altHoldConfig()->climbRate) {
|
||||
altHoldUpdateTargetAltitude();
|
||||
}
|
||||
altitudeControl(altHold.targetAltitudeCm, taskIntervalSeconds, altHold.targetVelocity);
|
||||
|
|
|
@ -138,23 +138,22 @@ void resetPositionControl(const gpsLocation_t *initialTargetLocation, unsigned t
|
|||
|
||||
void autopilotInit(void)
|
||||
{
|
||||
const apConfig_t *cfg = apConfig();
|
||||
|
||||
const autopilotConfig_t *cfg = autopilotConfig();
|
||||
ap.sticksActive = false;
|
||||
ap.maxAngle = cfg->max_angle;
|
||||
altitudePidCoeffs.Kp = cfg->altitude_P * ALTITUDE_P_SCALE;
|
||||
altitudePidCoeffs.Ki = cfg->altitude_I * ALTITUDE_I_SCALE;
|
||||
altitudePidCoeffs.Kd = cfg->altitude_D * ALTITUDE_D_SCALE;
|
||||
altitudePidCoeffs.Kf = cfg->altitude_F * ALTITUDE_F_SCALE;
|
||||
positionPidCoeffs.Kp = cfg->position_P * POSITION_P_SCALE;
|
||||
positionPidCoeffs.Ki = cfg->position_I * POSITION_I_SCALE;
|
||||
positionPidCoeffs.Kd = cfg->position_D * POSITION_D_SCALE;
|
||||
positionPidCoeffs.Kf = cfg->position_A * POSITION_A_SCALE; // Kf used for acceleration
|
||||
ap.maxAngle = cfg->maxAngle;
|
||||
altitudePidCoeffs.Kp = cfg->altitudeP * ALTITUDE_P_SCALE;
|
||||
altitudePidCoeffs.Ki = cfg->altitudeI * ALTITUDE_I_SCALE;
|
||||
altitudePidCoeffs.Kd = cfg->altitudeD * ALTITUDE_D_SCALE;
|
||||
altitudePidCoeffs.Kf = cfg->altitudeF * ALTITUDE_F_SCALE;
|
||||
positionPidCoeffs.Kp = cfg->positionP * POSITION_P_SCALE;
|
||||
positionPidCoeffs.Ki = cfg->positionI * POSITION_I_SCALE;
|
||||
positionPidCoeffs.Kd = cfg->positionD * POSITION_D_SCALE;
|
||||
positionPidCoeffs.Kf = cfg->positionA * POSITION_A_SCALE; // Kf used for acceleration
|
||||
// initialise filters with approximate filter gains; location isn't used at this point.
|
||||
ap.upsampleLpfGain = pt3FilterGain(UPSAMPLING_CUTOFF_HZ, 0.01f); // 5Hz, assuming 100Hz task rate at init
|
||||
resetUpsampleFilters();
|
||||
// Initialise PT1 filters for velocity and acceleration in earth frame axes
|
||||
ap.vaLpfCutoff = cfg->position_cutoff * 0.01f;
|
||||
ap.vaLpfCutoff = cfg->positionCutoff * 0.01f;
|
||||
const float vaGain = pt1FilterGain(ap.vaLpfCutoff, 0.1f); // assume 10Hz GPS connection at start; value is overwritten before first filter use
|
||||
for (unsigned i = 0; i < ARRAYLEN(ap.efAxis); i++) {
|
||||
resetEFAxisFilters(&ap.efAxis[i], vaGain);
|
||||
|
@ -193,7 +192,7 @@ void altitudeControl(float targetAltitudeCm, float taskIntervalS, float targetAl
|
|||
|
||||
const float altitudeF = targetAltitudeStep * altitudePidCoeffs.Kf;
|
||||
|
||||
const float hoverOffset = apConfig()->hover_throttle - PWM_RANGE_MIN;
|
||||
const float hoverOffset = autopilotConfig()->hoverThrottle - PWM_RANGE_MIN;
|
||||
float throttleOffset = altitudeP + altitudeI - altitudeD + altitudeF + hoverOffset;
|
||||
|
||||
const float tiltMultiplier = 1.0f / fmaxf(getCosTiltAngle(), 0.5f);
|
||||
|
@ -203,7 +202,7 @@ void altitudeControl(float targetAltitudeCm, float taskIntervalS, float targetAl
|
|||
throttleOffset *= tiltMultiplier;
|
||||
|
||||
float newThrottle = PWM_RANGE_MIN + throttleOffset;
|
||||
newThrottle = constrainf(newThrottle, apConfig()->throttle_min, apConfig()->throttle_max);
|
||||
newThrottle = constrainf(newThrottle, autopilotConfig()->throttleMin, autopilotConfig()->throttleMax);
|
||||
DEBUG_SET(DEBUG_AUTOPILOT_ALTITUDE, 0, lrintf(newThrottle)); // normal range 1000-2000 but is before constraint
|
||||
|
||||
newThrottle = scaleRangef(newThrottle, MAX(rxConfig()->mincheck, PWM_RANGE_MIN), PWM_RANGE_MAX, 0.0f, 1.0f);
|
||||
|
@ -386,7 +385,7 @@ bool positionControl(void)
|
|||
|
||||
bool isBelowLandingAltitude(void)
|
||||
{
|
||||
return getAltitudeCm() < 100.0f * apConfig()->landing_altitude_m;
|
||||
return getAltitudeCm() < 100.0f * autopilotConfig()->landingAltitudeM;
|
||||
}
|
||||
|
||||
float getAutopilotThrottle(void)
|
||||
|
|
|
@ -630,7 +630,7 @@ static void descend(bool newGpsData)
|
|||
{
|
||||
if (newGpsData) {
|
||||
// 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 * apConfig()->landing_altitude_m);
|
||||
const float distanceToLandingAreaM = rescueState.sensor.distanceToHomeM - (0.5f * autopilotConfig()->landingAltitudeM);
|
||||
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
|
||||
|
|
|
@ -268,7 +268,7 @@ const mixer_t mixers[] = {
|
|||
{ 1, true, NULL }, // MIXER_SINGLECOPTER
|
||||
{ 4, false, mixerAtail4 }, // MIXER_ATAIL4
|
||||
{ 0, false, NULL }, // MIXER_CUSTOM
|
||||
{ 2, true, NULL }, // MIXER_CUSTOM_AIRPLANE
|
||||
{ 1, true, NULL }, // MIXER_CUSTOM_AIRPLANE
|
||||
{ 3, true, NULL }, // MIXER_CUSTOM_TRI
|
||||
{ 4, false, mixerQuadX1234 }, // MIXER_QUADX_1234
|
||||
{ 8, false, mixerOctoX8P }, // MIXER_OCTOX8P
|
||||
|
|
|
@ -586,7 +586,7 @@ STATIC_UNIT_TESTED FAST_CODE_NOINLINE float pidLevel(int axis, const pidProfile_
|
|||
angleLimit = 85.0f; // allow autopilot to use whatever angle it needs to stop
|
||||
}
|
||||
// limit pilot requested angle to half the autopilot angle to avoid excess speed and chaotic stops
|
||||
angleLimit = fminf(0.5f * apConfig()->max_angle, angleLimit);
|
||||
angleLimit = fminf(0.5f * autopilotConfig()->maxAngle, angleLimit);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -51,8 +51,8 @@ static posHoldState_t posHold;
|
|||
|
||||
void posHoldInit(void)
|
||||
{
|
||||
posHold.deadband = posHoldConfig()->pos_hold_deadband * 0.01f;
|
||||
posHold.useStickAdjustment = posHoldConfig()->pos_hold_deadband;
|
||||
posHold.deadband = posHoldConfig()->deadband * 0.01f;
|
||||
posHold.useStickAdjustment = posHoldConfig()->deadband;
|
||||
}
|
||||
|
||||
static void posHoldCheckSticks(void)
|
||||
|
@ -73,7 +73,7 @@ static bool sensorsOk(void)
|
|||
#ifdef USE_MAG
|
||||
!compassIsHealthy() &&
|
||||
#endif
|
||||
(!posHoldConfig()->pos_hold_without_mag || !canUseGPSHeading)) {
|
||||
(!posHoldConfig()->posHoldWithoutMag || !canUseGPSHeading)) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
@ -105,6 +105,6 @@ bool posHoldFailure(void) {
|
|||
return FLIGHT_MODE(POS_HOLD_MODE) && (!posHold.isControlOk || !posHold.areSensorsOk);
|
||||
}
|
||||
|
||||
#endif // USE_POS_HOLD
|
||||
#endif // USE_POSITION_HOLD
|
||||
|
||||
#endif // !USE_WING
|
||||
|
|
|
@ -52,6 +52,6 @@ bool posHoldFailure(void) {
|
|||
return true;
|
||||
}
|
||||
|
||||
#endif // USE_POS_HOLD
|
||||
#endif // USE_POSITION_HOLD
|
||||
|
||||
#endif // USE_WING
|
||||
|
|
|
@ -288,7 +288,7 @@ void gimbalUpdate(timeUs_t currentTimeUs)
|
|||
if (gimbalInCount == sizeof(gimbalCmdIn.u.gimbalCmd)) {
|
||||
uint16_t crc = gimbalCrc((uint8_t *)&gimbalCmdIn, sizeof(gimbalCmdIn) - 2);
|
||||
// Only use the data if the CRC is correct
|
||||
if (gimbalCmdIn.u.crc == crc) {
|
||||
if (gimbalCmdIn.u.gimbalCmd.crc == crc) {
|
||||
gimbalCmdOut = gimbalCmdIn.u.gimbalCmd;
|
||||
gimbalSet(gimbalCmdIn.u.gimbalCmd.roll, gimbalCmdIn.u.gimbalCmd.pitch, gimbalCmdIn.u.gimbalCmd.yaw);
|
||||
serialWriteBuf(gimbalSerialPort, (uint8_t *)&gimbalCmdOut, sizeof(gimbalCmdOut));
|
||||
|
|
1299
src/main/io/gps.c
1299
src/main/io/gps.c
File diff suppressed because it is too large
Load diff
|
@ -36,7 +36,7 @@
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/motor.h"
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
@ -143,23 +143,23 @@ inline void setEscOutput(uint8_t selEsc)
|
|||
|
||||
uint8_t esc4wayInit(void)
|
||||
{
|
||||
// StopPwmAllMotors();
|
||||
// XXX Review effect of motor refactor
|
||||
//pwmDisableMotors();
|
||||
escCount = 0;
|
||||
motorShutdown();
|
||||
uint8_t escIndex = 0;
|
||||
|
||||
memset(&escHardware, 0, sizeof(escHardware));
|
||||
pwmOutputPort_t *pwmMotors = pwmGetMotors();
|
||||
for (volatile uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
if (pwmMotors[i].enabled) {
|
||||
if (pwmMotors[i].io != IO_NONE) {
|
||||
escHardware[escCount].io = pwmMotors[i].io;
|
||||
setEscInput(escCount);
|
||||
setEscHi(escCount);
|
||||
escCount++;
|
||||
if (motorIsMotorEnabled(i)) {
|
||||
const IO_t io = motorGetIo(i);
|
||||
if (io != IO_NONE) {
|
||||
escHardware[escIndex].io = io;
|
||||
setEscInput(escIndex);
|
||||
setEscHi(escIndex);
|
||||
escIndex++;
|
||||
}
|
||||
}
|
||||
}
|
||||
motorDisable();
|
||||
escCount = escIndex;
|
||||
return escCount;
|
||||
}
|
||||
|
||||
|
|
|
@ -1092,7 +1092,7 @@ static bool mspProcessOutCommand(mspDescriptor_t srcDesc, int16_t cmdMSP, sbuf_t
|
|||
#else
|
||||
sbufWriteU16(dst, 0);
|
||||
#endif
|
||||
sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_RANGEFINDER) << 4 | sensors(SENSOR_GYRO) << 5);
|
||||
sbufWriteU16(dst, sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_RANGEFINDER) << 4 | sensors(SENSOR_GYRO) << 5 | sensors(SENSOR_OPTICALFLOW) << 6);
|
||||
sbufWriteData(dst, &flightModeFlags, 4); // unconditional part of flags, first 32 bits
|
||||
sbufWriteU8(dst, getCurrentPidProfileIndex());
|
||||
sbufWriteU16(dst, constrain(getAverageSystemLoadPercent(), 0, LOAD_PERCENTAGE_ONE));
|
||||
|
@ -1128,6 +1128,7 @@ static bool mspProcessOutCommand(mspDescriptor_t srcDesc, int16_t cmdMSP, sbuf_t
|
|||
#else
|
||||
sbufWriteU16(dst, 0);
|
||||
#endif
|
||||
sbufWriteU8(dst, CONTROL_RATE_PROFILE_COUNT);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1529,9 +1530,9 @@ case MSP_NAME:
|
|||
sbufWriteU16(dst, gpsRescueConfig()->returnAltitudeM);
|
||||
sbufWriteU16(dst, gpsRescueConfig()->descentDistanceM);
|
||||
sbufWriteU16(dst, gpsRescueConfig()->groundSpeedCmS);
|
||||
sbufWriteU16(dst, apConfig()->throttle_min);
|
||||
sbufWriteU16(dst, apConfig()->throttle_max);
|
||||
sbufWriteU16(dst, apConfig()->hover_throttle);
|
||||
sbufWriteU16(dst, autopilotConfig()->throttleMin);
|
||||
sbufWriteU16(dst, autopilotConfig()->throttleMax);
|
||||
sbufWriteU16(dst, autopilotConfig()->hoverThrottle);
|
||||
sbufWriteU8(dst, gpsRescueConfig()->sanityChecks);
|
||||
sbufWriteU8(dst, gpsRescueConfig()->minSats);
|
||||
|
||||
|
@ -1547,9 +1548,9 @@ case MSP_NAME:
|
|||
break;
|
||||
|
||||
case MSP_GPS_RESCUE_PIDS:
|
||||
sbufWriteU16(dst, apConfig()->altitude_P);
|
||||
sbufWriteU16(dst, apConfig()->altitude_I);
|
||||
sbufWriteU16(dst, apConfig()->altitude_D);
|
||||
sbufWriteU16(dst, autopilotConfig()->altitudeP);
|
||||
sbufWriteU16(dst, autopilotConfig()->altitudeI);
|
||||
sbufWriteU16(dst, autopilotConfig()->altitudeD);
|
||||
// altitude_F not implemented yet
|
||||
sbufWriteU16(dst, gpsRescueConfig()->velP);
|
||||
sbufWriteU16(dst, gpsRescueConfig()->velI);
|
||||
|
@ -1796,7 +1797,7 @@ case MSP_NAME:
|
|||
sbufWriteU8(dst, rcControlsConfig()->deadband);
|
||||
sbufWriteU8(dst, rcControlsConfig()->yaw_deadband);
|
||||
#if defined(USE_POSITION_HOLD) && !defined(USE_WING)
|
||||
sbufWriteU8(dst, posHoldConfig()->pos_hold_deadband);
|
||||
sbufWriteU8(dst, posHoldConfig()->deadband);
|
||||
#else
|
||||
sbufWriteU8(dst, 0);
|
||||
#endif
|
||||
|
@ -2131,7 +2132,7 @@ case MSP_NAME:
|
|||
#else
|
||||
sbufWriteU8(dst, SENSOR_NOT_AVAILABLE);
|
||||
#endif
|
||||
#ifdef USE_OPTICAL_FLOW
|
||||
#ifdef USE_OPTICALFLOW
|
||||
sbufWriteU8(dst, detectedSensors[SENSOR_INDEX_OPTICALFLOW]);
|
||||
#else
|
||||
sbufWriteU8(dst, SENSOR_NOT_AVAILABLE);
|
||||
|
@ -2900,9 +2901,9 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
|||
gpsRescueConfigMutable()->returnAltitudeM = sbufReadU16(src);
|
||||
gpsRescueConfigMutable()->descentDistanceM = sbufReadU16(src);
|
||||
gpsRescueConfigMutable()->groundSpeedCmS = sbufReadU16(src);
|
||||
apConfigMutable()->throttle_min = sbufReadU16(src);
|
||||
apConfigMutable()->throttle_max = sbufReadU16(src);
|
||||
apConfigMutable()->hover_throttle = sbufReadU16(src);
|
||||
autopilotConfigMutable()->throttleMin = sbufReadU16(src);
|
||||
autopilotConfigMutable()->throttleMax = sbufReadU16(src);
|
||||
autopilotConfigMutable()->hoverThrottle = sbufReadU16(src);
|
||||
gpsRescueConfigMutable()->sanityChecks = sbufReadU8(src);
|
||||
gpsRescueConfigMutable()->minSats = sbufReadU8(src);
|
||||
if (sbufBytesRemaining(src) >= 6) {
|
||||
|
@ -2923,9 +2924,9 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
|||
break;
|
||||
|
||||
case MSP_SET_GPS_RESCUE_PIDS:
|
||||
apConfigMutable()->altitude_P = sbufReadU16(src);
|
||||
apConfigMutable()->altitude_I = sbufReadU16(src);
|
||||
apConfigMutable()->altitude_D = sbufReadU16(src);
|
||||
autopilotConfigMutable()->altitudeP = sbufReadU16(src);
|
||||
autopilotConfigMutable()->altitudeI = sbufReadU16(src);
|
||||
autopilotConfigMutable()->altitudeD = sbufReadU16(src);
|
||||
// altitude_F not included in msp yet
|
||||
gpsRescueConfigMutable()->velP = sbufReadU16(src);
|
||||
gpsRescueConfigMutable()->velI = sbufReadU16(src);
|
||||
|
@ -2989,7 +2990,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
|||
rcControlsConfigMutable()->deadband = sbufReadU8(src);
|
||||
rcControlsConfigMutable()->yaw_deadband = sbufReadU8(src);
|
||||
#if defined(USE_POSITION_HOLD) && !defined(USE_WING)
|
||||
posHoldConfigMutable()->pos_hold_deadband = sbufReadU8(src);
|
||||
posHoldConfigMutable()->deadband = sbufReadU8(src);
|
||||
#else
|
||||
sbufReadU8(src);
|
||||
#endif
|
||||
|
@ -3350,18 +3351,23 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
|||
sbufReadU8(src);
|
||||
#endif
|
||||
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
#ifdef USE_RANGEFINDER
|
||||
rangefinderConfigMutable()->rangefinder_hardware = sbufReadU8(src);
|
||||
rangefinderConfigMutable()->rangefinder_hardware = sbufReadU8(src);
|
||||
#else
|
||||
sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
#endif
|
||||
}
|
||||
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
#ifdef USE_OPTICALFLOW
|
||||
opticalflowConfigMutable()->opticalflow_hardware = sbufReadU8(src);
|
||||
opticalflowConfigMutable()->opticalflow_hardware = sbufReadU8(src);
|
||||
#else
|
||||
sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
|
||||
#ifdef USE_ACC
|
||||
case MSP_ACC_CALIBRATION:
|
||||
if (!ARMING_FLAG(ARMED))
|
||||
|
@ -4147,7 +4153,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
|||
}
|
||||
|
||||
const unsigned textLength = MIN(textSpace, sbufReadU8(src));
|
||||
memset(textVar, 0, strlen(textVar));
|
||||
textVar[textLength] = '\0';
|
||||
sbufReadData(src, textVar, textLength);
|
||||
|
||||
#ifdef USE_OSD
|
||||
|
|
|
@ -27,7 +27,9 @@
|
|||
#include "msp/msp.h"
|
||||
|
||||
// Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 3 MSP ports.
|
||||
#ifndef MAX_MSP_PORT_COUNT
|
||||
#define MAX_MSP_PORT_COUNT 3
|
||||
#endif
|
||||
|
||||
typedef enum {
|
||||
PORT_IDLE,
|
||||
|
|
|
@ -35,8 +35,8 @@
|
|||
PG_REGISTER_WITH_RESET_TEMPLATE(altHoldConfig_t, altHoldConfig, PG_ALTHOLD_CONFIG, 4);
|
||||
|
||||
PG_RESET_TEMPLATE(altHoldConfig_t, altHoldConfig,
|
||||
.alt_hold_adjust_rate = 50, // max vertical velocity change at full/zero throttle. 50 means 5 m/s
|
||||
.alt_hold_deadband = 20, // throttle deadband in percent of stick travel
|
||||
.climbRate = 50, // max vertical velocity change at full/zero throttle. 50 means 5 m/s
|
||||
.deadband = 20, // throttle deadband in percent of stick travel
|
||||
);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -28,8 +28,8 @@
|
|||
#include "pg/pg.h"
|
||||
|
||||
typedef struct altHoldConfig_s {
|
||||
uint8_t alt_hold_adjust_rate;
|
||||
uint8_t alt_hold_deadband;
|
||||
uint8_t climbRate;
|
||||
uint8_t deadband;
|
||||
} altHoldConfig_t;
|
||||
|
||||
PG_DECLARE(altHoldConfig_t, altHoldConfig);
|
||||
|
|
|
@ -30,23 +30,23 @@
|
|||
|
||||
#include "autopilot.h"
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(apConfig_t, apConfig, PG_AUTOPILOT, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(autopilotConfig_t, autopilotConfig, PG_AUTOPILOT, 2);
|
||||
|
||||
PG_RESET_TEMPLATE(apConfig_t, apConfig,
|
||||
.landing_altitude_m = 4,
|
||||
.hover_throttle = 1275,
|
||||
.throttle_min = 1100,
|
||||
.throttle_max = 1700,
|
||||
.altitude_P = 15,
|
||||
.altitude_I = 15,
|
||||
.altitude_D = 15,
|
||||
.altitude_F = 15,
|
||||
.position_P = 30,
|
||||
.position_I = 30,
|
||||
.position_D = 30,
|
||||
.position_A = 30,
|
||||
.position_cutoff = 80,
|
||||
.max_angle = 50,
|
||||
PG_RESET_TEMPLATE(autopilotConfig_t, autopilotConfig,
|
||||
.landingAltitudeM = 4,
|
||||
.hoverThrottle = 1275,
|
||||
.throttleMin = 1100,
|
||||
.throttleMax = 1700,
|
||||
.altitudeP = 15,
|
||||
.altitudeI = 15,
|
||||
.altitudeD = 15,
|
||||
.altitudeF = 15,
|
||||
.positionP = 30,
|
||||
.positionI = 30,
|
||||
.positionD = 30,
|
||||
.positionA = 30,
|
||||
.positionCutoff = 80,
|
||||
.maxAngle = 50,
|
||||
);
|
||||
|
||||
#endif // !USE_WING
|
||||
|
|
|
@ -27,23 +27,23 @@
|
|||
|
||||
#include "pg/pg.h"
|
||||
|
||||
typedef struct apConfig_s {
|
||||
uint8_t landing_altitude_m; // altitude below which landing behaviours can change, metres
|
||||
uint16_t hover_throttle; // value used at the start of a rescue or position hold
|
||||
uint16_t throttle_min;
|
||||
uint16_t throttle_max;
|
||||
uint8_t altitude_P;
|
||||
uint8_t altitude_I;
|
||||
uint8_t altitude_D;
|
||||
uint8_t altitude_F;
|
||||
uint8_t position_P;
|
||||
uint8_t position_I;
|
||||
uint8_t position_D;
|
||||
uint8_t position_A;
|
||||
uint8_t position_cutoff;
|
||||
uint8_t max_angle;
|
||||
} apConfig_t;
|
||||
typedef struct autopilotConfig_s {
|
||||
uint8_t landingAltitudeM; // altitude below which landing behaviours can change, metres
|
||||
uint16_t hoverThrottle; // value used at the start of a rescue or position hold
|
||||
uint16_t throttleMin;
|
||||
uint16_t throttleMax;
|
||||
uint8_t altitudeP;
|
||||
uint8_t altitudeI;
|
||||
uint8_t altitudeD;
|
||||
uint8_t altitudeF;
|
||||
uint8_t positionP;
|
||||
uint8_t positionI;
|
||||
uint8_t positionD;
|
||||
uint8_t positionA;
|
||||
uint8_t positionCutoff;
|
||||
uint8_t maxAngle;
|
||||
} autopilotConfig_t;
|
||||
|
||||
PG_DECLARE(apConfig_t, apConfig);
|
||||
PG_DECLARE(autopilotConfig_t, autopilotConfig);
|
||||
|
||||
#endif // !USE_WING
|
||||
|
|
|
@ -30,9 +30,9 @@
|
|||
|
||||
#include "autopilot.h"
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(apConfig_t, apConfig, PG_AUTOPILOT, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(autopilotConfig_t, autopilotConfig, PG_AUTOPILOT, 2);
|
||||
|
||||
PG_RESET_TEMPLATE(apConfig_t, apConfig,
|
||||
PG_RESET_TEMPLATE(autopilotConfig_t, autopilotConfig,
|
||||
);
|
||||
|
||||
#endif // USE_WING
|
||||
|
|
|
@ -27,10 +27,10 @@
|
|||
|
||||
#include "pg/pg.h"
|
||||
|
||||
typedef struct apConfig_s {
|
||||
typedef struct autopilotConfig_s {
|
||||
uint8_t dummy;
|
||||
} apConfig_t;
|
||||
} autopilotConfig_t;
|
||||
|
||||
PG_DECLARE(apConfig_t, apConfig);
|
||||
PG_DECLARE(autopilotConfig_t, autopilotConfig);
|
||||
|
||||
#endif // USE_WING
|
||||
|
|
|
@ -41,7 +41,7 @@ PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
|
|||
.autoConfig = GPS_AUTOCONFIG_ON,
|
||||
.autoBaud = GPS_AUTOBAUD_OFF,
|
||||
.gps_ublox_acquire_model = UBLOX_MODEL_STATIONARY,
|
||||
.gps_ublox_flight_model = UBLOX_MODEL_AIRBORNE_4G,
|
||||
.gps_ublox_flight_model = UBLOX_MODEL_AIRBORNE_1G,
|
||||
.gps_update_rate_hz = 10,
|
||||
.gps_ublox_use_galileo = false,
|
||||
.gps_set_home_point_once = false,
|
||||
|
|
|
@ -159,7 +159,6 @@
|
|||
//#define PG_SOFTSERIAL_PIN_CONFIG 558 // removed, merged into SERIAL_PIN_CONFIG
|
||||
#define PG_GIMBAL_TRACK_CONFIG 559
|
||||
#define PG_OPTICALFLOW_CONFIG 560
|
||||
#define PG_BETAFLIGHT_END 560
|
||||
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
|
|
|
@ -35,8 +35,8 @@
|
|||
PG_REGISTER_WITH_RESET_TEMPLATE(posHoldConfig_t, posHoldConfig, PG_POSHOLD_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(posHoldConfig_t, posHoldConfig,
|
||||
.pos_hold_without_mag = false, // position hold within this percentage stick deflection
|
||||
.pos_hold_deadband = 5, // deadband in percent of stick travel for roll and pitch. Must be non-zero, and exceeded, for target location to be changed with sticks
|
||||
.posHoldWithoutMag = false, // position hold within this percentage stick deflection
|
||||
.deadband = 5, // deadband in percent of stick travel for roll and pitch. Must be non-zero, and exceeded, for target location to be changed with sticks
|
||||
);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -28,8 +28,8 @@
|
|||
#include "pg/pg.h"
|
||||
|
||||
typedef struct posHoldConfig_s {
|
||||
bool pos_hold_without_mag;
|
||||
uint8_t pos_hold_deadband;
|
||||
bool posHoldWithoutMag;
|
||||
uint8_t deadband;
|
||||
} posHoldConfig_t;
|
||||
|
||||
PG_DECLARE(posHoldConfig_t, posHoldConfig);
|
||||
|
|
|
@ -167,11 +167,11 @@ retry:
|
|||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#if defined(USE_ACC_MPU6500) || defined(USE_ACC_SPI_MPU6500)
|
||||
case ACC_MPU6500:
|
||||
case ACC_ICM20601:
|
||||
case ACC_ICM20602:
|
||||
case ACC_ICM20608G:
|
||||
#if defined(USE_ACC_MPU6500) || defined(USE_ACC_SPI_MPU6500)
|
||||
#ifdef USE_ACC_SPI_MPU6500
|
||||
if (mpu6500SpiAccDetect(dev)) {
|
||||
#else
|
||||
|
@ -195,8 +195,8 @@ retry:
|
|||
}
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#ifdef USE_ACC_SPI_ICM20649
|
||||
case ACC_ICM20649:
|
||||
|
@ -287,6 +287,7 @@ retry:
|
|||
|
||||
default:
|
||||
case ACC_NONE: // disable ACC
|
||||
UNUSED(dev);
|
||||
accHardware = ACC_NONE;
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -500,6 +500,7 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
|
|||
#endif
|
||||
|
||||
default:
|
||||
UNUSED(dev);
|
||||
gyroHardware = GYRO_NONE;
|
||||
}
|
||||
|
||||
|
|
|
@ -68,8 +68,8 @@ PG_REGISTER_WITH_RESET_TEMPLATE(opticalflowConfig_t, opticalflowConfig, PG_OPTIC
|
|||
PG_RESET_TEMPLATE(opticalflowConfig_t, opticalflowConfig,
|
||||
.opticalflow_hardware = OPTICALFLOW_NONE,
|
||||
.rotation = 0,
|
||||
.flow_lpf = 0,
|
||||
.flip_x = 0
|
||||
.flip_x = 0,
|
||||
.flow_lpf = 0
|
||||
);
|
||||
|
||||
static opticalflow_t opticalflow;
|
||||
|
|
|
@ -301,7 +301,9 @@
|
|||
#define USE_HUFFMAN
|
||||
|
||||
#define PID_PROFILE_COUNT 4
|
||||
#define CONTROL_RATE_PROFILE_COUNT 4
|
||||
#ifndef CONTROL_RATE_PROFILE_COUNT
|
||||
#define CONTROL_RATE_PROFILE_COUNT 4 // or maybe 6
|
||||
#endif
|
||||
|
||||
#define USE_CLI_BATCH
|
||||
#define USE_RESOURCE_MGMT
|
||||
|
|
|
@ -685,6 +685,7 @@ static motorVTable_t bbVTable = {
|
|||
.shutdown = bbShutdown,
|
||||
.isMotorIdle = bbDshotIsMotorIdle,
|
||||
.requestTelemetry = bbDshotRequestTelemetry,
|
||||
.getMotorIO = bbGetMotorIO,
|
||||
};
|
||||
|
||||
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||
|
|
|
@ -24,6 +24,12 @@
|
|||
#include "platform.h"
|
||||
#include "drivers/resource.h"
|
||||
|
||||
#if defined(APM32F4)
|
||||
#define PLATFORM_TRAIT_DMA_STREAM_REQUIRED 1
|
||||
#endif
|
||||
|
||||
#define DMA_ARCH_TYPE DMA_Stream_TypeDef
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA1_ST0_HANDLER = 1,
|
||||
|
@ -88,3 +94,17 @@ typedef enum {
|
|||
#define DMA_IT_FEIF ((uint32_t)0x00000001)
|
||||
|
||||
void dmaMuxEnable(dmaIdentifier_e identifier, uint32_t dmaMuxId);
|
||||
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->SCFG & DMA_SCFGx_EN)
|
||||
#define REG_NDTR NDATA
|
||||
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
// We actually need these LL case only
|
||||
#define xLL_EX_DMA_DeInit(dmaResource) LL_EX_DMA_DeInit((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_Init(dmaResource, initstruct) LL_EX_DMA_Init((DMA_ARCH_TYPE *)(dmaResource), initstruct)
|
||||
#define xLL_EX_DMA_DisableResource(dmaResource) LL_EX_DMA_DisableResource((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_EnableResource(dmaResource) LL_EX_DMA_EnableResource((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_GetDataLength(dmaResource) LL_EX_DMA_GetDataLength((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_SetDataLength(dmaResource, length) LL_EX_DMA_SetDataLength((DMA_ARCH_TYPE *)(dmaResource), length)
|
||||
#define xLL_EX_DMA_EnableIT_TC(dmaResource) LL_EX_DMA_EnableIT_TC((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#endif
|
|
@ -111,8 +111,9 @@ DEVICE_STDPERIPH_SRC := \
|
|||
VPATH := $(VPATH):$(LIB_MAIN_DIR)/APM32F4/Libraries/Device/Geehy/APM32F4xx
|
||||
|
||||
INCLUDE_DIRS += \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(PLATFORM_DIR)/common/stm32 \
|
||||
$(STDPERIPH_DIR)/Include \
|
||||
$(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \
|
||||
|
|
|
@ -31,6 +31,7 @@
|
|||
#include "drivers/io.h"
|
||||
#include "drivers/motor.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_output_impl.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
|
@ -89,15 +90,15 @@ static bool useContinuousUpdate = true;
|
|||
static void pwmWriteStandard(uint8_t index, float value)
|
||||
{
|
||||
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */
|
||||
*motors[index].channel.ccr = lrintf((value * motors[index].pulseScale) + motors[index].pulseOffset);
|
||||
*pwmMotors[index].channel.ccr = lrintf((value * pwmMotors[index].pulseScale) + pwmMotors[index].pulseOffset);
|
||||
}
|
||||
|
||||
static void pwmShutdownPulsesForAllMotors(void)
|
||||
{
|
||||
for (int index = 0; index < pwmMotorCount; index++) {
|
||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
||||
if (motors[index].channel.ccr) {
|
||||
*motors[index].channel.ccr = 0;
|
||||
if (pwmMotors[index].channel.ccr) {
|
||||
*pwmMotors[index].channel.ccr = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -108,16 +109,6 @@ static void pwmDisableMotors(void)
|
|||
}
|
||||
|
||||
static motorVTable_t motorPwmVTable;
|
||||
static bool pwmEnableMotors(void)
|
||||
{
|
||||
/* check motors can be enabled */
|
||||
return pwmMotorCount > 0;
|
||||
}
|
||||
|
||||
static bool pwmIsMotorEnabled(unsigned index)
|
||||
{
|
||||
return motors[index].enabled;
|
||||
}
|
||||
|
||||
static void pwmCompleteMotorUpdate(void)
|
||||
{
|
||||
|
@ -126,12 +117,12 @@ static void pwmCompleteMotorUpdate(void)
|
|||
}
|
||||
|
||||
for (int index = 0; index < pwmMotorCount; index++) {
|
||||
if (motors[index].forceOverflow) {
|
||||
timerForceOverflow(motors[index].channel.tim);
|
||||
if (pwmMotors[index].forceOverflow) {
|
||||
timerForceOverflow(pwmMotors[index].channel.tim);
|
||||
}
|
||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again.
|
||||
// This compare register will be set to the output value on the next main loop.
|
||||
*motors[index].channel.ccr = 0;
|
||||
*pwmMotors[index].channel.ccr = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -158,11 +149,12 @@ static motorVTable_t motorPwmVTable = {
|
|||
.updateComplete = pwmCompleteMotorUpdate,
|
||||
.requestTelemetry = NULL,
|
||||
.isMotorIdle = NULL,
|
||||
.getMotorIO = pwmGetMotorIO,
|
||||
};
|
||||
|
||||
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
||||
{
|
||||
memset(motors, 0, sizeof(motors));
|
||||
memset(pwmMotors, 0, sizeof(pwmMotors));
|
||||
|
||||
if (!device || !motorConfig) {
|
||||
return false;
|
||||
|
@ -214,10 +206,10 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
return false;
|
||||
}
|
||||
|
||||
motors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(pwmMotors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
|
||||
IOConfigGPIOAF(motors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
IOConfigGPIOAF(pwmMotors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
|
||||
/* standard PWM outputs */
|
||||
// margin of safety is 4 periods when unsynced
|
||||
|
@ -234,20 +226,20 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
TODO: this can be moved back to periodMin and periodLen
|
||||
once mixer outputs a 0..1 float value.
|
||||
*/
|
||||
motors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||
motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000);
|
||||
pwmMotors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||
pwmMotors[motorIndex].pulseOffset = (sMin * hz) - (pwmMotors[motorIndex].pulseScale * 1000);
|
||||
|
||||
pwmOutConfig(&motors[motorIndex].channel, timerHardware, hz, period, idlePulse, motorConfig->motorInversion);
|
||||
pwmOutConfig(&pwmMotors[motorIndex].channel, timerHardware, hz, period, idlePulse, motorConfig->motorInversion);
|
||||
|
||||
bool timerAlreadyUsed = false;
|
||||
for (int i = 0; i < motorIndex; i++) {
|
||||
if (motors[i].channel.tim == motors[motorIndex].channel.tim) {
|
||||
if (pwmMotors[i].channel.tim == pwmMotors[motorIndex].channel.tim) {
|
||||
timerAlreadyUsed = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||
motors[motorIndex].enabled = true;
|
||||
pwmMotors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||
pwmMotors[motorIndex].enabled = true;
|
||||
}
|
||||
|
||||
return true;
|
||||
|
@ -255,7 +247,7 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
|
||||
pwmOutputPort_t *pwmGetMotors(void)
|
||||
{
|
||||
return motors;
|
||||
return pwmMotors;
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
|
|
|
@ -330,8 +330,9 @@ static void timerNVICConfigure(uint8_t irq)
|
|||
TMR_HandleTypeDef* timerFindTimerHandle(TMR_TypeDef *tim)
|
||||
{
|
||||
uint8_t timerIndex = lookupTimerIndex(tim);
|
||||
if (timerIndex >= USED_TIMER_COUNT)
|
||||
if (timerIndex >= USED_TIMER_COUNT) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
return &timerHandle[timerIndex].Handle;
|
||||
}
|
||||
|
@ -1196,4 +1197,43 @@ DAL_StatusTypeDef DMA_SetCurrDataCounter(TMR_HandleTypeDef *htim, uint32_t Chann
|
|||
/* Return function status */
|
||||
return DAL_OK;
|
||||
}
|
||||
|
||||
void timerReset(TIM_TypeDef *timer)
|
||||
{
|
||||
DDL_TMR_DeInit(timer);
|
||||
}
|
||||
|
||||
void timerSetPeriod(TIM_TypeDef *timer, uint32_t period)
|
||||
{
|
||||
timer->AUTORLD = period;
|
||||
}
|
||||
|
||||
uint32_t timerGetPeriod(TIM_TypeDef *timer)
|
||||
{
|
||||
return timer->AUTORLD;
|
||||
}
|
||||
|
||||
void timerSetCounter(TIM_TypeDef *timer, uint32_t counter)
|
||||
{
|
||||
timer->CNT = counter;
|
||||
}
|
||||
|
||||
void timerDisable(TIM_TypeDef *timer)
|
||||
{
|
||||
DDL_TMR_DisableIT_UPDATE(timer);
|
||||
DDL_TMR_DisableCounter(timer);
|
||||
}
|
||||
|
||||
void timerEnable(TIM_TypeDef *timer)
|
||||
{
|
||||
DDL_TMR_EnableCounter(timer);
|
||||
DDL_TMR_GenerateEvent_UPDATE(timer);
|
||||
}
|
||||
|
||||
void timerEnableInterrupt(TIM_TypeDef *timer)
|
||||
{
|
||||
DDL_TMR_ClearFlag_UPDATE(timer);
|
||||
DDL_TMR_EnableIT_UPDATE(timer);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -583,7 +583,7 @@ static void bbUpdateComplete(void)
|
|||
}
|
||||
|
||||
#ifdef USE_DSHOT_CACHE_MGMT
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||
// Only clean each buffer once. If all motors are on a common port they'll share a buffer.
|
||||
bool clean = false;
|
||||
for (int i = 0; i < motorIndex; i++) {
|
||||
|
@ -677,6 +677,7 @@ static motorVTable_t bbVTable = {
|
|||
.shutdown = bbShutdown,
|
||||
.isMotorIdle = bbDshotIsMotorIdle,
|
||||
.requestTelemetry = bbDshotRequestTelemetry,
|
||||
.getMotorIO = bbGetMotorIO,
|
||||
};
|
||||
|
||||
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||
|
|
|
@ -24,6 +24,12 @@
|
|||
#include "platform.h"
|
||||
#include "drivers/resource.h"
|
||||
|
||||
#if defined(USE_ATBSP_DRIVER)
|
||||
#define PLATFORM_TRAIT_DMA_MUX_REQUIRED 1
|
||||
#endif
|
||||
|
||||
#define DMA_ARCH_TYPE dma_channel_type
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA1_CH1_HANDLER = 1,
|
||||
|
@ -90,3 +96,6 @@ void dmaMuxEnable(dmaIdentifier_e identifier, uint32_t dmaMuxId);
|
|||
#define xDMA_SetCurrDataCounter(dmaResource, count) dma_data_number_set((DMA_ARCH_TYPE *)(dmaResource), count)
|
||||
#define xDMA_GetFlagStatus(dmaResource, flags) dma_flag_get((DMA_ARCH_TYPE *)(dmaResource), flags)
|
||||
#define xDMA_ClearFlag(dmaResource, flags) dma_flag_clear((DMA_ARCH_TYPE *)(dmaResource), flags)
|
||||
|
||||
#define DMA_CCR_EN 1
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->ctrl_bit.chen & DMA_CCR_EN)
|
|
@ -122,16 +122,6 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
|||
return;
|
||||
}
|
||||
|
||||
const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||
RCC_ClockCmd(rcc, ENABLE);
|
||||
|
||||
gpio_init_type init = {
|
||||
.gpio_pins = IO_Pin(io),
|
||||
.gpio_mode = (cfg >> 0) & 0x03,
|
||||
.gpio_drive_strength = (cfg >> 2) & 0x03,
|
||||
.gpio_out_type = (cfg >> 4) & 0x01,
|
||||
.gpio_pull = (cfg >> 5) & 0x03,
|
||||
};
|
||||
gpio_init(IO_GPIO(io), &init);
|
||||
IOConfigGPIO(io, cfg);
|
||||
gpio_pin_mux_config(IO_GPIO(io), IO_GPIO_PinSource(io), af);
|
||||
}
|
||||
|
|
|
@ -61,8 +61,9 @@ VCP_INCLUDES = \
|
|||
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
|
||||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(PLATFORM_DIR)/common/stm32 \
|
||||
$(STDPERIPH_DIR)/inc \
|
||||
$(CMSIS_DIR)/cm4/core_support \
|
||||
|
|
|
@ -31,6 +31,7 @@
|
|||
#include "drivers/io.h"
|
||||
#include "drivers/motor_impl.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_output_impl.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
|
@ -80,15 +81,15 @@ static FAST_DATA_ZERO_INIT motorDevice_t *pwmMotorDevice;
|
|||
static void pwmWriteStandard(uint8_t index, float value)
|
||||
{
|
||||
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */
|
||||
*motors[index].channel.ccr = lrintf((value * motors[index].pulseScale) + motors[index].pulseOffset);
|
||||
*pwmMotors[index].channel.ccr = lrintf((value * pwmMotors[index].pulseScale) + pwmMotors[index].pulseOffset);
|
||||
}
|
||||
|
||||
static void pwmShutdownPulsesForAllMotors(void)
|
||||
{
|
||||
for (int index = 0; index < pwmMotorCount; index++) {
|
||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
||||
if (motors[index].channel.ccr) {
|
||||
*motors[index].channel.ccr = 0;
|
||||
if (pwmMotors[index].channel.ccr) {
|
||||
*pwmMotors[index].channel.ccr = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -98,18 +99,6 @@ static void pwmDisableMotors(void)
|
|||
pwmShutdownPulsesForAllMotors();
|
||||
}
|
||||
|
||||
static motorVTable_t motorPwmVTable;
|
||||
static bool pwmEnableMotors(void)
|
||||
{
|
||||
/* check motors can be enabled */
|
||||
return (pwmMotorDevice->vTable);
|
||||
}
|
||||
|
||||
static bool pwmIsMotorEnabled(unsigned index)
|
||||
{
|
||||
return motors[index].enabled;
|
||||
}
|
||||
|
||||
static bool useContinuousUpdate = true;
|
||||
|
||||
static void pwmCompleteMotorUpdate(void)
|
||||
|
@ -119,12 +108,12 @@ static void pwmCompleteMotorUpdate(void)
|
|||
}
|
||||
|
||||
for (int index = 0; index < pwmMotorCount; index++) {
|
||||
if (motors[index].forceOverflow) {
|
||||
timerForceOverflow(motors[index].channel.tim);
|
||||
if (pwmMotors[index].forceOverflow) {
|
||||
timerForceOverflow(pwmMotors[index].channel.tim);
|
||||
}
|
||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again.
|
||||
// This compare register will be set to the output value on the next main loop.
|
||||
*motors[index].channel.ccr = 0;
|
||||
*pwmMotors[index].channel.ccr = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -151,11 +140,12 @@ static motorVTable_t motorPwmVTable = {
|
|||
.updateComplete = pwmCompleteMotorUpdate,
|
||||
.requestTelemetry = NULL,
|
||||
.isMotorIdle = NULL,
|
||||
.getMotorIO = pwmGetMotorIO,
|
||||
};
|
||||
|
||||
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
||||
{
|
||||
memset(motors, 0, sizeof(motors));
|
||||
memset(pwmMotors, 0, sizeof(pwmMotors));
|
||||
|
||||
if (!device) {
|
||||
return false;
|
||||
|
@ -208,10 +198,10 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
return false;
|
||||
}
|
||||
|
||||
motors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(pwmMotors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
|
||||
IOConfigGPIOAF(motors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
IOConfigGPIOAF(pwmMotors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
|
||||
/* standard PWM outputs */
|
||||
// margin of safety is 4 periods when unsynced
|
||||
|
@ -228,27 +218,27 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
TODO: this can be moved back to periodMin and periodLen
|
||||
once mixer outputs a 0..1 float value.
|
||||
*/
|
||||
motors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||
motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000);
|
||||
pwmMotors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||
pwmMotors[motorIndex].pulseOffset = (sMin * hz) - (pwmMotors[motorIndex].pulseScale * 1000);
|
||||
|
||||
pwmOutConfig(&motors[motorIndex].channel, timerHardware, hz, period, idlePulse, motorConfig->motorInversion);
|
||||
pwmOutConfig(&pwmMotors[motorIndex].channel, timerHardware, hz, period, idlePulse, motorConfig->motorInversion);
|
||||
|
||||
bool timerAlreadyUsed = false;
|
||||
for (int i = 0; i < motorIndex; i++) {
|
||||
if (motors[i].channel.tim == motors[motorIndex].channel.tim) {
|
||||
if (pwmMotors[i].channel.tim == pwmMotors[motorIndex].channel.tim) {
|
||||
timerAlreadyUsed = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||
motors[motorIndex].enabled = true;
|
||||
pwmMotors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||
pwmMotors[motorIndex].enabled = true;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
pwmOutputPort_t *pwmGetMotors(void)
|
||||
{
|
||||
return motors;
|
||||
return pwmMotors;
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
|
|
|
@ -60,6 +60,7 @@
|
|||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define USE_SPI_DEVICE_4
|
||||
#define USE_SPI_DMA_ENABLE_LATE
|
||||
|
||||
#define USE_EXTI
|
||||
|
@ -96,5 +97,6 @@
|
|||
#undef USE_RX_EXPRESSLRS
|
||||
// #undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#undef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
#define USE_ESCSERIAL
|
||||
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x0800) // 2K sectors
|
||||
|
|
|
@ -60,6 +60,7 @@
|
|||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define USE_SPI_DEVICE_4
|
||||
#define USE_SPI_DMA_ENABLE_LATE
|
||||
|
||||
#define USE_EXTI
|
||||
|
@ -96,5 +97,6 @@
|
|||
#undef USE_RX_EXPRESSLRS
|
||||
// #undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#undef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
#define USE_ESCSERIAL
|
||||
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x1000) // 4K sectors
|
||||
|
|
|
@ -777,4 +777,50 @@ uint16_t timerGetPrescalerByDesiredHertz(tmr_type *tim, uint32_t hz)
|
|||
}
|
||||
return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
|
||||
}
|
||||
|
||||
void timerReset(tmr_type *timer)
|
||||
{
|
||||
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||
tmr_counter_enable(timer, FALSE);
|
||||
}
|
||||
}
|
||||
|
||||
void timerSetPeriod(tmr_type *timer, uint32_t period)
|
||||
{
|
||||
tmr_period_value_set(timer, period);
|
||||
}
|
||||
|
||||
uint32_t timerGetPeriod(tmr_type *timer)
|
||||
{
|
||||
return tmr_period_value_get(timer);
|
||||
}
|
||||
|
||||
void timerSetCounter(tmr_type *timer, uint32_t counter)
|
||||
{
|
||||
tmr_counter_value_set(timer, counter);
|
||||
}
|
||||
|
||||
void timerReconfigureTimeBase(tmr_type *timer, uint16_t period, uint32_t hz)
|
||||
{
|
||||
configTimeBase(timer, period, hz);
|
||||
}
|
||||
|
||||
void timerDisable(TIM_TypeDef *timer)
|
||||
{
|
||||
tmr_interrupt_enable(timer, TMR_OVF_INT, FALSE);
|
||||
tmr_counter_enable(timer, FALSE);
|
||||
}
|
||||
|
||||
void timerEnable(TIM_TypeDef *timer)
|
||||
{
|
||||
tmr_counter_enable(timer, TRUE);
|
||||
tmr_overflow_event_disable(timer, TRUE);
|
||||
}
|
||||
|
||||
void timerEnableInterrupt(TIM_TypeDef *timer)
|
||||
{
|
||||
tmr_flag_clear(timer, TMR_OVF_FLAG);
|
||||
tmr_interrupt_enable(timer, TMR_OVF_INT, TRUE);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
27
src/platform/SIMULATOR/include/platform/dma.h
Normal file
27
src/platform/SIMULATOR/include/platform/dma.h
Normal file
|
@ -0,0 +1,27 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the GNU General
|
||||
* Public License as published by the Free Software Foundation,
|
||||
* either version 3 of the License, or (at your option) any later
|
||||
* version.
|
||||
*
|
||||
* Betaflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
*
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public
|
||||
* License along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA_LAST_HANDLER = DMA_NONE
|
||||
} dmaIdentifier_e;
|
|
@ -2,6 +2,7 @@
|
|||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(LIB_MAIN_DIR)/dyad
|
||||
|
||||
MCU_COMMON_SRC := \
|
||||
|
|
|
@ -41,6 +41,7 @@
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_output_impl.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#include "drivers/timer.h"
|
||||
|
@ -543,11 +544,9 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
|
|||
}
|
||||
}
|
||||
|
||||
static motorDevice_t pwmMotorDevice; // Forward
|
||||
|
||||
pwmOutputPort_t *pwmGetMotors(void)
|
||||
{
|
||||
return motors;
|
||||
return pwmMotors;
|
||||
}
|
||||
|
||||
static float pwmConvertFromExternal(uint16_t externalValue)
|
||||
|
@ -562,14 +561,7 @@ static uint16_t pwmConvertToExternal(float motorValue)
|
|||
|
||||
static void pwmDisableMotors(void)
|
||||
{
|
||||
pwmMotorDevice.enabled = false;
|
||||
}
|
||||
|
||||
static bool pwmEnableMotors(void)
|
||||
{
|
||||
pwmMotorDevice.enabled = true;
|
||||
|
||||
return true;
|
||||
// NOOP
|
||||
}
|
||||
|
||||
static void pwmWriteMotor(uint8_t index, float value)
|
||||
|
@ -594,12 +586,7 @@ static void pwmWriteMotorInt(uint8_t index, uint16_t value)
|
|||
|
||||
static void pwmShutdownPulsesForAllMotors(void)
|
||||
{
|
||||
pwmMotorDevice.enabled = false;
|
||||
}
|
||||
|
||||
static bool pwmIsMotorEnabled(unsigned index)
|
||||
{
|
||||
return motors[index].enabled;
|
||||
// NOOP
|
||||
}
|
||||
|
||||
static void pwmCompleteMotorUpdate(void)
|
||||
|
@ -647,7 +634,7 @@ static const motorVTable_t vTable = {
|
|||
.shutdown = pwmShutdownPulsesForAllMotors,
|
||||
.requestTelemetry = NULL,
|
||||
.isMotorIdle = NULL,
|
||||
|
||||
.getMotorIO = NULL,
|
||||
};
|
||||
|
||||
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t _idlePulse)
|
||||
|
@ -657,15 +644,17 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
if (!device) {
|
||||
return false;
|
||||
}
|
||||
|
||||
pwmMotorCount = device->count;
|
||||
device->vTable = &vTable;
|
||||
const uint8_t motorCount = device->count;
|
||||
printf("Initialized motor count %d\n", motorCount);
|
||||
pwmRawPkt.motorCount = motorCount;
|
||||
|
||||
printf("Initialized motor count %d\n", pwmMotorCount);
|
||||
pwmRawPkt.motorCount = pwmMotorCount;
|
||||
|
||||
idlePulse = _idlePulse;
|
||||
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||
motors[motorIndex].enabled = true;
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < pwmMotorCount; motorIndex++) {
|
||||
pwmMotors[motorIndex].enabled = true;
|
||||
}
|
||||
|
||||
return true;
|
||||
|
|
|
@ -116,6 +116,14 @@ const i2cHardware_t i2cHardware[I2CDEV_COUNT] = {
|
|||
|
||||
i2cDevice_t i2cDevice[I2CDEV_COUNT];
|
||||
|
||||
// State used by event handler ISR
|
||||
typedef struct {
|
||||
uint8_t subaddress_sent; // flag to indicate if subaddess sent
|
||||
uint8_t final_stop; // flag to indicate final bus condition
|
||||
int8_t index; // index is signed -1 == send the subaddress
|
||||
} i2cEvState_t;
|
||||
static i2cEvState_t i2c_ev_state[I2CDEV_COUNT];
|
||||
|
||||
static volatile uint16_t i2cErrorCount = 0;
|
||||
|
||||
void I2C1_ER_IRQHandler(void)
|
||||
|
@ -316,18 +324,17 @@ void i2c_ev_handler(I2CDevice device)
|
|||
{
|
||||
I2C_TypeDef *I2Cx = i2cDevice[device].hardware->reg;
|
||||
|
||||
i2cEvState_t *ev_state = &i2c_ev_state[device];
|
||||
i2cState_t *state = &i2cDevice[device].state;
|
||||
|
||||
static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition
|
||||
static int8_t index; // index is signed -1 == send the subaddress
|
||||
uint8_t SReg_1 = I2Cx->SR1; // read the status register here
|
||||
|
||||
if (SReg_1 & I2C_SR1_SB) { // we just sent a start - EV5 in ref manual
|
||||
I2Cx->CR1 &= ~I2C_CR1_POS; // reset the POS bit so ACK/NACK applied to the current byte
|
||||
I2C_AcknowledgeConfig(I2Cx, ENABLE); // make sure ACK is on
|
||||
index = 0; // reset the index
|
||||
if (state->reading && (subaddress_sent || 0xFF == state->reg)) { // we have sent the subaddr
|
||||
subaddress_sent = 1; // make sure this is set in case of no subaddress, so following code runs correctly
|
||||
ev_state->index = 0; // reset the index
|
||||
if (state->reading && (ev_state->subaddress_sent || 0xFF == state->reg)) { // we have sent the subaddr
|
||||
ev_state->subaddress_sent = 1; // make sure this is set in case of no subaddress, so following code runs correctly
|
||||
if (state->bytes == 2)
|
||||
I2Cx->CR1 |= I2C_CR1_POS; // set the POS bit so NACK applied to the final byte in the two byte read
|
||||
I2C_Send7bitAddress(I2Cx, state->addr, I2C_Direction_Receiver); // send the address and set hardware mode
|
||||
|
@ -335,93 +342,93 @@ void i2c_ev_handler(I2CDevice device)
|
|||
else { // direction is Tx, or we havent sent the sub and rep start
|
||||
I2C_Send7bitAddress(I2Cx, state->addr, I2C_Direction_Transmitter); // send the address and set hardware mode
|
||||
if (state->reg != 0xFF) // 0xFF as subaddress means it will be ignored, in Tx or Rx mode
|
||||
index = -1; // send a subaddress
|
||||
ev_state->index = -1; // send a subaddress
|
||||
}
|
||||
}
|
||||
else if (SReg_1 & I2C_SR1_ADDR) { // we just sent the address - EV6 in ref manual
|
||||
// Read SR1,2 to clear ADDR
|
||||
__DMB(); // memory fence to control hardware
|
||||
if (state->bytes == 1 && state->reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
|
||||
if (state->bytes == 1 && state->reading && ev_state->subaddress_sent) { // we are receiving 1 byte - EV6_3
|
||||
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
||||
__DMB();
|
||||
(void)I2Cx->SR2; // clear ADDR after ACK is turned off
|
||||
I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop
|
||||
final_stop = 1;
|
||||
ev_state->final_stop = 1;
|
||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // allow us to have an EV7
|
||||
}
|
||||
else { // EV6 and EV6_1
|
||||
(void)I2Cx->SR2; // clear the ADDR here
|
||||
__DMB();
|
||||
if (state->bytes == 2 && state->reading && subaddress_sent) { // rx 2 bytes - EV6_1
|
||||
if (state->bytes == 2 && state->reading && ev_state->subaddress_sent) { // rx 2 bytes - EV6_1
|
||||
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to fill
|
||||
}
|
||||
else if (state->bytes == 3 && state->reading && subaddress_sent) // rx 3 bytes
|
||||
else if (state->bytes == 3 && state->reading && ev_state->subaddress_sent) // rx 3 bytes
|
||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // make sure RXNE disabled so we get a BTF in two bytes time
|
||||
else // receiving greater than three bytes, sending subaddress, or transmitting
|
||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE);
|
||||
}
|
||||
}
|
||||
else if (SReg_1 & I2C_SR1_BTF) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2
|
||||
final_stop = 1;
|
||||
if (state->reading && subaddress_sent) { // EV7_2, EV7_3
|
||||
ev_state->final_stop = 1;
|
||||
if (state->reading && ev_state->subaddress_sent) { // EV7_2, EV7_3
|
||||
if (state->bytes > 2) { // EV7_2
|
||||
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
|
||||
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2
|
||||
state->read_p[ev_state->index++] = (uint8_t)I2Cx->DR; // read data N-2
|
||||
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
|
||||
final_stop = 1; // required to fix hardware
|
||||
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
|
||||
ev_state->final_stop = 1; // required to fix hardware
|
||||
state->read_p[ev_state->index++] = (uint8_t)I2Cx->DR; // read data N - 1
|
||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // enable TXE to allow the final EV7
|
||||
}
|
||||
else { // EV7_3
|
||||
if (final_stop)
|
||||
if (ev_state->final_stop)
|
||||
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
|
||||
else
|
||||
I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
|
||||
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
|
||||
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N
|
||||
index++; // to show job completed
|
||||
state->read_p[ev_state->index++] = (uint8_t)I2Cx->DR; // read data N - 1
|
||||
state->read_p[ev_state->index++] = (uint8_t)I2Cx->DR; // read data N
|
||||
ev_state->index++; // to show job completed
|
||||
}
|
||||
}
|
||||
else { // EV8_2, which may be due to a subaddress sent or a write completion
|
||||
if (subaddress_sent || (state->writing)) {
|
||||
if (final_stop)
|
||||
if (ev_state->subaddress_sent || (state->writing)) {
|
||||
if (ev_state->final_stop)
|
||||
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
|
||||
else
|
||||
I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
|
||||
index++; // to show that the job is complete
|
||||
ev_state->index++; // to show that the job is complete
|
||||
}
|
||||
else { // We need to send a subaddress
|
||||
I2C_GenerateSTART(I2Cx, ENABLE); // program the repeated Start
|
||||
subaddress_sent = 1; // this is set back to zero upon completion of the current task
|
||||
ev_state->subaddress_sent = 1; // this is set back to zero upon completion of the current task
|
||||
}
|
||||
}
|
||||
// we must wait for the start to clear, otherwise we get constant BTF
|
||||
while (I2Cx->CR1 & I2C_CR1_START) {; }
|
||||
}
|
||||
else if (SReg_1 & I2C_SR1_RXNE) { // Byte received - EV7
|
||||
state->read_p[index++] = (uint8_t)I2Cx->DR;
|
||||
if (state->bytes == (index + 3))
|
||||
state->read_p[ev_state->index++] = (uint8_t)I2Cx->DR;
|
||||
if (state->bytes == (ev_state->index + 3))
|
||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush so we can get an EV7_2
|
||||
if (state->bytes == index) // We have completed a final EV7
|
||||
index++; // to show job is complete
|
||||
if (state->bytes == ev_state->index) // We have completed a final EV7
|
||||
ev_state->index++; // to show job is complete
|
||||
}
|
||||
else if (SReg_1 & I2C_SR1_TXE) { // Byte transmitted EV8 / EV8_1
|
||||
if (index != -1) { // we dont have a subaddress to send
|
||||
I2Cx->DR = state->write_p[index++];
|
||||
if (state->bytes == index) // we have sent all the data
|
||||
if (ev_state->index != -1) { // we dont have a subaddress to send
|
||||
I2Cx->DR = state->write_p[ev_state->index++];
|
||||
if (state->bytes == ev_state->index) // we have sent all the data
|
||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
|
||||
}
|
||||
else {
|
||||
index++;
|
||||
ev_state->index++;
|
||||
I2Cx->DR = state->reg; // send the subaddress
|
||||
if (state->reading || !(state->bytes)) // if receiving or sending 0 bytes, flush now
|
||||
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
|
||||
}
|
||||
}
|
||||
if (index == state->bytes + 1) { // we have completed the current job
|
||||
subaddress_sent = 0; // reset this here
|
||||
if (final_stop) // If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF
|
||||
if (ev_state->index == state->bytes + 1) { // we have completed the current job
|
||||
ev_state->subaddress_sent = 0; // reset this here
|
||||
if (ev_state->final_stop) // If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF
|
||||
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
|
||||
state->busy = 0;
|
||||
}
|
||||
|
|
|
@ -716,6 +716,7 @@ static const motorVTable_t bbVTable = {
|
|||
.shutdown = bbShutdown,
|
||||
.isMotorIdle = bbDshotIsMotorIdle,
|
||||
.requestTelemetry = bbDshotRequestTelemetry,
|
||||
.getMotorIO = bbGetMotorIO,
|
||||
};
|
||||
|
||||
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||
|
|
238
src/platform/STM32/include/platform/dma.h
Normal file
238
src/platform/STM32/include/platform/dma.h
Normal file
|
@ -0,0 +1,238 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the GNU General
|
||||
* Public License as published by the Free Software Foundation,
|
||||
* either version 3 of the License, or (at your option) any later
|
||||
* version.
|
||||
*
|
||||
* Betaflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
*
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public
|
||||
* License along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(APM32F4)
|
||||
#define PLATFORM_TRAIT_DMA_STREAM_REQUIRED 1
|
||||
#endif
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
#define DMA_ARCH_TYPE DMA_Stream_TypeDef
|
||||
#elif defined(STM32H7)
|
||||
// H7 has stream based DMA and channel based BDMA, but we ignore BDMA (for now).
|
||||
#define DMA_ARCH_TYPE DMA_Stream_TypeDef
|
||||
#else
|
||||
#define DMA_ARCH_TYPE DMA_Channel_TypeDef
|
||||
#endif
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA1_ST0_HANDLER = 1,
|
||||
DMA1_ST1_HANDLER,
|
||||
DMA1_ST2_HANDLER,
|
||||
DMA1_ST3_HANDLER,
|
||||
DMA1_ST4_HANDLER,
|
||||
DMA1_ST5_HANDLER,
|
||||
DMA1_ST6_HANDLER,
|
||||
DMA1_ST7_HANDLER,
|
||||
DMA2_ST0_HANDLER,
|
||||
DMA2_ST1_HANDLER,
|
||||
DMA2_ST2_HANDLER,
|
||||
DMA2_ST3_HANDLER,
|
||||
DMA2_ST4_HANDLER,
|
||||
DMA2_ST5_HANDLER,
|
||||
DMA2_ST6_HANDLER,
|
||||
DMA2_ST7_HANDLER,
|
||||
DMA_LAST_HANDLER = DMA2_ST7_HANDLER
|
||||
} dmaIdentifier_e;
|
||||
|
||||
#define DMA_DEVICE_NO(x) ((((x)-1) / 8) + 1)
|
||||
#define DMA_DEVICE_INDEX(x) ((((x)-1) % 8))
|
||||
#define DMA_OUTPUT_INDEX 0
|
||||
#define DMA_OUTPUT_STRING "DMA%d Stream %d:"
|
||||
#define DMA_INPUT_STRING "DMA%d_ST%d"
|
||||
|
||||
#define DEFINE_DMA_CHANNEL(d, s, f) { \
|
||||
.dma = d, \
|
||||
.ref = (dmaResource_t *)d ## _Stream ## s, \
|
||||
.stream = s, \
|
||||
.irqHandlerCallback = NULL, \
|
||||
.flagsShift = f, \
|
||||
.irqN = d ## _Stream ## s ## _IRQn, \
|
||||
.userParam = 0, \
|
||||
.owner.owner = 0, \
|
||||
.owner.resourceIndex = 0 \
|
||||
}
|
||||
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, s, i) FAST_IRQ_HANDLER void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\
|
||||
const uint8_t index = DMA_IDENTIFIER_TO_INDEX(i); \
|
||||
dmaCallbackHandlerFuncPtr handler = dmaDescriptors[index].irqHandlerCallback; \
|
||||
if (handler) \
|
||||
handler(&dmaDescriptors[index]); \
|
||||
}
|
||||
|
||||
#define DMA_CLEAR_FLAG(d, flag) if (d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift)
|
||||
#define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift))
|
||||
|
||||
#define DMA_IT_TCIF ((uint32_t)0x00000020)
|
||||
#define DMA_IT_HTIF ((uint32_t)0x00000010)
|
||||
#define DMA_IT_TEIF ((uint32_t)0x00000008)
|
||||
#define DMA_IT_DMEIF ((uint32_t)0x00000004)
|
||||
#define DMA_IT_FEIF ((uint32_t)0x00000001)
|
||||
|
||||
void dmaMuxEnable(dmaIdentifier_e identifier, uint32_t dmaMuxId);
|
||||
|
||||
#else
|
||||
|
||||
#if defined(STM32G4)
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA1_CH1_HANDLER = 1,
|
||||
DMA1_CH2_HANDLER,
|
||||
DMA1_CH3_HANDLER,
|
||||
DMA1_CH4_HANDLER,
|
||||
DMA1_CH5_HANDLER,
|
||||
DMA1_CH6_HANDLER,
|
||||
DMA1_CH7_HANDLER,
|
||||
DMA1_CH8_HANDLER,
|
||||
DMA2_CH1_HANDLER,
|
||||
DMA2_CH2_HANDLER,
|
||||
DMA2_CH3_HANDLER,
|
||||
DMA2_CH4_HANDLER,
|
||||
DMA2_CH5_HANDLER,
|
||||
DMA2_CH6_HANDLER,
|
||||
DMA2_CH7_HANDLER,
|
||||
DMA2_CH8_HANDLER,
|
||||
DMA_LAST_HANDLER = DMA2_CH8_HANDLER
|
||||
} dmaIdentifier_e;
|
||||
|
||||
#define DMA_DEVICE_NO(x) ((((x)-1) / 8) + 1)
|
||||
#define DMA_DEVICE_INDEX(x) ((((x)-1) % 8) + 1)
|
||||
|
||||
uint32_t dmaGetChannel(const uint8_t channel);
|
||||
|
||||
#else // !STM32G4
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA1_CH1_HANDLER = 1,
|
||||
DMA1_CH2_HANDLER,
|
||||
DMA1_CH3_HANDLER,
|
||||
DMA1_CH4_HANDLER,
|
||||
DMA1_CH5_HANDLER,
|
||||
DMA1_CH6_HANDLER,
|
||||
DMA1_CH7_HANDLER,
|
||||
DMA_LAST_HANDLER = DMA1_CH7_HANDLER
|
||||
} dmaIdentifier_e;
|
||||
|
||||
#define DMA_DEVICE_NO(x) ((((x)-1) / 7) + 1)
|
||||
#define DMA_DEVICE_INDEX(x) ((((x)-1) % 7) + 1)
|
||||
|
||||
#endif // STM32G4
|
||||
|
||||
#define DMA_OUTPUT_INDEX 0
|
||||
#define DMA_OUTPUT_STRING "DMA%d Channel %d:"
|
||||
#define DMA_INPUT_STRING "DMA%d_CH%d"
|
||||
|
||||
#define DEFINE_DMA_CHANNEL(d, c, f) { \
|
||||
.dma = d, \
|
||||
.ref = (dmaResource_t *)d ## _Channel ## c, \
|
||||
.irqHandlerCallback = NULL, \
|
||||
.flagsShift = f, \
|
||||
.irqN = d ## _Channel ## c ## _IRQn, \
|
||||
.userParam = 0, \
|
||||
.owner.owner = 0, \
|
||||
.owner.resourceIndex = 0 \
|
||||
}
|
||||
|
||||
#define DMA_HANDLER_CODE
|
||||
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, c, i) DMA_HANDLER_CODE void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\
|
||||
const uint8_t index = DMA_IDENTIFIER_TO_INDEX(i); \
|
||||
dmaCallbackHandlerFuncPtr handler = dmaDescriptors[index].irqHandlerCallback; \
|
||||
if (handler) \
|
||||
handler(&dmaDescriptors[index]); \
|
||||
}
|
||||
|
||||
#define DMA_CLEAR_FLAG(d, flag) d->dma->IFCR = (flag << d->flagsShift)
|
||||
#define DMA_GET_FLAG_STATUS(d, flag) (d->dma->ISR & (flag << d->flagsShift))
|
||||
|
||||
#define DMA_IT_TCIF ((uint32_t)0x00000002)
|
||||
#define DMA_IT_HTIF ((uint32_t)0x00000004)
|
||||
#define DMA_IT_TEIF ((uint32_t)0x00000008)
|
||||
|
||||
#endif
|
||||
|
||||
// Macros to avoid direct register and register bit access
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CR & DMA_SxCR_EN)
|
||||
#define REG_NDTR NDTR
|
||||
#elif defined(STM32H7)
|
||||
// For H7, we have to differenciate DMA1/2 and BDMA for access to the control register.
|
||||
// HAL library has a macro for this, but it is extremely inefficient in that it compares
|
||||
// the address against all possible values.
|
||||
// Here, we just compare the address against regions of memory.
|
||||
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
|
||||
// For H7A3, if it's lower than CD_AHB2PERIPH_BASE, then it's DMA1/2 and it's stream based.
|
||||
// If not, it's BDMA and it's channel based.
|
||||
#define IS_DMA_ENABLED(reg) \
|
||||
((uint32_t)(reg) < CD_AHB2PERIPH_BASE) ? \
|
||||
(((DMA_Stream_TypeDef *)(reg))->CR & DMA_SxCR_EN) : \
|
||||
(((BDMA_Channel_TypeDef *)(reg))->CCR & BDMA_CCR_EN)
|
||||
#else
|
||||
// For H743 and H750, if it's not in D3 peripheral area, then it's DMA1/2 and it's stream based.
|
||||
// If not, it's BDMA and it's channel based.
|
||||
#define IS_DMA_ENABLED(reg) \
|
||||
((uint32_t)(reg) < D3_AHB1PERIPH_BASE) ? \
|
||||
(((DMA_Stream_TypeDef *)(reg))->CR & DMA_SxCR_EN) : \
|
||||
(((BDMA_Channel_TypeDef *)(reg))->CCR & BDMA_CCR_EN)
|
||||
#endif
|
||||
#elif defined(STM32G4)
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN)
|
||||
// Missing __HAL_DMA_SET_COUNTER in FW library V1.0.0
|
||||
#define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNDTR = (uint16_t)(__COUNTER__))
|
||||
#else
|
||||
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN)
|
||||
#define DMAx_SetMemoryAddress(reg, address) ((DMA_ARCH_TYPE *)(reg))->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail]
|
||||
#endif
|
||||
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
|
||||
// We actually need these LL case only
|
||||
|
||||
#define xLL_EX_DMA_DeInit(dmaResource) LL_EX_DMA_DeInit((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_Init(dmaResource, initstruct) LL_EX_DMA_Init((DMA_ARCH_TYPE *)(dmaResource), initstruct)
|
||||
#define xLL_EX_DMA_DisableResource(dmaResource) LL_EX_DMA_DisableResource((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_EnableResource(dmaResource) LL_EX_DMA_EnableResource((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_GetDataLength(dmaResource) LL_EX_DMA_GetDataLength((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xLL_EX_DMA_SetDataLength(dmaResource, length) LL_EX_DMA_SetDataLength((DMA_ARCH_TYPE *)(dmaResource), length)
|
||||
#define xLL_EX_DMA_EnableIT_TC(dmaResource) LL_EX_DMA_EnableIT_TC((DMA_ARCH_TYPE *)(dmaResource))
|
||||
|
||||
#else
|
||||
|
||||
#define xDMA_Init(dmaResource, initStruct) DMA_Init((DMA_ARCH_TYPE *)(dmaResource), initStruct)
|
||||
#define xDMA_DeInit(dmaResource) DMA_DeInit((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xDMA_Cmd(dmaResource, newState) DMA_Cmd((DMA_ARCH_TYPE *)(dmaResource), newState)
|
||||
#define xDMA_ITConfig(dmaResource, flags, newState) DMA_ITConfig((DMA_ARCH_TYPE *)(dmaResource), flags, newState)
|
||||
#define xDMA_GetCurrDataCounter(dmaResource) DMA_GetCurrDataCounter((DMA_ARCH_TYPE *)(dmaResource))
|
||||
#define xDMA_SetCurrDataCounter(dmaResource, count) DMA_SetCurrDataCounter((DMA_ARCH_TYPE *)(dmaResource), count)
|
||||
#define xDMA_GetFlagStatus(dmaResource, flags) DMA_GetFlagStatus((DMA_ARCH_TYPE *)(dmaResource), flags)
|
||||
#define xDMA_ClearFlag(dmaResource, flags) DMA_ClearFlag((DMA_ARCH_TYPE *)(dmaResource), flags)
|
||||
#define xDMA_MemoryTargetConfig(dmaResource, address, target) DMA_MemoryTargetConfig((DMA_ARCH_TYPE *)(dmaResource), address, target)
|
||||
|
||||
#endif
|
|
@ -117,6 +117,7 @@ CMSIS_SRC :=
|
|||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \
|
||||
|
@ -132,6 +133,7 @@ CMSIS_SRC := \
|
|||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(STDPERIPH_DIR)/inc \
|
||||
$(LIB_MAIN_DIR)/$(USBOTG_DIR)/inc \
|
||||
|
|
|
@ -85,6 +85,7 @@ VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7x
|
|||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \
|
||||
|
|
|
@ -78,6 +78,7 @@ CMSIS_SRC :=
|
|||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \
|
||||
|
|
|
@ -87,6 +87,7 @@ VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H5x
|
|||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \
|
||||
|
|
|
@ -91,6 +91,7 @@ VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H7x
|
|||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(TARGET_PLATFORM_DIR) \
|
||||
$(TARGET_PLATFORM_DIR)/include \
|
||||
$(TARGET_PLATFORM_DIR)/startup \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_output_impl.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
|
@ -110,15 +111,15 @@ void pwmOutConfig(timerChannel_t *channel, const timerHardware_t *timerHardware,
|
|||
static void pwmWriteStandard(uint8_t index, float value)
|
||||
{
|
||||
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */
|
||||
*motors[index].channel.ccr = lrintf((value * motors[index].pulseScale) + motors[index].pulseOffset);
|
||||
*pwmMotors[index].channel.ccr = lrintf((value * pwmMotors[index].pulseScale) + pwmMotors[index].pulseOffset);
|
||||
}
|
||||
|
||||
static void pwmShutdownPulsesForAllMotors(void)
|
||||
{
|
||||
for (int index = 0; pwmMotorCount; index++) {
|
||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
||||
if (motors[index].channel.ccr) {
|
||||
*motors[index].channel.ccr = 0;
|
||||
if (pwmMotors[index].channel.ccr) {
|
||||
*pwmMotors[index].channel.ccr = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -128,17 +129,6 @@ static void pwmDisableMotors(void)
|
|||
pwmShutdownPulsesForAllMotors();
|
||||
}
|
||||
|
||||
static bool pwmEnableMotors(void)
|
||||
{
|
||||
/* check motors can be enabled */
|
||||
return pwmMotorCount > 0;
|
||||
}
|
||||
|
||||
static bool pwmIsMotorEnabled(unsigned index)
|
||||
{
|
||||
return motors[index].enabled;
|
||||
}
|
||||
|
||||
static void pwmCompleteMotorUpdate(void)
|
||||
{
|
||||
if (useContinuousUpdate) {
|
||||
|
@ -146,12 +136,12 @@ static void pwmCompleteMotorUpdate(void)
|
|||
}
|
||||
|
||||
for (int index = 0; pwmMotorCount; index++) {
|
||||
if (motors[index].forceOverflow) {
|
||||
timerForceOverflow(motors[index].channel.tim);
|
||||
if (pwmMotors[index].forceOverflow) {
|
||||
timerForceOverflow(pwmMotors[index].channel.tim);
|
||||
}
|
||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again.
|
||||
// This compare register will be set to the output value on the next main loop.
|
||||
*motors[index].channel.ccr = 0;
|
||||
*pwmMotors[index].channel.ccr = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -178,11 +168,12 @@ static const motorVTable_t motorPwmVTable = {
|
|||
.updateComplete = pwmCompleteMotorUpdate,
|
||||
.requestTelemetry = NULL,
|
||||
.isMotorIdle = NULL,
|
||||
.getMotorIO = pwmGetMotorIO,
|
||||
};
|
||||
|
||||
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
||||
{
|
||||
memset(motors, 0, sizeof(motors));
|
||||
memset(pwmMotors, 0, sizeof(pwmMotors));
|
||||
|
||||
pwmMotorCount = device->count;
|
||||
device->vTable = &motorPwmVTable;
|
||||
|
@ -230,10 +221,10 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
return false;
|
||||
}
|
||||
|
||||
motors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(pwmMotors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
|
||||
IOConfigGPIOAF(motors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
IOConfigGPIOAF(pwmMotors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||
|
||||
/* standard PWM outputs */
|
||||
// margin of safety is 4 periods when unsynced
|
||||
|
@ -250,20 +241,20 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
TODO: this can be moved back to periodMin and periodLen
|
||||
once mixer outputs a 0..1 float value.
|
||||
*/
|
||||
motors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||
motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000);
|
||||
pwmMotors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||
pwmMotors[motorIndex].pulseOffset = (sMin * hz) - (pwmMotors[motorIndex].pulseScale * 1000);
|
||||
|
||||
pwmOutConfig(&motors[motorIndex].channel, timerHardware, hz, period, idlePulse, motorConfig->motorInversion);
|
||||
pwmOutConfig(&pwmMotors[motorIndex].channel, timerHardware, hz, period, idlePulse, motorConfig->motorInversion);
|
||||
|
||||
bool timerAlreadyUsed = false;
|
||||
for (int i = 0; i < motorIndex; i++) {
|
||||
if (motors[i].channel.tim == motors[motorIndex].channel.tim) {
|
||||
if (pwmMotors[i].channel.tim == pwmMotors[motorIndex].channel.tim) {
|
||||
timerAlreadyUsed = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||
motors[motorIndex].enabled = true;
|
||||
pwmMotors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||
pwmMotors[motorIndex].enabled = true;
|
||||
}
|
||||
|
||||
return true;
|
||||
|
@ -271,7 +262,7 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
|||
|
||||
pwmOutputPort_t *pwmGetMotors(void)
|
||||
{
|
||||
return motors;
|
||||
return pwmMotors;
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
|
|
|
@ -118,7 +118,6 @@ void SystemInit(void)
|
|||
void SystemCoreClockUpdate(void)
|
||||
{
|
||||
uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
|
||||
|
||||
uint32_t tmp, pllvco, pllr, pllsource, pllm;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
|
@ -225,6 +224,7 @@ void Error_Handler(void)
|
|||
// Target frequencies for cpu_overclock (Levels 0 through 3)
|
||||
|
||||
uint16_t sysclkSeries8[] = { 168, 192, 216, 240 };
|
||||
uint16_t sysclkSeries26[] = { 169, 195, 221, 247 };
|
||||
uint16_t sysclkSeries27[] = { 171, 198, 225, 252 };
|
||||
#define OVERCLOCK_LEVELS ARRAYLEN(sysclkSeries8)
|
||||
|
||||
|
@ -247,6 +247,13 @@ static bool systemComputePLLParameters(uint8_t src, uint16_t target, int *sysclk
|
|||
multDiff = vcoDiff / 16 * 2;
|
||||
*plln = 42 + multDiff;
|
||||
vcoFreq = 8 * *plln;
|
||||
} else if (src == 26) {
|
||||
*pllm = 2;
|
||||
vcoBase = 169 * 2;
|
||||
vcoDiff = vcoTarget - vcoBase;
|
||||
multDiff = vcoDiff / 26 * 2;
|
||||
*plln = 26 + multDiff;
|
||||
vcoFreq = 13 * *plln;
|
||||
} else if (src == 27) {
|
||||
*pllm = 3;
|
||||
vcoBase = 171 * 2;
|
||||
|
@ -289,8 +296,10 @@ static bool systemClock_PLLConfig(int overclockLevel)
|
|||
pllSrc = RCC_PLLSOURCE_HSE;
|
||||
if (pllInput == 8 || pllInput == 16 || pllInput == 24) {
|
||||
targetMhz = sysclkSeries8[overclockLevel];
|
||||
} else if (pllInput == 26) {
|
||||
targetMhz = sysclkSeries26[overclockLevel];
|
||||
} else if (pllInput == 27) {
|
||||
targetMhz = sysclkSeries8[overclockLevel];
|
||||
targetMhz = sysclkSeries27[overclockLevel];
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
|
@ -303,9 +312,9 @@ void systemClockSetHSEValue(uint32_t frequency)
|
|||
{
|
||||
uint32_t freqMhz = frequency / 1000000;
|
||||
|
||||
// Only supported HSE crystal/resonator is 27MHz or integer multiples of 8MHz
|
||||
// Only supported HSE crystal/resonator is 27MHz, 26 MHz or integer multiples of 8MHz
|
||||
|
||||
if (freqMhz != 27 && (freqMhz / 8) * 8 != freqMhz) {
|
||||
if (freqMhz != 27 && freqMhz != 26 && (freqMhz / 8) * 8 != freqMhz) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -371,10 +380,12 @@ void SystemClock_Config(void)
|
|||
|
||||
// Initializes the CPU, AHB and APB busses clocks
|
||||
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_HSI48
|
||||
|RCC_OSCILLATORTYPE_LSI|RCC_OSCILLATORTYPE_HSE;
|
||||
|
||||
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
|
||||
const bool useHse = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE) != 0;
|
||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSI48
|
||||
| RCC_OSCILLATORTYPE_LSI
|
||||
| (useHse ? RCC_OSCILLATORTYPE_HSE : 0);
|
||||
RCC_OscInitStruct.HSEState = useHse ? RCC_HSE_ON : RCC_HSE_OFF;
|
||||
|
||||
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
|
||||
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
|
||||
RCC_OscInitStruct.LSIState = RCC_LSI_ON;
|
||||
|
|
|
@ -1251,4 +1251,43 @@ HAL_StatusTypeDef DMA_SetCurrDataCounter(TIM_HandleTypeDef *htim, uint32_t Chann
|
|||
/* Return function status */
|
||||
return HAL_OK;
|
||||
}
|
||||
|
||||
void timerReset(TIM_TypeDef *timer)
|
||||
{
|
||||
LL_TIM_DeInit(timer);
|
||||
}
|
||||
|
||||
void timerSetPeriod(TIM_TypeDef *timer, uint32_t period)
|
||||
{
|
||||
timer->ARR = period;
|
||||
}
|
||||
|
||||
uint32_t timerGetPeriod(TIM_TypeDef *timer)
|
||||
{
|
||||
return timer->ARR;
|
||||
}
|
||||
|
||||
void timerSetCounter(TIM_TypeDef *timer, uint32_t counter)
|
||||
{
|
||||
timer->CNT = counter;
|
||||
}
|
||||
|
||||
void timerDisable(TIM_TypeDef *timer)
|
||||
{
|
||||
LL_TIM_DisableIT_UPDATE(timer);
|
||||
LL_TIM_DisableCounter(timer);
|
||||
}
|
||||
|
||||
void timerEnable(TIM_TypeDef *timer)
|
||||
{
|
||||
LL_TIM_EnableCounter(timer);
|
||||
LL_TIM_GenerateEvent_UPDATE(timer);
|
||||
}
|
||||
|
||||
void timerEnableInterrupt(TIM_TypeDef *timer)
|
||||
{
|
||||
LL_TIM_ClearFlag_UPDATE(timer);
|
||||
LL_TIM_EnableIT_UPDATE(timer);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -954,4 +954,43 @@ uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz)
|
|||
}
|
||||
return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
|
||||
}
|
||||
|
||||
void timerReset(TIM_TypeDef *timer)
|
||||
{
|
||||
TIM_DeInit(timer);
|
||||
}
|
||||
|
||||
void timerSetPeriod(TIM_TypeDef *timer, uint32_t period)
|
||||
{
|
||||
timer->ARR = period;
|
||||
}
|
||||
|
||||
uint32_t timerGetPeriod(TIM_TypeDef *timer)
|
||||
{
|
||||
return timer->ARR;
|
||||
}
|
||||
|
||||
void timerSetCounter(TIM_TypeDef *timer, uint32_t counter)
|
||||
{
|
||||
timer->CNT = counter;
|
||||
}
|
||||
|
||||
void timerDisable(TIM_TypeDef *timer)
|
||||
{
|
||||
TIM_ITConfig(timer, TIM_IT_Update, DISABLE);
|
||||
TIM_Cmd(timer, DISABLE);
|
||||
}
|
||||
|
||||
void timerEnable(TIM_TypeDef *timer)
|
||||
{
|
||||
TIM_Cmd(timer, ENABLE);
|
||||
TIM_GenerateEvent(timer, TIM_EventSource_Update);
|
||||
}
|
||||
|
||||
void timerEnableInterrupt(TIM_TypeDef *timer)
|
||||
{
|
||||
TIM_ClearFlag(timer, TIM_FLAG_Update);
|
||||
TIM_ITConfig(timer, TIM_IT_Update, ENABLE);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -285,3 +285,4 @@ int bbDMA_Count(bbPort_t *bbPort);
|
|||
|
||||
void bbDshotRequestTelemetry(unsigned motorIndex);
|
||||
bool bbDshotIsMotorIdle(unsigned motorIndex);
|
||||
IO_t bbGetMotorIO(unsigned index);
|
||||
|
|
|
@ -54,6 +54,14 @@ bool bbDshotIsMotorIdle(unsigned motorIndex)
|
|||
return bbmotor->protocolControl.value == 0;
|
||||
}
|
||||
|
||||
IO_t bbGetMotorIO(unsigned index)
|
||||
{
|
||||
if (index >= dshotMotorCount) {
|
||||
return IO_NONE;
|
||||
}
|
||||
return bbMotors[index].io;
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
bool isDshotBitbangActive(const motorDevConfig_t *motorDevConfig)
|
||||
{
|
||||
|
|
|
@ -123,7 +123,15 @@ static bool dshotPwmEnableMotors(void)
|
|||
|
||||
static bool dshotPwmIsMotorEnabled(unsigned index)
|
||||
{
|
||||
return motors[index].enabled;
|
||||
return pwmMotors[index].enabled;
|
||||
}
|
||||
|
||||
static IO_t pwmDshotGetMotorIO(unsigned index)
|
||||
{
|
||||
if (index >= dshotMotorCount) {
|
||||
return IO_NONE;
|
||||
}
|
||||
return pwmMotors[index].io;
|
||||
}
|
||||
|
||||
static FAST_CODE void dshotWriteInt(uint8_t index, uint16_t value)
|
||||
|
@ -150,6 +158,7 @@ static const motorVTable_t dshotPwmVTable = {
|
|||
.shutdown = dshotPwmShutdown,
|
||||
.requestTelemetry = pwmDshotRequestTelemetry,
|
||||
.isMotorIdle = pwmDshotIsMotorIdle,
|
||||
.getMotorIO = pwmDshotGetMotorIO,
|
||||
};
|
||||
|
||||
bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||
|
@ -181,15 +190,15 @@ bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
|||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
|
||||
if (timerHardware != NULL) {
|
||||
motors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||
IOInit(pwmMotors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||
|
||||
if (pwmDshotMotorHardwareConfig(timerHardware,
|
||||
motorIndex,
|
||||
reorderedMotorIndex,
|
||||
motorConfig->motorProtocol,
|
||||
motorConfig->motorInversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output)) {
|
||||
motors[motorIndex].enabled = true;
|
||||
pwmMotors[motorIndex].enabled = true;
|
||||
|
||||
continue;
|
||||
}
|
||||
|
|
|
@ -346,6 +346,8 @@ const mcuTypeInfo_t *getMcuTypeInfo(void)
|
|||
{ .id = MCU_TYPE_F746, .name = "STM32F746" },
|
||||
#elif defined(STM32F765xx)
|
||||
{ .id = MCU_TYPE_F765, .name = "STM32F765" },
|
||||
#elif defined(STM32H563xx)
|
||||
{ .id = MCU_TYPE_H563, .name = "STM32H563" },
|
||||
#elif defined(STM32H750xx)
|
||||
{ .id = MCU_TYPE_H750, .name = "STM32H750" },
|
||||
#elif defined(STM32H730xx)
|
||||
|
|
|
@ -50,7 +50,7 @@ extern "C" {
|
|||
|
||||
PG_REGISTER(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 0);
|
||||
PG_REGISTER(altHoldConfig_t, altHoldConfig, PG_ALTHOLD_CONFIG, 0);
|
||||
PG_REGISTER(apConfig_t, apConfig, PG_AUTOPILOT, 0);
|
||||
PG_REGISTER(autopilotConfig_t, autopilotConfig, PG_AUTOPILOT, 0);
|
||||
PG_REGISTER(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 0);
|
||||
PG_REGISTER(positionConfig_t, positionConfig, PG_POSITION, 0);
|
||||
PG_REGISTER(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 0);
|
||||
|
|
|
@ -79,7 +79,7 @@ extern "C" {
|
|||
PG_REGISTER(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 0);
|
||||
PG_REGISTER(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_RESCUE, 0);
|
||||
PG_REGISTER(positionConfig_t, positionConfig, PG_POSITION, 0);
|
||||
PG_REGISTER(apConfig_t, apConfig, PG_AUTOPILOT, 0);
|
||||
PG_REGISTER(autopilotConfig_t, autopilotConfig, PG_AUTOPILOT, 0);
|
||||
|
||||
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
uint16_t averageSystemLoadPercent = 0;
|
||||
|
|
|
@ -75,7 +75,7 @@ extern "C" {
|
|||
PG_REGISTER(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 0);
|
||||
PG_REGISTER(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 0);
|
||||
PG_REGISTER(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 0);
|
||||
PG_REGISTER(apConfig_t, apConfig, PG_AUTOPILOT, 0);
|
||||
PG_REGISTER(autopilotConfig_t, autopilotConfig, PG_AUTOPILOT, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
|
||||
.enabledFeatures = 0
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
|
||||
|
||||
#define PID_PROFILE_COUNT 4
|
||||
#define CONTROL_RATE_PROFILE_COUNT 4
|
||||
#define CONTROL_RATE_PROFILE_COUNT 4
|
||||
#define USE_MAG
|
||||
#define USE_BARO
|
||||
#define USE_GPS
|
||||
|
|
27
src/test/unit/platform/dma.h
Normal file
27
src/test/unit/platform/dma.h
Normal file
|
@ -0,0 +1,27 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the GNU General
|
||||
* Public License as published by the Free Software Foundation,
|
||||
* either version 3 of the License, or (at your option) any later
|
||||
* version.
|
||||
*
|
||||
* Betaflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
*
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public
|
||||
* License along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
typedef enum {
|
||||
DMA_NONE = 0,
|
||||
DMA_LAST_HANDLER = DMA_NONE
|
||||
} dmaIdentifier_e;
|
|
@ -58,6 +58,7 @@
|
|||
#define USE_LED_STRIP_STATUS_MODE
|
||||
#define USE_SERVOS
|
||||
#define USE_TRANSPONDER
|
||||
#define USE_VIRTUAL_LED
|
||||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue