1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 20:10:18 +03:00

Call updateInit() before writing motor command data (#12865)

This commit is contained in:
Steve Evans 2023-06-13 23:09:51 +01:00 committed by GitHub
parent 646de8c57d
commit 2af7337204
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
3 changed files with 22 additions and 10 deletions

View file

@ -182,6 +182,7 @@ void dshotCommandWrite(uint8_t index, uint8_t motorCount, uint8_t command, dshot
uint8_t repeats = 1; uint8_t repeats = 1;
timeUs_t delayAfterCommandUs = DSHOT_COMMAND_DELAY_US; timeUs_t delayAfterCommandUs = DSHOT_COMMAND_DELAY_US;
motorVTable_t *vTable = motorGetVTable();
switch (command) { switch (command) {
case DSHOT_CMD_SPIN_DIRECTION_1: case DSHOT_CMD_SPIN_DIRECTION_1:
@ -216,18 +217,29 @@ void dshotCommandWrite(uint8_t index, uint8_t motorCount, uint8_t command, dshot
for (; repeats; repeats--) { for (; repeats; repeats--) {
delayMicroseconds(DSHOT_COMMAND_DELAY_US); delayMicroseconds(DSHOT_COMMAND_DELAY_US);
#ifdef USE_DSHOT_TELEMETRY // Initialise the output buffers
timeUs_t timeoutUs = micros() + 1000; if (vTable->updateInit) {
while (!motorGetVTable().decodeTelemetry() && vTable->updateInit();
cmpTimeUs(timeoutUs, micros()) > 0); }
#endif
for (uint8_t i = 0; i < motorDeviceCount(); i++) { for (uint8_t i = 0; i < motorDeviceCount(); i++) {
motorDmaOutput_t *const motor = getMotorDmaOutput(i); motorDmaOutput_t *const motor = getMotorDmaOutput(i);
motor->protocolControl.requestTelemetry = true; motor->protocolControl.requestTelemetry = true;
motorGetVTable().writeInt(i, (i == index || index == ALL_MOTORS) ? command : DSHOT_CMD_MOTOR_STOP); vTable->writeInt(i, (i == index || index == ALL_MOTORS) ? command : DSHOT_CMD_MOTOR_STOP);
} }
motorGetVTable().updateComplete(); // Don't attempt to write commands to the motors if telemetry is still being received
if (vTable->telemetryWait) {
(void)vTable->telemetryWait();
}
vTable->updateComplete();
// Perform the decode of the last data received
// New data will be received once the send of motor data, triggered above, completes
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
vTable->decodeTelemetry();
#endif
} }
delayMicroseconds(delayAfterCommandUs); delayMicroseconds(delayAfterCommandUs);

View file

@ -114,9 +114,9 @@ unsigned motorDeviceCount(void)
return motorDevice->count; return motorDevice->count;
} }
motorVTable_t motorGetVTable(void) motorVTable_t *motorGetVTable(void)
{ {
return motorDevice->vTable; return &motorDevice->vTable;
} }
// This is not motor generic anymore; should be moved to analog pwm module // This is not motor generic anymore; should be moved to analog pwm module

View file

@ -86,7 +86,7 @@ uint16_t motorConvertToExternal(float motorValue);
struct motorDevConfig_s; // XXX Shouldn't be needed once pwm_output* is really cleaned up. struct motorDevConfig_s; // XXX Shouldn't be needed once pwm_output* is really cleaned up.
void motorDevInit(const struct motorDevConfig_s *motorConfig, uint16_t idlePulse, uint8_t motorCount); void motorDevInit(const struct motorDevConfig_s *motorConfig, uint16_t idlePulse, uint8_t motorCount);
unsigned motorDeviceCount(void); unsigned motorDeviceCount(void);
motorVTable_t motorGetVTable(void); motorVTable_t *motorGetVTable(void);
bool checkMotorProtocolEnabled(const motorDevConfig_t *motorConfig, bool *protocolIsDshot); bool checkMotorProtocolEnabled(const motorDevConfig_t *motorConfig, bool *protocolIsDshot);
bool isMotorProtocolDshot(void); bool isMotorProtocolDshot(void);
bool isMotorProtocolEnabled(void); bool isMotorProtocolEnabled(void);