mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 11:59:58 +03:00
Fixed problem when sending blocking Dshot commands with bitbanged Dshot enabled.
This commit is contained in:
parent
57c9c12781
commit
bfa5cc1cd4
3 changed files with 15 additions and 8 deletions
|
@ -34,9 +34,10 @@
|
||||||
|
|
||||||
#include "drivers/dshot.h"
|
#include "drivers/dshot.h"
|
||||||
#include "drivers/dshot_dpwm.h"
|
#include "drivers/dshot_dpwm.h"
|
||||||
#include "drivers/dshot_command.h"
|
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
|
|
||||||
|
#include "dshot_command.h"
|
||||||
|
|
||||||
#define DSHOT_PROTOCOL_DETECTION_DELAY_MS 3000
|
#define DSHOT_PROTOCOL_DETECTION_DELAY_MS 3000
|
||||||
#define DSHOT_INITIAL_DELAY_US 10000
|
#define DSHOT_INITIAL_DELAY_US 10000
|
||||||
#define DSHOT_COMMAND_DELAY_US 1000
|
#define DSHOT_COMMAND_DELAY_US 1000
|
||||||
|
@ -141,7 +142,7 @@ static dshotCommandControl_t* addCommand()
|
||||||
|
|
||||||
static bool allMotorsAreIdle(void)
|
static bool allMotorsAreIdle(void)
|
||||||
{
|
{
|
||||||
for (unsigned i = 0; i < dshotPwmDevice.count; i++) {
|
for (unsigned i = 0; i < motorDeviceCount(); i++) {
|
||||||
const motorDmaOutput_t *motor = getMotorDmaOutput(i);
|
const motorDmaOutput_t *motor = getMotorDmaOutput(i);
|
||||||
if (motor->protocolControl.value) {
|
if (motor->protocolControl.value) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -216,18 +217,18 @@ void dshotCommandWrite(uint8_t index, uint8_t motorCount, uint8_t command, dshot
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
timeUs_t timeoutUs = micros() + 1000;
|
timeUs_t timeoutUs = micros() + 1000;
|
||||||
while (!pwmStartDshotMotorUpdate() &&
|
while (!motorGetVTable().updateStart() &&
|
||||||
cmpTimeUs(timeoutUs, micros()) > 0);
|
cmpTimeUs(timeoutUs, micros()) > 0);
|
||||||
#endif
|
#endif
|
||||||
for (uint8_t i = 0; i < dshotPwmDevice.count; i++) {
|
for (uint8_t i = 0; i < motorDeviceCount(); i++) {
|
||||||
if ((i == index) || (index == ALL_MOTORS)) {
|
if ((i == index) || (index == ALL_MOTORS)) {
|
||||||
motorDmaOutput_t *const motor = getMotorDmaOutput(i);
|
motorDmaOutput_t *const motor = getMotorDmaOutput(i);
|
||||||
motor->protocolControl.requestTelemetry = true;
|
motor->protocolControl.requestTelemetry = true;
|
||||||
dshotPwmDevice.vTable.writeInt(i, command);
|
motorGetVTable().writeInt(i, command);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
dshotPwmDevice.vTable.updateComplete();
|
motorGetVTable().updateComplete();
|
||||||
}
|
}
|
||||||
delayMicroseconds(delayAfterCommandUs);
|
delayMicroseconds(delayAfterCommandUs);
|
||||||
} else if (commandType == DSHOT_CMD_TYPE_INLINE) {
|
} else if (commandType == DSHOT_CMD_TYPE_INLINE) {
|
||||||
|
|
|
@ -73,11 +73,16 @@ void motorWriteAll(float *values)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
int motorDeviceCount(void)
|
unsigned motorDeviceCount(void)
|
||||||
{
|
{
|
||||||
return motorDevice->count;
|
return motorDevice->count;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
motorVTable_t motorGetVTable(void)
|
||||||
|
{
|
||||||
|
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
|
||||||
static void analogInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow) {
|
static 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)) {
|
||||||
|
|
|
@ -83,7 +83,8 @@ 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);
|
||||||
int motorDeviceCount(void);
|
unsigned motorDeviceCount(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);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue