Skip to content

Commit

Permalink
FIX: AT32 not reading ESC (betaflight#14220)
Browse files Browse the repository at this point in the history
  • Loading branch information
blckmn authored Jan 30, 2025
1 parent bfea69a commit 3dba5e6
Show file tree
Hide file tree
Showing 13 changed files with 75 additions and 82 deletions.
6 changes: 3 additions & 3 deletions src/main/drivers/pwm_output.c
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -53,12 +53,12 @@ IO_t pwmGetMotorIO(unsigned index)
if (index >= pwmMotorCount) {
return IO_NONE;
}
return motors[index].io;
return pwmMotors[index].io;
}

bool pwmIsMotorEnabled(unsigned index)
{
return motors[index].enabled;
return pwmMotors[index].enabled;
}

bool pwmEnableMotors(void)
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/pwm_output.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
8 changes: 0 additions & 8 deletions src/platform/APM32/dshot_bitbang.c
Original file line number Diff line number Diff line change
Expand Up @@ -669,14 +669,6 @@ static void bbPostInit(void)
}
}

static IO_t bbGetMotorIO(unsigned index)
{
if (index >= dshotMotorCount) {
return IO_NONE;
}
return bbMotors[index].io;
}

static motorVTable_t bbVTable = {
.postInit = bbPostInit,
.enable = bbEnableMotors,
Expand Down
34 changes: 17 additions & 17 deletions src/platform/APM32/pwm_output_apm32.c
Original file line number Diff line number Diff line change
Expand Up @@ -90,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;
}
}
}
Expand All @@ -117,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;
}
}

Expand Down Expand Up @@ -154,7 +154,7 @@ static motorVTable_t motorPwmVTable = {

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;
Expand Down Expand Up @@ -206,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
Expand All @@ -226,28 +226,28 @@ 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
Expand Down
3 changes: 2 additions & 1 deletion src/platform/AT32/dshot_bitbang.c
Original file line number Diff line number Diff line change
Expand Up @@ -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++) {
Expand Down Expand Up @@ -677,6 +677,7 @@ static motorVTable_t bbVTable = {
.shutdown = bbShutdown,
.isMotorIdle = bbDshotIsMotorIdle,
.requestTelemetry = bbDshotRequestTelemetry,
.getMotorIO = bbGetMotorIO,
};

dshotBitbangStatus_e dshotBitbangGetStatus(void)
Expand Down
12 changes: 1 addition & 11 deletions src/platform/AT32/io_at32.c
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
34 changes: 17 additions & 17 deletions src/platform/AT32/pwm_output_at32bsp.c
Original file line number Diff line number Diff line change
Expand Up @@ -81,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;
}
}
}
Expand All @@ -108,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;
}
}

Expand Down Expand Up @@ -145,7 +145,7 @@ static motorVTable_t motorPwmVTable = {

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;
Expand Down Expand Up @@ -198,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
Expand All @@ -218,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
Expand Down
4 changes: 2 additions & 2 deletions src/platform/SIMULATOR/sitl.c
Original file line number Diff line number Diff line change
Expand Up @@ -546,7 +546,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)

pwmOutputPort_t *pwmGetMotors(void)
{
return motors;
return pwmMotors;
}

static float pwmConvertFromExternal(uint16_t externalValue)
Expand Down Expand Up @@ -652,7 +652,7 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
idlePulse = _idlePulse;

for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
motors[motorIndex].enabled = true;
pwmMotors[motorIndex].enabled = true;
}

return true;
Expand Down
1 change: 1 addition & 0 deletions src/platform/STM32/dshot_bitbang.c
Original file line number Diff line number Diff line change
Expand Up @@ -716,6 +716,7 @@ static const motorVTable_t bbVTable = {
.shutdown = bbShutdown,
.isMotorIdle = bbDshotIsMotorIdle,
.requestTelemetry = bbDshotRequestTelemetry,
.getMotorIO = bbGetMotorIO,
};

dshotBitbangStatus_e dshotBitbangGetStatus(void)
Expand Down
34 changes: 17 additions & 17 deletions src/platform/STM32/pwm_output_hw.c
Original file line number Diff line number Diff line change
Expand Up @@ -111,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;
}
}
}
Expand All @@ -136,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;
}
}

Expand Down Expand Up @@ -173,7 +173,7 @@ static const motorVTable_t motorPwmVTable = {

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;
Expand Down Expand Up @@ -221,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
Expand All @@ -241,28 +241,28 @@ 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
Expand Down
1 change: 1 addition & 0 deletions src/platform/common/stm32/dshot_bitbang_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -285,3 +285,4 @@ int bbDMA_Count(bbPort_t *bbPort);

void bbDshotRequestTelemetry(unsigned motorIndex);
bool bbDshotIsMotorIdle(unsigned motorIndex);
IO_t bbGetMotorIO(unsigned index);
Loading

0 comments on commit 3dba5e6

Please sign in to comment.