mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +03:00
FIX: AT32 not reading ESC (#14220)
This commit is contained in:
parent
bfea69a04f
commit
3dba5e65e4
13 changed files with 75 additions and 82 deletions
|
@ -28,7 +28,7 @@
|
||||||
|
|
||||||
#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 pwmOutputPort_t pwmMotors[MAX_SUPPORTED_MOTORS];
|
||||||
FAST_DATA_ZERO_INIT uint8_t pwmMotorCount;
|
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)
|
||||||
|
@ -53,12 +53,12 @@ IO_t pwmGetMotorIO(unsigned index)
|
||||||
if (index >= pwmMotorCount) {
|
if (index >= pwmMotorCount) {
|
||||||
return IO_NONE;
|
return IO_NONE;
|
||||||
}
|
}
|
||||||
return motors[index].io;
|
return pwmMotors[index].io;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pwmIsMotorEnabled(unsigned index)
|
bool pwmIsMotorEnabled(unsigned index)
|
||||||
{
|
{
|
||||||
return motors[index].enabled;
|
return pwmMotors[index].enabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool pwmEnableMotors(void)
|
bool pwmEnableMotors(void)
|
||||||
|
|
|
@ -50,7 +50,7 @@ typedef struct {
|
||||||
IO_t io;
|
IO_t io;
|
||||||
} pwmOutputPort_t;
|
} 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;
|
extern FAST_DATA_ZERO_INIT uint8_t pwmMotorCount;
|
||||||
|
|
||||||
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorDevConfig, uint16_t idlePulse);
|
bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorDevConfig, uint16_t idlePulse);
|
||||||
|
|
|
@ -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 = {
|
static motorVTable_t bbVTable = {
|
||||||
.postInit = bbPostInit,
|
.postInit = bbPostInit,
|
||||||
.enable = bbEnableMotors,
|
.enable = bbEnableMotors,
|
||||||
|
|
|
@ -90,15 +90,15 @@ static bool useContinuousUpdate = true;
|
||||||
static void pwmWriteStandard(uint8_t index, float value)
|
static void pwmWriteStandard(uint8_t index, float value)
|
||||||
{
|
{
|
||||||
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */
|
/* 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)
|
static void pwmShutdownPulsesForAllMotors(void)
|
||||||
{
|
{
|
||||||
for (int index = 0; index < pwmMotorCount; 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 (pwmMotors[index].channel.ccr) {
|
||||||
*motors[index].channel.ccr = 0;
|
*pwmMotors[index].channel.ccr = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -117,12 +117,12 @@ static void pwmCompleteMotorUpdate(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int index = 0; index < pwmMotorCount; index++) {
|
for (int index = 0; index < pwmMotorCount; index++) {
|
||||||
if (motors[index].forceOverflow) {
|
if (pwmMotors[index].forceOverflow) {
|
||||||
timerForceOverflow(motors[index].channel.tim);
|
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.
|
// 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.
|
// 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;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -154,7 +154,7 @@ static motorVTable_t motorPwmVTable = {
|
||||||
|
|
||||||
bool 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(pwmMotors, 0, sizeof(pwmMotors));
|
||||||
|
|
||||||
if (!device || !motorConfig) {
|
if (!device || !motorConfig) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -206,10 +206,10 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
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 */
|
/* standard PWM outputs */
|
||||||
// margin of safety is 4 periods when unsynced
|
// margin of safety is 4 periods when unsynced
|
||||||
|
@ -226,20 +226,20 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
TODO: this can be moved back to periodMin and periodLen
|
TODO: this can be moved back to periodMin and periodLen
|
||||||
once mixer outputs a 0..1 float value.
|
once mixer outputs a 0..1 float value.
|
||||||
*/
|
*/
|
||||||
motors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
pwmMotors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||||
motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000);
|
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;
|
bool timerAlreadyUsed = false;
|
||||||
for (int i = 0; i < motorIndex; i++) {
|
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;
|
timerAlreadyUsed = true;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
pwmMotors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||||
motors[motorIndex].enabled = true;
|
pwmMotors[motorIndex].enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
@ -247,7 +247,7 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
|
|
||||||
pwmOutputPort_t *pwmGetMotors(void)
|
pwmOutputPort_t *pwmGetMotors(void)
|
||||||
{
|
{
|
||||||
return motors;
|
return pwmMotors;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
|
|
|
@ -583,7 +583,7 @@ static void bbUpdateComplete(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_DSHOT_CACHE_MGMT
|
#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.
|
// Only clean each buffer once. If all motors are on a common port they'll share a buffer.
|
||||||
bool clean = false;
|
bool clean = false;
|
||||||
for (int i = 0; i < motorIndex; i++) {
|
for (int i = 0; i < motorIndex; i++) {
|
||||||
|
@ -677,6 +677,7 @@ static motorVTable_t bbVTable = {
|
||||||
.shutdown = bbShutdown,
|
.shutdown = bbShutdown,
|
||||||
.isMotorIdle = bbDshotIsMotorIdle,
|
.isMotorIdle = bbDshotIsMotorIdle,
|
||||||
.requestTelemetry = bbDshotRequestTelemetry,
|
.requestTelemetry = bbDshotRequestTelemetry,
|
||||||
|
.getMotorIO = bbGetMotorIO,
|
||||||
};
|
};
|
||||||
|
|
||||||
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||||
|
|
|
@ -122,16 +122,6 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
IOConfigGPIO(io, cfg);
|
||||||
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);
|
|
||||||
gpio_pin_mux_config(IO_GPIO(io), IO_GPIO_PinSource(io), af);
|
gpio_pin_mux_config(IO_GPIO(io), IO_GPIO_PinSource(io), af);
|
||||||
}
|
}
|
||||||
|
|
|
@ -81,15 +81,15 @@ static FAST_DATA_ZERO_INIT motorDevice_t *pwmMotorDevice;
|
||||||
static void pwmWriteStandard(uint8_t index, float value)
|
static void pwmWriteStandard(uint8_t index, float value)
|
||||||
{
|
{
|
||||||
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */
|
/* 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)
|
static void pwmShutdownPulsesForAllMotors(void)
|
||||||
{
|
{
|
||||||
for (int index = 0; index < pwmMotorCount; 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 (pwmMotors[index].channel.ccr) {
|
||||||
*motors[index].channel.ccr = 0;
|
*pwmMotors[index].channel.ccr = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -108,12 +108,12 @@ static void pwmCompleteMotorUpdate(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int index = 0; index < pwmMotorCount; index++) {
|
for (int index = 0; index < pwmMotorCount; index++) {
|
||||||
if (motors[index].forceOverflow) {
|
if (pwmMotors[index].forceOverflow) {
|
||||||
timerForceOverflow(motors[index].channel.tim);
|
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.
|
// 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.
|
// 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;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -145,7 +145,7 @@ static motorVTable_t motorPwmVTable = {
|
||||||
|
|
||||||
bool 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(pwmMotors, 0, sizeof(pwmMotors));
|
||||||
|
|
||||||
if (!device) {
|
if (!device) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -198,10 +198,10 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
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 */
|
/* standard PWM outputs */
|
||||||
// margin of safety is 4 periods when unsynced
|
// margin of safety is 4 periods when unsynced
|
||||||
|
@ -218,27 +218,27 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
TODO: this can be moved back to periodMin and periodLen
|
TODO: this can be moved back to periodMin and periodLen
|
||||||
once mixer outputs a 0..1 float value.
|
once mixer outputs a 0..1 float value.
|
||||||
*/
|
*/
|
||||||
motors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
pwmMotors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||||
motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000);
|
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;
|
bool timerAlreadyUsed = false;
|
||||||
for (int i = 0; i < motorIndex; i++) {
|
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;
|
timerAlreadyUsed = true;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
pwmMotors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||||
motors[motorIndex].enabled = true;
|
pwmMotors[motorIndex].enabled = true;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
pwmOutputPort_t *pwmGetMotors(void)
|
pwmOutputPort_t *pwmGetMotors(void)
|
||||||
{
|
{
|
||||||
return motors;
|
return pwmMotors;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
|
|
|
@ -546,7 +546,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
|
||||||
|
|
||||||
pwmOutputPort_t *pwmGetMotors(void)
|
pwmOutputPort_t *pwmGetMotors(void)
|
||||||
{
|
{
|
||||||
return motors;
|
return pwmMotors;
|
||||||
}
|
}
|
||||||
|
|
||||||
static float pwmConvertFromExternal(uint16_t externalValue)
|
static float pwmConvertFromExternal(uint16_t externalValue)
|
||||||
|
@ -652,7 +652,7 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
idlePulse = _idlePulse;
|
idlePulse = _idlePulse;
|
||||||
|
|
||||||
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;
|
pwmMotors[motorIndex].enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -716,6 +716,7 @@ static const motorVTable_t bbVTable = {
|
||||||
.shutdown = bbShutdown,
|
.shutdown = bbShutdown,
|
||||||
.isMotorIdle = bbDshotIsMotorIdle,
|
.isMotorIdle = bbDshotIsMotorIdle,
|
||||||
.requestTelemetry = bbDshotRequestTelemetry,
|
.requestTelemetry = bbDshotRequestTelemetry,
|
||||||
|
.getMotorIO = bbGetMotorIO,
|
||||||
};
|
};
|
||||||
|
|
||||||
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||||
|
|
|
@ -111,15 +111,15 @@ void pwmOutConfig(timerChannel_t *channel, const timerHardware_t *timerHardware,
|
||||||
static void pwmWriteStandard(uint8_t index, float value)
|
static void pwmWriteStandard(uint8_t index, float value)
|
||||||
{
|
{
|
||||||
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */
|
/* 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)
|
static void pwmShutdownPulsesForAllMotors(void)
|
||||||
{
|
{
|
||||||
for (int index = 0; pwmMotorCount; 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 (pwmMotors[index].channel.ccr) {
|
||||||
*motors[index].channel.ccr = 0;
|
*pwmMotors[index].channel.ccr = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -136,12 +136,12 @@ static void pwmCompleteMotorUpdate(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int index = 0; pwmMotorCount; index++) {
|
for (int index = 0; pwmMotorCount; index++) {
|
||||||
if (motors[index].forceOverflow) {
|
if (pwmMotors[index].forceOverflow) {
|
||||||
timerForceOverflow(motors[index].channel.tim);
|
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.
|
// 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.
|
// 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;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -173,7 +173,7 @@ static const motorVTable_t motorPwmVTable = {
|
||||||
|
|
||||||
bool 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(pwmMotors, 0, sizeof(pwmMotors));
|
||||||
|
|
||||||
pwmMotorCount = device->count;
|
pwmMotorCount = device->count;
|
||||||
device->vTable = &motorPwmVTable;
|
device->vTable = &motorPwmVTable;
|
||||||
|
@ -221,10 +221,10 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
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 */
|
/* standard PWM outputs */
|
||||||
// margin of safety is 4 periods when unsynced
|
// margin of safety is 4 periods when unsynced
|
||||||
|
@ -241,20 +241,20 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
TODO: this can be moved back to periodMin and periodLen
|
TODO: this can be moved back to periodMin and periodLen
|
||||||
once mixer outputs a 0..1 float value.
|
once mixer outputs a 0..1 float value.
|
||||||
*/
|
*/
|
||||||
motors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
pwmMotors[motorIndex].pulseScale = ((motorConfig->motorProtocol == MOTOR_PROTOCOL_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||||
motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000);
|
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;
|
bool timerAlreadyUsed = false;
|
||||||
for (int i = 0; i < motorIndex; i++) {
|
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;
|
timerAlreadyUsed = true;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
motors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
pwmMotors[motorIndex].forceOverflow = !timerAlreadyUsed;
|
||||||
motors[motorIndex].enabled = true;
|
pwmMotors[motorIndex].enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
@ -262,7 +262,7 @@ bool motorPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig,
|
||||||
|
|
||||||
pwmOutputPort_t *pwmGetMotors(void)
|
pwmOutputPort_t *pwmGetMotors(void)
|
||||||
{
|
{
|
||||||
return motors;
|
return pwmMotors;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
|
|
|
@ -285,3 +285,4 @@ int bbDMA_Count(bbPort_t *bbPort);
|
||||||
|
|
||||||
void bbDshotRequestTelemetry(unsigned motorIndex);
|
void bbDshotRequestTelemetry(unsigned motorIndex);
|
||||||
bool bbDshotIsMotorIdle(unsigned motorIndex);
|
bool bbDshotIsMotorIdle(unsigned motorIndex);
|
||||||
|
IO_t bbGetMotorIO(unsigned index);
|
||||||
|
|
|
@ -54,6 +54,14 @@ bool bbDshotIsMotorIdle(unsigned motorIndex)
|
||||||
return bbmotor->protocolControl.value == 0;
|
return bbmotor->protocolControl.value == 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
IO_t bbGetMotorIO(unsigned index)
|
||||||
|
{
|
||||||
|
if (index >= dshotMotorCount) {
|
||||||
|
return IO_NONE;
|
||||||
|
}
|
||||||
|
return bbMotors[index].io;
|
||||||
|
}
|
||||||
|
|
||||||
#ifdef USE_DSHOT_BITBANG
|
#ifdef USE_DSHOT_BITBANG
|
||||||
bool isDshotBitbangActive(const motorDevConfig_t *motorDevConfig)
|
bool isDshotBitbangActive(const motorDevConfig_t *motorDevConfig)
|
||||||
{
|
{
|
||||||
|
|
|
@ -123,7 +123,7 @@ static bool dshotPwmEnableMotors(void)
|
||||||
|
|
||||||
static bool dshotPwmIsMotorEnabled(unsigned index)
|
static bool dshotPwmIsMotorEnabled(unsigned index)
|
||||||
{
|
{
|
||||||
return motors[index].enabled;
|
return pwmMotors[index].enabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
static IO_t pwmDshotGetMotorIO(unsigned index)
|
static IO_t pwmDshotGetMotorIO(unsigned index)
|
||||||
|
@ -131,7 +131,7 @@ static IO_t pwmDshotGetMotorIO(unsigned index)
|
||||||
if (index >= dshotMotorCount) {
|
if (index >= dshotMotorCount) {
|
||||||
return IO_NONE;
|
return IO_NONE;
|
||||||
}
|
}
|
||||||
return motors[index].io;
|
return pwmMotors[index].io;
|
||||||
}
|
}
|
||||||
|
|
||||||
static FAST_CODE void dshotWriteInt(uint8_t index, uint16_t value)
|
static FAST_CODE void dshotWriteInt(uint8_t index, uint16_t value)
|
||||||
|
@ -190,15 +190,15 @@ bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig)
|
||||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||||
|
|
||||||
if (timerHardware != NULL) {
|
if (timerHardware != NULL) {
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
pwmMotors[motorIndex].io = IOGetByTag(tag);
|
||||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
IOInit(pwmMotors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex));
|
||||||
|
|
||||||
if (pwmDshotMotorHardwareConfig(timerHardware,
|
if (pwmDshotMotorHardwareConfig(timerHardware,
|
||||||
motorIndex,
|
motorIndex,
|
||||||
reorderedMotorIndex,
|
reorderedMotorIndex,
|
||||||
motorConfig->motorProtocol,
|
motorConfig->motorProtocol,
|
||||||
motorConfig->motorInversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output)) {
|
motorConfig->motorInversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output)) {
|
||||||
motors[motorIndex].enabled = true;
|
pwmMotors[motorIndex].enabled = true;
|
||||||
|
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue