mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +03:00
Consolidating motorCounts, and removing dependencies.
This commit is contained in:
parent
443336b3b5
commit
2c340a63d3
24 changed files with 128 additions and 145 deletions
|
@ -45,7 +45,6 @@
|
||||||
#include "drivers/dshot_command.h"
|
#include "drivers/dshot_command.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
|
||||||
|
|
||||||
#include "pg/rpm_filter.h"
|
#include "pg/rpm_filter.h"
|
||||||
|
|
||||||
|
@ -55,6 +54,8 @@
|
||||||
|
|
||||||
#define ERPM_PER_LSB 100.0f
|
#define ERPM_PER_LSB 100.0f
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT uint8_t dshotMotorCount = 0;
|
||||||
|
|
||||||
void dshotInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
void dshotInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
||||||
{
|
{
|
||||||
float outputLimitOffset = DSHOT_RANGE * (1 - outputLimit);
|
float outputLimitOffset = DSHOT_RANGE * (1 - outputLimit);
|
||||||
|
@ -162,7 +163,7 @@ void initDshotTelemetry(const timeUs_t looptimeUs)
|
||||||
|
|
||||||
if (motorConfig()->dev.useDshotTelemetry) {
|
if (motorConfig()->dev.useDshotTelemetry) {
|
||||||
// init LPFs for RPM data
|
// init LPFs for RPM data
|
||||||
for (int i = 0; i < getMotorCount(); i++) {
|
for (unsigned i = 0; i < dshotMotorCount; i++) {
|
||||||
pt1FilterInit(&motorFreqLpf[i], pt1FilterGain(rpmFilterConfig()->rpm_filter_lpf_hz, looptimeUs * 1e-6f));
|
pt1FilterInit(&motorFreqLpf[i], pt1FilterGain(rpmFilterConfig()->rpm_filter_lpf_hz, looptimeUs * 1e-6f));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -188,7 +189,7 @@ static uint32_t dshot_decode_eRPM_telemetry_value(uint16_t value)
|
||||||
static void dshot_decode_telemetry_value(uint8_t motorIndex, uint32_t *pDecoded, dshotTelemetryType_t *pType)
|
static void dshot_decode_telemetry_value(uint8_t motorIndex, uint32_t *pDecoded, dshotTelemetryType_t *pType)
|
||||||
{
|
{
|
||||||
uint16_t value = dshotTelemetryState.motorState[motorIndex].rawValue;
|
uint16_t value = dshotTelemetryState.motorState[motorIndex].rawValue;
|
||||||
const unsigned motorCount = motorDeviceCount();
|
const unsigned motorCount = dshotMotorCount;
|
||||||
|
|
||||||
if (dshotTelemetryState.motorState[motorIndex].telemetryTypes == DSHOT_NORMAL_TELEMETRY_MASK) { /* Check DSHOT_TELEMETRY_TYPE_eRPM mask */
|
if (dshotTelemetryState.motorState[motorIndex].telemetryTypes == DSHOT_NORMAL_TELEMETRY_MASK) { /* Check DSHOT_TELEMETRY_TYPE_eRPM mask */
|
||||||
// Decode eRPM telemetry
|
// Decode eRPM telemetry
|
||||||
|
@ -301,7 +302,7 @@ FAST_CODE_NOINLINE void updateDshotTelemetry(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
const unsigned motorCount = motorDeviceCount();
|
const unsigned motorCount = dshotMotorCount;
|
||||||
uint32_t erpmTotal = 0;
|
uint32_t erpmTotal = 0;
|
||||||
uint32_t rpmSamples = 0;
|
uint32_t rpmSamples = 0;
|
||||||
|
|
||||||
|
@ -330,7 +331,7 @@ FAST_CODE_NOINLINE void updateDshotTelemetry(void)
|
||||||
|
|
||||||
// update filtered rotation speed of motors for features (e.g. "RPM filter")
|
// update filtered rotation speed of motors for features (e.g. "RPM filter")
|
||||||
minMotorFrequencyHz = FLT_MAX;
|
minMotorFrequencyHz = FLT_MAX;
|
||||||
for (int motor = 0; motor < getMotorCount(); motor++) {
|
for (unsigned motor = 0; motor < dshotMotorCount; motor++) {
|
||||||
motorFrequencyHz[motor] = pt1FilterApply(&motorFreqLpf[motor], erpmToHz * getDshotErpm(motor));
|
motorFrequencyHz[motor] = pt1FilterApply(&motorFreqLpf[motor], erpmToHz * getDshotErpm(motor));
|
||||||
minMotorFrequencyHz = MIN(minMotorFrequencyHz, motorFrequencyHz[motor]);
|
minMotorFrequencyHz = MIN(minMotorFrequencyHz, motorFrequencyHz[motor]);
|
||||||
}
|
}
|
||||||
|
@ -371,7 +372,7 @@ bool isDshotMotorTelemetryActive(uint8_t motorIndex)
|
||||||
|
|
||||||
bool isDshotTelemetryActive(void)
|
bool isDshotTelemetryActive(void)
|
||||||
{
|
{
|
||||||
const unsigned motorCount = motorDeviceCount();
|
const unsigned motorCount = dshotMotorCount;
|
||||||
if (motorCount) {
|
if (motorCount) {
|
||||||
for (unsigned i = 0; i < motorCount; i++) {
|
for (unsigned i = 0; i < motorCount; i++) {
|
||||||
if (!isDshotMotorTelemetryActive(i)) {
|
if (!isDshotMotorTelemetryActive(i)) {
|
||||||
|
|
|
@ -93,6 +93,7 @@ uint16_t dshotConvertToExternal(float motorValue);
|
||||||
|
|
||||||
uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb);
|
uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb);
|
||||||
extern bool useDshotTelemetry;
|
extern bool useDshotTelemetry;
|
||||||
|
extern uint8_t dshotMotorCount;
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
|
||||||
|
@ -126,7 +127,7 @@ FAST_DATA_ZERO_INIT extern dshotTelemetryCycleCounters_t dshotDMAHandlerCycleCou
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig);
|
bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig);
|
||||||
|
|
||||||
extern dshotTelemetryState_t dshotTelemetryState;
|
extern dshotTelemetryState_t dshotTelemetryState;
|
||||||
|
|
||||||
|
|
|
@ -38,7 +38,7 @@ typedef enum {
|
||||||
DSHOT_BITBANG_STATUS_TOO_MANY_PORTS,
|
DSHOT_BITBANG_STATUS_TOO_MANY_PORTS,
|
||||||
} dshotBitbangStatus_e;
|
} dshotBitbangStatus_e;
|
||||||
|
|
||||||
void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig);
|
bool dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig);
|
||||||
dshotBitbangStatus_e dshotBitbangGetStatus();
|
dshotBitbangStatus_e dshotBitbangGetStatus();
|
||||||
const timerHardware_t *dshotBitbangTimerGetAllocatedByNumberAndChannel(int8_t timerNumber, uint16_t timerChannel);
|
const timerHardware_t *dshotBitbangTimerGetAllocatedByNumberAndChannel(int8_t timerNumber, uint16_t timerChannel);
|
||||||
const resourceOwner_t *dshotBitbangTimerGetOwner(const timerHardware_t *timer);
|
const resourceOwner_t *dshotBitbangTimerGetOwner(const timerHardware_t *timer);
|
||||||
|
|
|
@ -283,29 +283,30 @@ void motorDevInit(unsigned motorCount)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
bool success = false;
|
||||||
motorDevice.count = motorCount;
|
motorDevice.count = motorCount;
|
||||||
if (isMotorProtocolEnabled()) {
|
if (isMotorProtocolEnabled()) {
|
||||||
do {
|
do {
|
||||||
if (!isMotorProtocolDshot()) {
|
if (!isMotorProtocolDshot()) {
|
||||||
#ifdef USE_PWM_OUTPUT
|
#ifdef USE_PWM_OUTPUT
|
||||||
motorPwmDevInit(&motorDevice, motorDevConfig, idlePulse);
|
success = motorPwmDevInit(&motorDevice, motorDevConfig, idlePulse);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
#ifdef USE_DSHOT_BITBANG
|
#ifdef USE_DSHOT_BITBANG
|
||||||
if (isDshotBitbangActive(motorDevConfig)) {
|
if (isDshotBitbangActive(motorDevConfig)) {
|
||||||
dshotBitbangDevInit(&motorDevice, motorDevConfig);
|
success = dshotBitbangDevInit(&motorDevice, motorDevConfig);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
dshotPwmDevInit(&motorDevice, motorDevConfig);
|
success = dshotPwmDevInit(&motorDevice, motorDevConfig);
|
||||||
#endif
|
#endif
|
||||||
} while(0);
|
} while(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// if the VTable has been populated, the device is initialized.
|
// if the VTable has been populated, the device is initialized.
|
||||||
if (motorDevice.vTable) {
|
if (success) {
|
||||||
motorDevice.initialized = true;
|
motorDevice.initialized = true;
|
||||||
motorDevice.motorEnableTimeMs = 0;
|
motorDevice.motorEnableTimeMs = 0;
|
||||||
motorDevice.enabled = false;
|
motorDevice.enabled = false;
|
||||||
|
|
|
@ -28,12 +28,7 @@
|
||||||
|
|
||||||
#include "drivers/motor_types.h"
|
#include "drivers/motor_types.h"
|
||||||
|
|
||||||
void motorPostInitNull();
|
void motorPostInit(void);
|
||||||
void motorWriteNull(uint8_t index, float value);
|
|
||||||
bool motorDecodeTelemetryNull(void);
|
|
||||||
void motorUpdateCompleteNull(void);
|
|
||||||
|
|
||||||
void motorPostInit();
|
|
||||||
void motorWriteAll(float *values);
|
void motorWriteAll(float *values);
|
||||||
void motorRequestTelemetry(unsigned index);
|
void motorRequestTelemetry(unsigned index);
|
||||||
|
|
||||||
|
|
|
@ -24,6 +24,7 @@
|
||||||
#include "drivers/motor_types.h"
|
#include "drivers/motor_types.h"
|
||||||
|
|
||||||
void motorPostInitNull(void);
|
void motorPostInitNull(void);
|
||||||
|
void motorWriteNull(uint8_t index, float value);
|
||||||
bool motorDecodeTelemetryNull(void);
|
bool motorDecodeTelemetryNull(void);
|
||||||
void motorUpdateCompleteNull(void);
|
void motorUpdateCompleteNull(void);
|
||||||
|
|
||||||
|
|
|
@ -24,9 +24,13 @@
|
||||||
#include "pg/motor.h"
|
#include "pg/motor.h"
|
||||||
#include "fc/rc_controls.h" // for flight3DConfig_t
|
#include "fc/rc_controls.h" // for flight3DConfig_t
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
#include "drivers/pwm_output.h"
|
||||||
|
|
||||||
#if defined(USE_PWM_OUTPUT) && defined(USE_MOTOR)
|
#if defined(USE_PWM_OUTPUT) && defined(USE_MOTOR)
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT pwmOutputPort_t motors[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)
|
void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow)
|
||||||
{
|
{
|
||||||
if (featureIsEnabled(FEATURE_3D)) {
|
if (featureIsEnabled(FEATURE_3D)) {
|
||||||
|
|
|
@ -51,8 +51,9 @@ typedef struct {
|
||||||
} pwmOutputPort_t;
|
} pwmOutputPort_t;
|
||||||
|
|
||||||
extern FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
extern FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
||||||
|
extern FAST_DATA_ZERO_INIT uint8_t pwmMotorCount;
|
||||||
|
|
||||||
void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorDevConfig, uint16_t idlePulse);
|
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorDevConfig, uint16_t idlePulse);
|
||||||
|
|
||||||
typedef struct servoDevConfig_s {
|
typedef struct servoDevConfig_s {
|
||||||
// PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms)
|
// PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms)
|
||||||
|
|
|
@ -56,16 +56,6 @@
|
||||||
// Maximum time to wait for telemetry reception to complete
|
// Maximum time to wait for telemetry reception to complete
|
||||||
#define DSHOT_TELEMETRY_TIMEOUT 2000
|
#define DSHOT_TELEMETRY_TIMEOUT 2000
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbPacer_t bbPacers[MAX_MOTOR_PACERS]; // TIM1 or TIM8
|
|
||||||
FAST_DATA_ZERO_INIT int usedMotorPacers = 0;
|
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbPort_t bbPorts[MAX_SUPPORTED_MOTOR_PORTS];
|
|
||||||
FAST_DATA_ZERO_INIT int usedMotorPorts;
|
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
|
||||||
|
|
||||||
dshotBitbangStatus_e bbStatus;
|
|
||||||
|
|
||||||
// For MCUs that use MPU to control DMA coherency, there might be a performance hit
|
// For MCUs that use MPU to control DMA coherency, there might be a performance hit
|
||||||
// on manipulating input buffer content especially if it is read multiple times,
|
// on manipulating input buffer content especially if it is read multiple times,
|
||||||
// as the buffer region is attributed as not cachable.
|
// as the buffer region is attributed as not cachable.
|
||||||
|
@ -523,7 +513,7 @@ static bool bbDecodeTelemetry(void)
|
||||||
SCB_InvalidateDCache_by_Addr((uint32_t *)bbPort->portInputBuffer, DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES);
|
SCB_InvalidateDCache_by_Addr((uint32_t *)bbPort->portInputBuffer, DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
#ifdef APM32F4
|
#ifdef APM32F4
|
||||||
uint32_t rawValue = decode_bb_bitband(
|
uint32_t rawValue = decode_bb_bitband(
|
||||||
bbMotors[motorIndex].bbPort->portInputBuffer,
|
bbMotors[motorIndex].bbPort->portInputBuffer,
|
||||||
|
@ -606,7 +596,7 @@ static void bbUpdateComplete(void)
|
||||||
// If there is a dshot command loaded up, time it correctly with motor update
|
// If there is a dshot command loaded up, time it correctly with motor update
|
||||||
|
|
||||||
if (!dshotCommandQueueEmpty()) {
|
if (!dshotCommandQueueEmpty()) {
|
||||||
if (!dshotCommandOutputIsEnabled(motorCount)) {
|
if (!dshotCommandOutputIsEnabled(dshotMotorCount)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -641,7 +631,7 @@ static void bbUpdateComplete(void)
|
||||||
|
|
||||||
static bool bbEnableMotors(void)
|
static bool bbEnableMotors(void)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < dshotMotorCount; i++) {
|
||||||
if (bbMotors[i].configured) {
|
if (bbMotors[i].configured) {
|
||||||
IOConfigGPIO(bbMotors[i].io, bbMotors[i].iocfg);
|
IOConfigGPIO(bbMotors[i].io, bbMotors[i].iocfg);
|
||||||
}
|
}
|
||||||
|
@ -668,7 +658,7 @@ static void bbPostInit(void)
|
||||||
{
|
{
|
||||||
bbFindPacerTimer();
|
bbFindPacerTimer();
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
|
|
||||||
if (!bbMotorConfig(bbMotors[motorIndex].io, motorIndex, motorProtocol, bbMotors[motorIndex].output)) {
|
if (!bbMotorConfig(bbMotors[motorIndex].io, motorIndex, motorProtocol, bbMotors[motorIndex].output)) {
|
||||||
return;
|
return;
|
||||||
|
@ -701,18 +691,18 @@ dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||||
return bbStatus;
|
return bbStatus;
|
||||||
}
|
}
|
||||||
|
|
||||||
void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
bool dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||||
{
|
{
|
||||||
dbgPinLo(0);
|
dbgPinLo(0);
|
||||||
dbgPinLo(1);
|
dbgPinLo(1);
|
||||||
|
|
||||||
if (!device || !motorConfig) {
|
if (!device || !motorConfig) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motorProtocol = motorConfig->motorProtocol;
|
motorProtocol = motorConfig->motorProtocol;
|
||||||
device->vTable = &bbVTable;
|
device->vTable = &bbVTable;
|
||||||
motorCount = device->count;
|
dshotMotorCount = device->count;
|
||||||
bbStatus = DSHOT_BITBANG_STATUS_OK;
|
bbStatus = DSHOT_BITBANG_STATUS_OK;
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
@ -721,7 +711,7 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
|
|
||||||
memset(bbOutputBuffer, 0, sizeof(bbOutputBuffer));
|
memset(bbOutputBuffer, 0, sizeof(bbOutputBuffer));
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||||
const timerHardware_t *timerHardware = timerGetConfiguredByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
const timerHardware_t *timerHardware = timerGetConfiguredByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
||||||
const IO_t io = IOGetByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
const IO_t io = IOGetByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
||||||
|
@ -738,9 +728,9 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
if (!IOIsFreeOrPreinit(io)) {
|
if (!IOIsFreeOrPreinit(io)) {
|
||||||
/* not enough motors initialised for the mixer or a break in the motors */
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
device->vTable = NULL;
|
device->vTable = NULL;
|
||||||
motorCount = 0;
|
dshotMotorCount = 0;
|
||||||
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
int pinIndex = IO_GPIOPinIdx(io);
|
int pinIndex = IO_GPIOPinIdx(io);
|
||||||
|
@ -760,6 +750,7 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
IOHi(io);
|
IOHi(io);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // USE_DSHOT_BITBANG
|
#endif // USE_DSHOT_BITBANG
|
||||||
|
|
|
@ -35,8 +35,6 @@
|
||||||
|
|
||||||
#include "pg/motor.h"
|
#include "pg/motor.h"
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
|
||||||
|
|
||||||
static void pwmOCConfig(TMR_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
static void pwmOCConfig(TMR_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
||||||
{
|
{
|
||||||
TMR_HandleTypeDef* Handle = timerFindTimerHandle(tim);
|
TMR_HandleTypeDef* Handle = timerFindTimerHandle(tim);
|
||||||
|
@ -85,7 +83,6 @@ void pwmOutConfig(timerChannel_t *channel, const timerHardware_t *timerHardware,
|
||||||
*channel->ccr = 0;
|
*channel->ccr = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
static int motorCount = 0;
|
|
||||||
static bool useContinuousUpdate = true;
|
static bool useContinuousUpdate = true;
|
||||||
|
|
||||||
static void pwmWriteStandard(uint8_t index, float value)
|
static void pwmWriteStandard(uint8_t index, float value)
|
||||||
|
@ -96,7 +93,7 @@ static void pwmWriteStandard(uint8_t index, float value)
|
||||||
|
|
||||||
void pwmShutdownPulsesForAllMotors(void)
|
void pwmShutdownPulsesForAllMotors(void)
|
||||||
{
|
{
|
||||||
for (int index = 0; index < motorCount; index++) {
|
for (int index = 0; index < pwmMotorCount; index++) {
|
||||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
||||||
if (motors[index].channel.ccr) {
|
if (motors[index].channel.ccr) {
|
||||||
*motors[index].channel.ccr = 0;
|
*motors[index].channel.ccr = 0;
|
||||||
|
@ -113,7 +110,7 @@ static motorVTable_t motorPwmVTable;
|
||||||
bool pwmEnableMotors(void)
|
bool pwmEnableMotors(void)
|
||||||
{
|
{
|
||||||
/* check motors can be enabled */
|
/* check motors can be enabled */
|
||||||
return motorCount > 0;
|
return pwmMotorCount > 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pwmIsMotorEnabled(unsigned index)
|
bool pwmIsMotorEnabled(unsigned index)
|
||||||
|
@ -127,7 +124,7 @@ static void pwmCompleteMotorUpdate(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int index = 0; index < motorCount; index++) {
|
for (int index = 0; index < pwmMotorCount; index++) {
|
||||||
if (motors[index].forceOverflow) {
|
if (motors[index].forceOverflow) {
|
||||||
timerForceOverflow(motors[index].channel.tim);
|
timerForceOverflow(motors[index].channel.tim);
|
||||||
}
|
}
|
||||||
|
@ -162,15 +159,15 @@ static motorVTable_t motorPwmVTable = {
|
||||||
.isMotorIdle = NULL,
|
.isMotorIdle = NULL,
|
||||||
};
|
};
|
||||||
|
|
||||||
void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
||||||
{
|
{
|
||||||
memset(motors, 0, sizeof(motors));
|
memset(motors, 0, sizeof(motors));
|
||||||
|
|
||||||
if (!device || !motorConfig) {
|
if (!device || !motorConfig) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motorCount = device->count;
|
pwmMotorCount = device->count;
|
||||||
device->vTable = &motorPwmVTable;
|
device->vTable = &motorPwmVTable;
|
||||||
|
|
||||||
useContinuousUpdate = motorConfig->useContinuousUpdate;
|
useContinuousUpdate = motorConfig->useContinuousUpdate;
|
||||||
|
@ -203,7 +200,7 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < pwmMotorCount; motorIndex++) {
|
||||||
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||||
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
||||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||||
|
@ -211,9 +208,9 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
if (timerHardware == NULL) {
|
if (timerHardware == NULL) {
|
||||||
/* not enough motors initialised for the mixer or a break in the motors */
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
device->vTable = NULL;
|
device->vTable = NULL;
|
||||||
motorCount = 0;
|
pwmMotorCount = 0;
|
||||||
/* TODO: block arming and add reason system cannot arm */
|
/* TODO: block arming and add reason system cannot arm */
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
motors[motorIndex].io = IOGetByTag(tag);
|
||||||
|
@ -251,6 +248,8 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||||
motors[motorIndex].enabled = true;
|
motors[motorIndex].enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
pwmOutputPort_t *pwmGetMotors(void)
|
pwmOutputPort_t *pwmGetMotors(void)
|
||||||
|
|
|
@ -127,7 +127,7 @@ FAST_CODE static void pwmDshotSetDirectionInput(
|
||||||
FAST_CODE void pwmCompleteDshotMotorUpdate(void)
|
FAST_CODE void pwmCompleteDshotMotorUpdate(void)
|
||||||
{
|
{
|
||||||
/* If there is a dshot command loaded up, time it correctly with motor update*/
|
/* If there is a dshot command loaded up, time it correctly with motor update*/
|
||||||
if (!dshotCommandQueueEmpty() && !dshotCommandOutputIsEnabled(motorCount)) {
|
if (!dshotCommandQueueEmpty() && !dshotCommandOutputIsEnabled(dshotMotorCount)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -49,16 +49,6 @@
|
||||||
// Maximum time to wait for telemetry reception to complete
|
// Maximum time to wait for telemetry reception to complete
|
||||||
#define DSHOT_TELEMETRY_TIMEOUT 2000
|
#define DSHOT_TELEMETRY_TIMEOUT 2000
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbPacer_t bbPacers[MAX_MOTOR_PACERS]; // TIM1 or TIM8
|
|
||||||
FAST_DATA_ZERO_INIT int usedMotorPacers = 0;
|
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbPort_t bbPorts[MAX_SUPPORTED_MOTOR_PORTS];
|
|
||||||
FAST_DATA_ZERO_INIT int usedMotorPorts;
|
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
|
||||||
|
|
||||||
dshotBitbangStatus_e bbStatus;
|
|
||||||
|
|
||||||
// For MCUs that use MPU to control DMA coherency, there might be a performance hit
|
// For MCUs that use MPU to control DMA coherency, there might be a performance hit
|
||||||
// on manipulating input buffer content especially if it is read multiple times,
|
// on manipulating input buffer content especially if it is read multiple times,
|
||||||
// as the buffer region is attributed as not cachable.
|
// as the buffer region is attributed as not cachable.
|
||||||
|
@ -503,7 +493,7 @@ static bool bbDecodeTelemetry(void)
|
||||||
SCB_InvalidateDCache_by_Addr((uint32_t *)bbPort->portInputBuffer, DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES);
|
SCB_InvalidateDCache_by_Addr((uint32_t *)bbPort->portInputBuffer, DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
|
|
||||||
uint32_t rawValue = decode_bb_bitband(
|
uint32_t rawValue = decode_bb_bitband(
|
||||||
bbMotors[motorIndex].bbPort->portInputBuffer,
|
bbMotors[motorIndex].bbPort->portInputBuffer,
|
||||||
|
@ -586,7 +576,7 @@ static void bbUpdateComplete(void)
|
||||||
// If there is a dshot command loaded up, time it correctly with motor update
|
// If there is a dshot command loaded up, time it correctly with motor update
|
||||||
|
|
||||||
if (!dshotCommandQueueEmpty()) {
|
if (!dshotCommandQueueEmpty()) {
|
||||||
if (!dshotCommandOutputIsEnabled(motorCount)) {
|
if (!dshotCommandOutputIsEnabled(dshotMotorCount)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -633,7 +623,7 @@ static void bbUpdateComplete(void)
|
||||||
|
|
||||||
static bool bbEnableMotors(void)
|
static bool bbEnableMotors(void)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < dshotMotorCount; i++) {
|
||||||
if (bbMotors[i].configured) {
|
if (bbMotors[i].configured) {
|
||||||
IOConfigGPIO(bbMotors[i].io, bbMotors[i].iocfg);
|
IOConfigGPIO(bbMotors[i].io, bbMotors[i].iocfg);
|
||||||
}
|
}
|
||||||
|
@ -660,7 +650,7 @@ static void bbPostInit(void)
|
||||||
{
|
{
|
||||||
bbFindPacerTimer();
|
bbFindPacerTimer();
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
|
|
||||||
if (!bbMotorConfig(bbMotors[motorIndex].io, motorIndex, motorProtocol, bbMotors[motorIndex].output)) {
|
if (!bbMotorConfig(bbMotors[motorIndex].io, motorIndex, motorProtocol, bbMotors[motorIndex].output)) {
|
||||||
return;
|
return;
|
||||||
|
@ -693,14 +683,14 @@ dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||||
return bbStatus;
|
return bbStatus;
|
||||||
}
|
}
|
||||||
|
|
||||||
void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
bool dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||||
{
|
{
|
||||||
dbgPinLo(0);
|
dbgPinLo(0);
|
||||||
dbgPinLo(1);
|
dbgPinLo(1);
|
||||||
|
|
||||||
motorProtocol = motorConfig->motorProtocol;
|
motorProtocol = motorConfig->motorProtocol;
|
||||||
device->vTable = &bbVTable;
|
device->vTable = &bbVTable;
|
||||||
motorCount = device->count;
|
dshotMotorCount = device->count;
|
||||||
|
|
||||||
bbStatus = DSHOT_BITBANG_STATUS_OK;
|
bbStatus = DSHOT_BITBANG_STATUS_OK;
|
||||||
|
|
||||||
|
@ -710,7 +700,7 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
|
|
||||||
memset(bbOutputBuffer, 0, sizeof(bbOutputBuffer));
|
memset(bbOutputBuffer, 0, sizeof(bbOutputBuffer));
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||||
const timerHardware_t *timerHardware = timerGetConfiguredByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
const timerHardware_t *timerHardware = timerGetConfiguredByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
||||||
const IO_t io = IOGetByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
const IO_t io = IOGetByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
||||||
|
@ -728,8 +718,8 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
/* not enough motors initialised for the mixer or a break in the motors */
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
||||||
device->vTable = NULL;
|
device->vTable = NULL;
|
||||||
motorCount = 0;
|
dshotMotorCount = 0;
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
int pinIndex = IO_GPIOPinIdx(io);
|
int pinIndex = IO_GPIOPinIdx(io);
|
||||||
|
@ -747,6 +737,7 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
IOHi(io);
|
IOHi(io);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // USE_DSHOT_BB
|
#endif // USE_DSHOT_BB
|
||||||
|
|
|
@ -28,16 +28,13 @@
|
||||||
#ifdef USE_PWM_OUTPUT
|
#ifdef USE_PWM_OUTPUT
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/motor.h"
|
#include "drivers/motor_impl.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
#include "pg/motor.h"
|
#include "pg/motor.h"
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
|
||||||
static int motorCount = 0;
|
|
||||||
|
|
||||||
static void pwmOCConfig(tmr_type *tim, uint8_t channel, uint16_t value, uint8_t output)
|
static void pwmOCConfig(tmr_type *tim, uint8_t channel, uint16_t value, uint8_t output)
|
||||||
{
|
{
|
||||||
tmr_output_config_type tmr_OCInitStruct;
|
tmr_output_config_type tmr_OCInitStruct;
|
||||||
|
@ -77,7 +74,7 @@ void pwmOutConfig(timerChannel_t *channel, const timerHardware_t *timerHardware,
|
||||||
*channel->ccr = 0;
|
*channel->ccr = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
static FAST_DATA_ZERO_INIT motorDevice_t *motorPwmDevice;
|
static FAST_DATA_ZERO_INIT motorDevice_t *pwmMotorDevice;
|
||||||
|
|
||||||
static void pwmWriteStandard(uint8_t index, float value)
|
static void pwmWriteStandard(uint8_t index, float value)
|
||||||
{
|
{
|
||||||
|
@ -87,7 +84,7 @@ static void pwmWriteStandard(uint8_t index, float value)
|
||||||
|
|
||||||
void pwmShutdownPulsesForAllMotors(void)
|
void pwmShutdownPulsesForAllMotors(void)
|
||||||
{
|
{
|
||||||
for (int index = 0; index < motorCount; index++) {
|
for (int index = 0; index < pwmMotorCount; index++) {
|
||||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
||||||
if (motors[index].channel.ccr) {
|
if (motors[index].channel.ccr) {
|
||||||
*motors[index].channel.ccr = 0;
|
*motors[index].channel.ccr = 0;
|
||||||
|
@ -104,7 +101,7 @@ static motorVTable_t motorPwmVTable;
|
||||||
bool pwmEnableMotors(void)
|
bool pwmEnableMotors(void)
|
||||||
{
|
{
|
||||||
/* check motors can be enabled */
|
/* check motors can be enabled */
|
||||||
return (motorPwmDevice->vTable);
|
return (pwmMotorDevice->vTable);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pwmIsMotorEnabled(unsigned index)
|
bool pwmIsMotorEnabled(unsigned index)
|
||||||
|
@ -120,7 +117,7 @@ static void pwmCompleteMotorUpdate(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int index = 0; index < motorCount; index++) {
|
for (int index = 0; index < pwmMotorCount; index++) {
|
||||||
if (motors[index].forceOverflow) {
|
if (motors[index].forceOverflow) {
|
||||||
timerForceOverflow(motors[index].channel.tim);
|
timerForceOverflow(motors[index].channel.tim);
|
||||||
}
|
}
|
||||||
|
@ -155,17 +152,17 @@ static motorVTable_t motorPwmVTable = {
|
||||||
.isMotorIdle = NULL,
|
.isMotorIdle = NULL,
|
||||||
};
|
};
|
||||||
|
|
||||||
void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
||||||
{
|
{
|
||||||
memset(motors, 0, sizeof(motors));
|
memset(motors, 0, sizeof(motors));
|
||||||
|
|
||||||
if (!device) {
|
if (!device) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
device->vTable = &motorPwmVTable;
|
device->vTable = &motorPwmVTable;
|
||||||
motorPwmDevice = device;
|
pwmMotorDevice = device;
|
||||||
motorCount = device->count;
|
pwmMotorCount = device->count;
|
||||||
useContinuousUpdate = motorConfig->useContinuousUpdate;
|
useContinuousUpdate = motorConfig->useContinuousUpdate;
|
||||||
|
|
||||||
float sMin = 0;
|
float sMin = 0;
|
||||||
|
@ -197,7 +194,7 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < pwmMotorCount; motorIndex++) {
|
||||||
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||||
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
||||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||||
|
@ -205,9 +202,9 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
if (timerHardware == NULL) {
|
if (timerHardware == NULL) {
|
||||||
/* not enough motors initialised for the mixer or a break in the motors */
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
device->vTable = NULL;
|
device->vTable = NULL;
|
||||||
motorCount = 0;
|
pwmMotorCount = 0;
|
||||||
/* TODO: block arming and add reason system cannot arm */
|
/* TODO: block arming and add reason system cannot arm */
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
motors[motorIndex].io = IOGetByTag(tag);
|
||||||
|
@ -245,6 +242,7 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||||
motors[motorIndex].enabled = true;
|
motors[motorIndex].enabled = true;
|
||||||
}
|
}
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
pwmOutputPort_t *pwmGetMotors(void)
|
pwmOutputPort_t *pwmGetMotors(void)
|
||||||
|
|
|
@ -249,7 +249,7 @@ void pwmCompleteDshotMotorUpdate(void)
|
||||||
{
|
{
|
||||||
// If there is a dshot command loaded up, time it correctly with motor update
|
// If there is a dshot command loaded up, time it correctly with motor update
|
||||||
if (!dshotCommandQueueEmpty()) {
|
if (!dshotCommandQueueEmpty()) {
|
||||||
if (!dshotCommandOutputIsEnabled(motorCount)) {
|
if (!dshotCommandOutputIsEnabled(dshotMotorCount)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/motor.h"
|
#include "drivers/motor_impl.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_tcp.h"
|
#include "drivers/serial_tcp.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
@ -504,7 +504,6 @@ int timeval_sub(struct timespec *result, struct timespec *x, struct timespec *y)
|
||||||
}
|
}
|
||||||
|
|
||||||
// PWM part
|
// PWM part
|
||||||
pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
|
||||||
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
||||||
|
|
||||||
// real value to send
|
// real value to send
|
||||||
|
@ -521,7 +520,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static motorDevice_t motorPwmDevice; // Forward
|
static motorDevice_t pwmMotorDevice; // Forward
|
||||||
|
|
||||||
pwmOutputPort_t *pwmGetMotors(void)
|
pwmOutputPort_t *pwmGetMotors(void)
|
||||||
{
|
{
|
||||||
|
@ -540,12 +539,12 @@ static uint16_t pwmConvertToExternal(float motorValue)
|
||||||
|
|
||||||
static void pwmDisableMotors(void)
|
static void pwmDisableMotors(void)
|
||||||
{
|
{
|
||||||
motorPwmDevice.enabled = false;
|
pwmMotorDevice.enabled = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool pwmEnableMotors(void)
|
static bool pwmEnableMotors(void)
|
||||||
{
|
{
|
||||||
motorPwmDevice.enabled = true;
|
pwmMotorDevice.enabled = true;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -572,7 +571,7 @@ static void pwmWriteMotorInt(uint8_t index, uint16_t value)
|
||||||
|
|
||||||
static void pwmShutdownPulsesForAllMotors(void)
|
static void pwmShutdownPulsesForAllMotors(void)
|
||||||
{
|
{
|
||||||
motorPwmDevice.enabled = false;
|
pwmMotorDevice.enabled = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pwmIsMotorEnabled(unsigned index)
|
bool pwmIsMotorEnabled(unsigned index)
|
||||||
|
@ -628,15 +627,15 @@ static const motorVTable_t vTable = {
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t _idlePulse)
|
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t _idlePulse)
|
||||||
{
|
{
|
||||||
UNUSED(motorConfig);
|
UNUSED(motorConfig);
|
||||||
|
|
||||||
if (!device) {
|
if (!device) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
device->vTable = &vTable;
|
device->vTable = &vTable;
|
||||||
uint8_t motorCount = device->count;
|
const uint8_t motorCount = device->count;
|
||||||
printf("Initialized motor count %d\n", motorCount);
|
printf("Initialized motor count %d\n", motorCount);
|
||||||
pwmRawPkt.motorCount = motorCount;
|
pwmRawPkt.motorCount = motorCount;
|
||||||
|
|
||||||
|
@ -645,6 +644,8 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||||
motors[motorIndex].enabled = true;
|
motors[motorIndex].enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// ADC part
|
// ADC part
|
||||||
|
|
|
@ -56,16 +56,6 @@
|
||||||
// Maximum time to wait for telemetry reception to complete
|
// Maximum time to wait for telemetry reception to complete
|
||||||
#define DSHOT_TELEMETRY_TIMEOUT 2000
|
#define DSHOT_TELEMETRY_TIMEOUT 2000
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbPacer_t bbPacers[MAX_MOTOR_PACERS]; // TIM1 or TIM8
|
|
||||||
FAST_DATA_ZERO_INIT int usedMotorPacers = 0;
|
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbPort_t bbPorts[MAX_SUPPORTED_MOTOR_PORTS];
|
|
||||||
FAST_DATA_ZERO_INIT int usedMotorPorts;
|
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
|
||||||
|
|
||||||
dshotBitbangStatus_e bbStatus;
|
|
||||||
|
|
||||||
// For MCUs that use MPU to control DMA coherency, there might be a performance hit
|
// For MCUs that use MPU to control DMA coherency, there might be a performance hit
|
||||||
// on manipulating input buffer content especially if it is read multiple times,
|
// on manipulating input buffer content especially if it is read multiple times,
|
||||||
// as the buffer region is attributed as not cachable.
|
// as the buffer region is attributed as not cachable.
|
||||||
|
@ -552,7 +542,7 @@ static bool bbDecodeTelemetry(void)
|
||||||
SCB_InvalidateDCache_by_Addr((uint32_t *)bbPort->portInputBuffer, DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES);
|
SCB_InvalidateDCache_by_Addr((uint32_t *)bbPort->portInputBuffer, DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
#ifdef STM32F4
|
#ifdef STM32F4
|
||||||
uint32_t rawValue = decode_bb_bitband(
|
uint32_t rawValue = decode_bb_bitband(
|
||||||
bbMotors[motorIndex].bbPort->portInputBuffer,
|
bbMotors[motorIndex].bbPort->portInputBuffer,
|
||||||
|
@ -635,7 +625,7 @@ static void bbUpdateComplete(void)
|
||||||
// If there is a dshot command loaded up, time it correctly with motor update
|
// If there is a dshot command loaded up, time it correctly with motor update
|
||||||
|
|
||||||
if (!dshotCommandQueueEmpty()) {
|
if (!dshotCommandQueueEmpty()) {
|
||||||
if (!dshotCommandOutputIsEnabled(motorCount)) {
|
if (!dshotCommandOutputIsEnabled(dshotMotorCount)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -673,7 +663,7 @@ static void bbUpdateComplete(void)
|
||||||
|
|
||||||
static bool bbEnableMotors(void)
|
static bool bbEnableMotors(void)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < dshotMotorCount; i++) {
|
||||||
if (bbMotors[i].configured) {
|
if (bbMotors[i].configured) {
|
||||||
IOConfigGPIO(bbMotors[i].io, bbMotors[i].iocfg);
|
IOConfigGPIO(bbMotors[i].io, bbMotors[i].iocfg);
|
||||||
}
|
}
|
||||||
|
@ -700,7 +690,7 @@ static void bbPostInit(void)
|
||||||
{
|
{
|
||||||
bbFindPacerTimer();
|
bbFindPacerTimer();
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
|
|
||||||
if (!bbMotorConfig(bbMotors[motorIndex].io, motorIndex, motorProtocol, bbMotors[motorIndex].output)) {
|
if (!bbMotorConfig(bbMotors[motorIndex].io, motorIndex, motorProtocol, bbMotors[motorIndex].output)) {
|
||||||
return;
|
return;
|
||||||
|
@ -733,19 +723,19 @@ dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||||
return bbStatus;
|
return bbStatus;
|
||||||
}
|
}
|
||||||
|
|
||||||
void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
bool dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||||
{
|
{
|
||||||
dbgPinLo(0);
|
dbgPinLo(0);
|
||||||
dbgPinLo(1);
|
dbgPinLo(1);
|
||||||
|
|
||||||
if (!device || !motorConfig) {
|
if (!device || !motorConfig) {
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motorProtocol = motorConfig->motorProtocol;
|
motorProtocol = motorConfig->motorProtocol;
|
||||||
device->vTable = &bbVTable;
|
device->vTable = &bbVTable;
|
||||||
|
|
||||||
motorCount = device->count;
|
dshotMotorCount = device->count;
|
||||||
bbStatus = DSHOT_BITBANG_STATUS_OK;
|
bbStatus = DSHOT_BITBANG_STATUS_OK;
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
@ -754,7 +744,7 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
|
|
||||||
memset(bbOutputBuffer, 0, sizeof(bbOutputBuffer));
|
memset(bbOutputBuffer, 0, sizeof(bbOutputBuffer));
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||||
const timerHardware_t *timerHardware = timerGetConfiguredByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
const timerHardware_t *timerHardware = timerGetConfiguredByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
||||||
const IO_t io = IOGetByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
const IO_t io = IOGetByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
||||||
|
@ -771,9 +761,9 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
if (!IOIsFreeOrPreinit(io)) {
|
if (!IOIsFreeOrPreinit(io)) {
|
||||||
/* not enough motors initialised for the mixer or a break in the motors */
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
device->vTable = NULL;
|
device->vTable = NULL;
|
||||||
motorCount = 0;
|
dshotMotorCount = 0;
|
||||||
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
int pinIndex = IO_GPIOPinIdx(io);
|
int pinIndex = IO_GPIOPinIdx(io);
|
||||||
|
@ -796,6 +786,7 @@ void dshotBitbangDevInit(motorDevice_t *device, const motorDevConfig_t *motorCon
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // USE_DSHOT_BB
|
#endif // USE_DSHOT_BB
|
||||||
|
|
|
@ -144,7 +144,7 @@ void pwmCompleteDshotMotorUpdate(void)
|
||||||
{
|
{
|
||||||
/* If there is a dshot command loaded up, time it correctly with motor update*/
|
/* If there is a dshot command loaded up, time it correctly with motor update*/
|
||||||
if (!dshotCommandQueueEmpty()) {
|
if (!dshotCommandQueueEmpty()) {
|
||||||
if (!dshotCommandOutputIsEnabled(motorCount)) {
|
if (!dshotCommandOutputIsEnabled(pwmMotorCount)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -138,7 +138,7 @@ FAST_CODE static void pwmDshotSetDirectionInput(
|
||||||
FAST_CODE void pwmCompleteDshotMotorUpdate(void)
|
FAST_CODE void pwmCompleteDshotMotorUpdate(void)
|
||||||
{
|
{
|
||||||
/* If there is a dshot command loaded up, time it correctly with motor update*/
|
/* If there is a dshot command loaded up, time it correctly with motor update*/
|
||||||
if (!dshotCommandQueueEmpty() && !dshotCommandOutputIsEnabled(motorCount)) {
|
if (!dshotCommandQueueEmpty() && !dshotCommandOutputIsEnabled(dshotMotorCount)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -34,9 +34,6 @@
|
||||||
|
|
||||||
#include "drivers/motor_impl.h"
|
#include "drivers/motor_impl.h"
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
|
||||||
|
|
||||||
static int motorCount = 0;
|
|
||||||
static bool useContinuousUpdate = true;
|
static bool useContinuousUpdate = true;
|
||||||
|
|
||||||
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
||||||
|
@ -118,7 +115,7 @@ static void pwmWriteStandard(uint8_t index, float value)
|
||||||
|
|
||||||
void pwmShutdownPulsesForAllMotors(void)
|
void pwmShutdownPulsesForAllMotors(void)
|
||||||
{
|
{
|
||||||
for (int index = 0; motorCount; index++) {
|
for (int index = 0; pwmMotorCount; index++) {
|
||||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
||||||
if (motors[index].channel.ccr) {
|
if (motors[index].channel.ccr) {
|
||||||
*motors[index].channel.ccr = 0;
|
*motors[index].channel.ccr = 0;
|
||||||
|
@ -134,7 +131,7 @@ void pwmDisableMotors(void)
|
||||||
bool pwmEnableMotors(void)
|
bool pwmEnableMotors(void)
|
||||||
{
|
{
|
||||||
/* check motors can be enabled */
|
/* check motors can be enabled */
|
||||||
return motorCount > 0;
|
return pwmMotorCount > 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pwmIsMotorEnabled(unsigned index)
|
bool pwmIsMotorEnabled(unsigned index)
|
||||||
|
@ -148,7 +145,7 @@ static void pwmCompleteMotorUpdate(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int index = 0; motorCount; index++) {
|
for (int index = 0; pwmMotorCount; index++) {
|
||||||
if (motors[index].forceOverflow) {
|
if (motors[index].forceOverflow) {
|
||||||
timerForceOverflow(motors[index].channel.tim);
|
timerForceOverflow(motors[index].channel.tim);
|
||||||
}
|
}
|
||||||
|
@ -183,11 +180,11 @@ static const motorVTable_t motorPwmVTable = {
|
||||||
.isMotorIdle = NULL,
|
.isMotorIdle = NULL,
|
||||||
};
|
};
|
||||||
|
|
||||||
void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig, uint16_t idlePulse)
|
||||||
{
|
{
|
||||||
memset(motors, 0, sizeof(motors));
|
memset(motors, 0, sizeof(motors));
|
||||||
|
|
||||||
motorCount = device->count;
|
pwmMotorCount = device->count;
|
||||||
device->vTable = &motorPwmVTable;
|
device->vTable = &motorPwmVTable;
|
||||||
useContinuousUpdate = motorConfig->useContinuousUpdate;
|
useContinuousUpdate = motorConfig->useContinuousUpdate;
|
||||||
|
|
||||||
|
@ -220,7 +217,7 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < pwmMotorCount; motorIndex++) {
|
||||||
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||||
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
||||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||||
|
@ -228,9 +225,9 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
if (timerHardware == NULL) {
|
if (timerHardware == NULL) {
|
||||||
/* not enough motors initialised for the mixer or a break in the motors */
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
device->vTable = NULL;
|
device->vTable = NULL;
|
||||||
motorCount = 0;
|
pwmMotorCount = 0;
|
||||||
/* TODO: block arming and add reason system cannot arm */
|
/* TODO: block arming and add reason system cannot arm */
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
motors[motorIndex].io = IOGetByTag(tag);
|
||||||
|
@ -269,6 +266,7 @@ void motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
motors[motorIndex].enabled = true;
|
motors[motorIndex].enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
pwmOutputPort_t *pwmGetMotors(void)
|
pwmOutputPort_t *pwmGetMotors(void)
|
||||||
|
|
|
@ -229,6 +229,7 @@ extern FAST_DATA_ZERO_INIT int usedMotorPorts;
|
||||||
extern FAST_DATA_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
extern FAST_DATA_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
extern uint8_t bbPuPdMode;
|
extern uint8_t bbPuPdMode;
|
||||||
|
extern dshotBitbangStatus_e bbStatus;
|
||||||
|
|
||||||
// DMA buffers
|
// DMA buffers
|
||||||
// Note that we are not sharing input and output buffers,
|
// Note that we are not sharing input and output buffers,
|
||||||
|
|
|
@ -21,6 +21,16 @@
|
||||||
|
|
||||||
#include "dshot_bitbang_impl.h"
|
#include "dshot_bitbang_impl.h"
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT bbPacer_t bbPacers[MAX_MOTOR_PACERS]; // TIM1 or TIM8
|
||||||
|
FAST_DATA_ZERO_INIT int usedMotorPacers = 0;
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT bbPort_t bbPorts[MAX_SUPPORTED_MOTOR_PORTS];
|
||||||
|
FAST_DATA_ZERO_INIT int usedMotorPorts;
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
|
dshotBitbangStatus_e bbStatus;
|
||||||
|
|
||||||
void bbDshotRequestTelemetry(unsigned motorIndex)
|
void bbDshotRequestTelemetry(unsigned motorIndex)
|
||||||
{
|
{
|
||||||
if (motorIndex >= ARRAYLEN(bbMotors)) {
|
if (motorIndex >= ARRAYLEN(bbMotors)) {
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
#include "pwm_output_dshot_shared.h"
|
#include "pwm_output_dshot_shared.h"
|
||||||
#include "drivers/dshot.h"
|
#include "drivers/dshot.h"
|
||||||
#include "dshot_dpwm.h"
|
#include "dshot_dpwm.h"
|
||||||
#include "drivers/motor.h"
|
#include "drivers/motor_impl.h"
|
||||||
|
|
||||||
#include "pg/motor.h"
|
#include "pg/motor.h"
|
||||||
|
|
||||||
|
@ -111,7 +111,7 @@ static void dshotPwmDisableMotors(void)
|
||||||
|
|
||||||
static bool dshotPwmEnableMotors(void)
|
static bool dshotPwmEnableMotors(void)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < dshotMotorCount; i++) {
|
||||||
motorDmaOutput_t *motor = getMotorDmaOutput(i);
|
motorDmaOutput_t *motor = getMotorDmaOutput(i);
|
||||||
const IO_t motorIO = IOGetByTag(motor->timerHardware->tag);
|
const IO_t motorIO = IOGetByTag(motor->timerHardware->tag);
|
||||||
IOConfigGPIOAF(motorIO, motor->iocfg, motor->timerHardware->alternateFunction);
|
IOConfigGPIOAF(motorIO, motor->iocfg, motor->timerHardware->alternateFunction);
|
||||||
|
@ -152,10 +152,10 @@ static const motorVTable_t dshotPwmVTable = {
|
||||||
.isMotorIdle = pwmDshotIsMotorIdle,
|
.isMotorIdle = pwmDshotIsMotorIdle,
|
||||||
};
|
};
|
||||||
|
|
||||||
void dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||||
{
|
{
|
||||||
device->vTable = &dshotPwmVTable;
|
device->vTable = &dshotPwmVTable;
|
||||||
motorCount = device->count;
|
dshotMotorCount = device->count;
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
useDshotTelemetry = motorConfig->useDshotTelemetry;
|
useDshotTelemetry = motorConfig->useDshotTelemetry;
|
||||||
#endif
|
#endif
|
||||||
|
@ -175,7 +175,7 @@ void dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < dshotMotorCount; motorIndex++) {
|
||||||
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||||
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
const ioTag_t tag = motorConfig->ioTags[reorderedMotorIndex];
|
||||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||||
|
@ -196,11 +196,12 @@ void dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||||
}
|
}
|
||||||
|
|
||||||
/* not enough motors initialised for the mixer or a break in the motors */
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
device->vTable = NULL;
|
dshotMotorCount = 0;
|
||||||
motorCount = 0;
|
|
||||||
/* TODO: block arming and add reason system cannot arm */
|
/* TODO: block arming and add reason system cannot arm */
|
||||||
return;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // USE_DSHOT
|
#endif // USE_DSHOT
|
||||||
|
|
|
@ -49,7 +49,6 @@
|
||||||
#include "pwm_output_dshot_shared.h"
|
#include "pwm_output_dshot_shared.h"
|
||||||
|
|
||||||
FAST_DATA_ZERO_INIT uint8_t dmaMotorTimerCount = 0;
|
FAST_DATA_ZERO_INIT uint8_t dmaMotorTimerCount = 0;
|
||||||
FAST_DATA_ZERO_INIT uint8_t motorCount = 0;
|
|
||||||
|
|
||||||
#ifdef STM32F7
|
#ifdef STM32F7
|
||||||
FAST_DATA_ZERO_INIT motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
|
FAST_DATA_ZERO_INIT motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
|
||||||
|
@ -216,7 +215,9 @@ static uint32_t decodeTelemetryPacket(const uint32_t buffer[], uint32_t count)
|
||||||
*/
|
*/
|
||||||
FAST_CODE_NOINLINE bool pwmTelemetryDecode(void)
|
FAST_CODE_NOINLINE bool pwmTelemetryDecode(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifndef USE_DSHOT_TELEMETRY
|
||||||
|
return true;
|
||||||
|
#else
|
||||||
if (!useDshotTelemetry) {
|
if (!useDshotTelemetry) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -226,7 +227,7 @@ FAST_CODE_NOINLINE bool pwmTelemetryDecode(void)
|
||||||
#endif
|
#endif
|
||||||
const timeUs_t currentUs = micros();
|
const timeUs_t currentUs = micros();
|
||||||
|
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < dshotMotorCount; i++) {
|
||||||
timeDelta_t usSinceInput = cmpTimeUs(currentUs, inputStampUs);
|
timeDelta_t usSinceInput = cmpTimeUs(currentUs, inputStampUs);
|
||||||
if (usSinceInput >= 0 && usSinceInput < dmaMotors[i].dshotTelemetryDeadtimeUs) {
|
if (usSinceInput >= 0 && usSinceInput < dmaMotors[i].dshotTelemetryDeadtimeUs) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -276,11 +277,9 @@ FAST_CODE_NOINLINE bool pwmTelemetryDecode(void)
|
||||||
|
|
||||||
dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED;
|
dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED;
|
||||||
inputStampUs = 0;
|
inputStampUs = 0;
|
||||||
dshotEnableChannels(motorCount);
|
dshotEnableChannels(dshotMotorCount);
|
||||||
|
|
||||||
|
|
||||||
#endif // USE_DSHOT_TELEMETRY
|
|
||||||
return true;
|
return true;
|
||||||
|
#endif // USE_DSHOT_TELEMETRY
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // USE_DSHOT
|
#endif // USE_DSHOT
|
||||||
|
|
|
@ -24,7 +24,6 @@
|
||||||
#include "dshot_dpwm.h"
|
#include "dshot_dpwm.h"
|
||||||
|
|
||||||
extern FAST_DATA_ZERO_INIT uint8_t dmaMotorTimerCount;
|
extern FAST_DATA_ZERO_INIT uint8_t dmaMotorTimerCount;
|
||||||
extern FAST_DATA_ZERO_INIT uint8_t motorCount;
|
|
||||||
|
|
||||||
extern FAST_DATA_ZERO_INIT motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
|
extern FAST_DATA_ZERO_INIT motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
|
||||||
extern FAST_DATA_ZERO_INIT motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];
|
extern FAST_DATA_ZERO_INIT motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue