1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 00:35:34 +03:00
* DSHOT protocol
* Fix real-time tasks, account time to TASK_SYSTEM
This commit is contained in:
Konstantin Sharlaimov 2018-10-20 09:06:05 +02:00 committed by GitHub
parent fd34e7acf2
commit db738810a0
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
19 changed files with 299 additions and 35 deletions

View file

@ -114,7 +114,12 @@ void ws2811LedStripInit(void)
timerConfigBase(ws2811TCH, period, WS2811_TIMER_HZ); timerConfigBase(ws2811TCH, period, WS2811_TIMER_HZ);
timerPWMConfigChannel(ws2811TCH, 0); timerPWMConfigChannel(ws2811TCH, 0);
timerPWMConfigChannelDMA(ws2811TCH, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE);
// If DMA failed - abort
if (!timerPWMConfigChannelDMA(ws2811TCH, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE)) {
ws2811Initialised = false;
return;
}
// Zero out DMA buffer // Zero out DMA buffer
memset(&ledStripDMABuffer, 0, sizeof(ledStripDMABuffer)); memset(&ledStripDMABuffer, 0, sizeof(ledStripDMABuffer));

View file

@ -164,8 +164,7 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
if (init->useServoOutputs && (timerHardwarePtr->usageFlags & TIM_USE_MC_SERVO)) { if (init->useServoOutputs && (timerHardwarePtr->usageFlags & TIM_USE_MC_SERVO)) {
type = MAP_TO_SERVO_OUTPUT; type = MAP_TO_SERVO_OUTPUT;
} }
else else if (timerHardwarePtr->usageFlags & TIM_USE_MC_MOTOR) {
if (timerHardwarePtr->usageFlags & TIM_USE_MC_MOTOR) {
type = MAP_TO_MOTOR_OUTPUT; type = MAP_TO_MOTOR_OUTPUT;
} }
} else { } else {

View file

@ -18,15 +18,18 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <math.h> #include <math.h>
#include <string.h>
#include "platform.h" #include "platform.h"
#include "build/debug.h" #include "build/debug.h"
#include "common/maths.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "timer.h" #include "drivers/timer.h"
#include "pwm_mapping.h" #include "drivers/pwm_mapping.h"
#include "pwm_output.h" #include "drivers/pwm_output.h"
#include "io_pca9685.h" #include "drivers/io_pca9685.h"
#include "io/pwmdriver_i2c.h" #include "io/pwmdriver_i2c.h"
@ -38,15 +41,37 @@
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_HZ * 5 / 1000000.0f) #define MULTISHOT_5US_PW (MULTISHOT_TIMER_HZ * 5 / 1000000.0f)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_HZ * 20 / 1000000.0f / 1000.0f) #define MULTISHOT_20US_MULT (MULTISHOT_TIMER_HZ * 20 / 1000000.0f / 1000.0f)
#ifdef USE_DSHOT
#define MOTOR_DSHOT1200_HZ 24000000
#define MOTOR_DSHOT600_HZ 12000000
#define MOTOR_DSHOT300_HZ 6000000
#define MOTOR_DSHOT150_HZ 3000000
#define DSHOT_MOTOR_BIT_0 7
#define DSHOT_MOTOR_BIT_1 14
#define DSHOT_MOTOR_BITLENGTH 19
#define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */
#endif
typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
typedef struct { typedef struct {
TCH_t * tch; TCH_t * tch;
volatile timCCR_t *ccr;
uint16_t period;
pwmWriteFuncPtr pwmWritePtr; pwmWriteFuncPtr pwmWritePtr;
bool configured;
uint16_t value; // Used to keep track of last motor value
// PWM parameters
volatile timCCR_t *ccr; // Shortcut for timer CCR register
float pulseOffset; float pulseOffset;
float pulseScale; float pulseScale;
#ifdef USE_DSHOT
// DSHOT parameters
uint32_t dmaBuffer[DSHOT_DMA_BUFFER_SIZE];
#endif
} pwmOutputPort_t; } pwmOutputPort_t;
static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS]; static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS];
@ -54,6 +79,13 @@ static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS];
static pwmOutputPort_t *motors[MAX_PWM_MOTORS]; static pwmOutputPort_t *motors[MAX_PWM_MOTORS];
static pwmOutputPort_t *servos[MAX_PWM_SERVOS]; static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
#ifdef USE_DSHOT
static bool isProtocolDshot = false;
static timeUs_t dshotMotorUpdateIntervalUs = 0;
static timeUs_t dshotMotorLastUpdateUs;
#endif
#ifdef BEEPER_PWM #ifdef BEEPER_PWM
static pwmOutputPort_t beeperPwmPort; static pwmOutputPort_t beeperPwmPort;
static pwmOutputPort_t *beeperPwm; static pwmOutputPort_t *beeperPwm;
@ -67,14 +99,13 @@ static bool pwmMotorsEnabled = true;
static void pwmOutConfigTimer(pwmOutputPort_t * p, TCH_t * tch, uint32_t hz, uint16_t period, uint16_t value) static void pwmOutConfigTimer(pwmOutputPort_t * p, TCH_t * tch, uint32_t hz, uint16_t period, uint16_t value)
{ {
p->tch = tch; p->tch = tch;
timerConfigBase(p->tch, period, hz); timerConfigBase(p->tch, period, hz);
timerPWMConfigChannel(p->tch, value); timerPWMConfigChannel(p->tch, value);
timerPWMStart(p->tch); timerPWMStart(p->tch);
timerEnable(p->tch); timerEnable(p->tch);
p->period = period;
p->ccr = timerCCR(p->tch); p->ccr = timerCCR(p->tch);
*p->ccr = 0; *p->ccr = 0;
} }
@ -140,9 +171,9 @@ void pwmEnableMotors(void)
pwmMotorsEnabled = true; pwmMotorsEnabled = true;
} }
bool isMotorBrushed(uint16_t motorPwmRate) bool isMotorBrushed(uint16_t motorPwmRateHz)
{ {
return (motorPwmRate > 500); return (motorPwmRateHz > 500);
} }
static pwmOutputPort_t * motorConfigPwm(const timerHardware_t *timerHardware, float sMin, float sLen, uint32_t motorPwmRateHz, bool enableOutput) static pwmOutputPort_t * motorConfigPwm(const timerHardware_t *timerHardware, float sMin, float sLen, uint32_t motorPwmRateHz, bool enableOutput)
@ -157,12 +188,119 @@ static pwmOutputPort_t * motorConfigPwm(const timerHardware_t *timerHardware, fl
if (port) { if (port) {
port->pulseScale = ((sLen == 0) ? period : (sLen * timerHz)) / 1000.0f; port->pulseScale = ((sLen == 0) ? period : (sLen * timerHz)) / 1000.0f;
port->pulseOffset = (sMin * timerHz) - (port->pulseScale * 1000); port->pulseOffset = (sMin * timerHz) - (port->pulseScale * 1000);
port->configured = true;
} }
return port; return port;
} }
bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, motorPwmProtocolTypes_e proto, bool enableOutput) #ifdef USE_DSHOT
uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType)
{
switch (pwmProtocolType) {
case(PWM_TYPE_DSHOT1200):
return MOTOR_DSHOT1200_HZ;
case(PWM_TYPE_DSHOT600):
return MOTOR_DSHOT600_HZ;
case(PWM_TYPE_DSHOT300):
return MOTOR_DSHOT300_HZ;
default:
case(PWM_TYPE_DSHOT150):
return MOTOR_DSHOT150_HZ;
}
}
static pwmOutputPort_t * motorConfigDshot(const timerHardware_t * timerHardware, motorPwmProtocolTypes_e proto, uint16_t motorPwmRateHz, bool enableOutput)
{
// Try allocating new port
pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, getDshotHz(proto), DSHOT_MOTOR_BITLENGTH, 0, enableOutput);
if (!port) {
return NULL;
}
// Keep track of motor update interval
const timeUs_t motorIntervalUs = 1000000 / motorPwmRateHz;
dshotMotorUpdateIntervalUs = MAX(dshotMotorUpdateIntervalUs, motorIntervalUs);
// Configure timer DMA
if (timerPWMConfigChannelDMA(port->tch, port->dmaBuffer, DSHOT_DMA_BUFFER_SIZE)) {
// Only mark as DSHOT channel if DMA was set successfully
memset(port->dmaBuffer, 0, sizeof(port->dmaBuffer));
port->configured = true;
}
return port;
}
static void pwmWriteDshot(uint8_t index, uint16_t value)
{
// DMA operation might still be running. Cache value for future use
motors[index]->value = value;
}
static void loadDmaBufferDshot(uint32_t * dmaBuffer, uint16_t packet)
{
for (int i = 0; i < 16; i++) {
dmaBuffer[i] = (packet & 0x8000) ? DSHOT_MOTOR_BIT_1 : DSHOT_MOTOR_BIT_0; // MSB first
packet <<= 1;
}
}
static uint16_t prepareDshotPacket(const uint16_t value, bool requestTelemetry)
{
uint16_t packet = (value << 1) | (requestTelemetry ? 1 : 0);
// compute checksum
int csum = 0;
int csum_data = packet;
for (int i = 0; i < 3; i++) {
csum ^= csum_data; // xor data by nibbles
csum_data >>= 4;
}
csum &= 0xf;
// append checksum
packet = (packet << 4) | csum;
return packet;
}
void pwmCompleteDshotUpdate(uint8_t motorCount, timeUs_t currentTimeUs)
{
// Enforce motor update rate
if (!isProtocolDshot || (dshotMotorUpdateIntervalUs == 0) || ((currentTimeUs - dshotMotorLastUpdateUs) <= dshotMotorUpdateIntervalUs)) {
return;
}
dshotMotorLastUpdateUs = currentTimeUs;
// Generate DMA buffers
for (int index = 0; index < motorCount; index++) {
if (motors[index] && motors[index]->configured) {
// TODO: ESC telemetry
uint16_t packet = prepareDshotPacket(motors[index]->value, false);
loadDmaBufferDshot(motors[index]->dmaBuffer, packet);
timerPWMPrepareDMA(motors[index]->tch, DSHOT_DMA_BUFFER_SIZE);
}
}
// Start DMA on all timers
for (int index = 0; index < motorCount; index++) {
if (motors[index] && motors[index]->configured) {
timerPWMStartDMA(motors[index]->tch);
}
}
}
bool isMotorProtocolDshot(void)
{
return isProtocolDshot;
}
#endif
bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRateHz, motorPwmProtocolTypes_e proto, bool enableOutput)
{ {
pwmOutputPort_t * port = NULL; pwmOutputPort_t * port = NULL;
pwmWriteFuncPtr pwmWritePtr; pwmWriteFuncPtr pwmWritePtr;
@ -173,21 +311,21 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, ui
switch (proto) { switch (proto) {
case PWM_TYPE_BRUSHED: case PWM_TYPE_BRUSHED:
port = motorConfigPwm(timerHardware, 0.0f, 0.0f, motorPwmRate, enableOutput); port = motorConfigPwm(timerHardware, 0.0f, 0.0f, motorPwmRateHz, enableOutput);
pwmWritePtr = pwmWriteStandard; pwmWritePtr = pwmWriteStandard;
break; break;
case PWM_TYPE_ONESHOT125: case PWM_TYPE_ONESHOT125:
port = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorPwmRate, enableOutput); port = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorPwmRateHz, enableOutput);
pwmWritePtr = pwmWriteStandard; pwmWritePtr = pwmWriteStandard;
break; break;
case PWM_TYPE_ONESHOT42: case PWM_TYPE_ONESHOT42:
port = motorConfigPwm(timerHardware, 42e-6f, 42e-6f, motorPwmRate, enableOutput); port = motorConfigPwm(timerHardware, 42e-6f, 42e-6f, motorPwmRateHz, enableOutput);
pwmWritePtr = pwmWriteStandard; pwmWritePtr = pwmWriteStandard;
break; break;
case PWM_TYPE_MULTISHOT: case PWM_TYPE_MULTISHOT:
port = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, motorPwmRate, enableOutput); port = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, motorPwmRateHz, enableOutput);
pwmWritePtr = pwmWriteStandard; pwmWritePtr = pwmWriteStandard;
break; break;
@ -196,13 +334,17 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, ui
case PWM_TYPE_DSHOT600: case PWM_TYPE_DSHOT600:
case PWM_TYPE_DSHOT300: case PWM_TYPE_DSHOT300:
case PWM_TYPE_DSHOT150: case PWM_TYPE_DSHOT150:
port = NULL; port = motorConfigDshot(timerHardware, proto, motorPwmRateHz, enableOutput);
if (port) {
isProtocolDshot = true;
pwmWritePtr = pwmWriteDshot;
}
break; break;
#endif #endif
default: default:
case PWM_TYPE_STANDARD: case PWM_TYPE_STANDARD:
port = motorConfigPwm(timerHardware, 1e-3f, 1e-3f, motorPwmRate, enableOutput); port = motorConfigPwm(timerHardware, 1e-3f, 1e-3f, motorPwmRateHz, enableOutput);
pwmWritePtr = pwmWriteStandard; pwmWritePtr = pwmWriteStandard;
break; break;
} }

View file

@ -18,6 +18,7 @@
#pragma once #pragma once
#include "drivers/io_types.h" #include "drivers/io_types.h"
#include "drivers/time.h"
typedef enum { typedef enum {
PWM_TYPE_STANDARD = 0, PWM_TYPE_STANDARD = 0,
@ -25,16 +26,16 @@ typedef enum {
PWM_TYPE_ONESHOT42, PWM_TYPE_ONESHOT42,
PWM_TYPE_MULTISHOT, PWM_TYPE_MULTISHOT,
PWM_TYPE_BRUSHED, PWM_TYPE_BRUSHED,
#ifdef USE_DSHOT
PWM_TYPE_DSHOT150, PWM_TYPE_DSHOT150,
PWM_TYPE_DSHOT300, PWM_TYPE_DSHOT300,
PWM_TYPE_DSHOT600, PWM_TYPE_DSHOT600,
PWM_TYPE_DSHOT1200, PWM_TYPE_DSHOT1200,
#endif
} motorPwmProtocolTypes_e; } motorPwmProtocolTypes_e;
void pwmWriteMotor(uint8_t index, uint16_t value); void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmShutdownPulsesForAllMotors(uint8_t motorCount); void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
void pwmCompleteDshotUpdate(uint8_t motorCount, timeUs_t currentTimeUs);
bool isMotorProtocolDshot(void);
void pwmWriteServo(uint8_t index, uint16_t value); void pwmWriteServo(uint8_t index, uint16_t value);

View file

@ -327,6 +327,11 @@ bool impl_timerPWMConfigChannelDMA(TCH_t * tch, void * dmaBuffer, uint32_t dmaBu
return false; return false;
} }
// If DMA is already in use - abort
if (tch->dma->owner != OWNER_FREE) {
return false;
}
// We assume that timer channels are already initialized by calls to: // We assume that timer channels are already initialized by calls to:
// timerConfigBase // timerConfigBase
// timerPWMConfigChannel // timerPWMConfigChannel

View file

@ -294,6 +294,11 @@ bool impl_timerPWMConfigChannelDMA(TCH_t * tch, void * dmaBuffer, uint32_t dmaBu
return false; return false;
} }
// If DMA is already in use - abort
if (tch->dma->owner != OWNER_FREE) {
return false;
}
// We assume that timer channels are already initialized by calls to: // We assume that timer channels are already initialized by calls to:
// timerConfigBase // timerConfigBase
// timerPWMConfigChannel // timerPWMConfigChannel

View file

@ -298,10 +298,17 @@ void validateAndFixConfig(void)
#endif #endif
// Limitations of different protocols // Limitations of different protocols
#if !defined(USE_DSHOT)
if (motorConfig()->motorPwmProtocol > PWM_TYPE_BRUSHED) {
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_STANDARD;
}
#endif
#ifdef BRUSHED_MOTORS #ifdef BRUSHED_MOTORS
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000); motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000);
#else #else
switch (motorConfig()->motorPwmProtocol) { switch (motorConfig()->motorPwmProtocol) {
default:
case PWM_TYPE_STANDARD: // Limited to 490 Hz case PWM_TYPE_STANDARD: // Limited to 490 Hz
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 490); motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 490);
break; break;
@ -317,6 +324,23 @@ void validateAndFixConfig(void)
case PWM_TYPE_BRUSHED: // 500Hz - 32kHz case PWM_TYPE_BRUSHED: // 500Hz - 32kHz
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000); motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000);
break; break;
#ifdef USE_DSHOT
// One DSHOT packet takes 16 bits x 19 ticks + 2uS = 304 timer ticks + 2uS
case PWM_TYPE_DSHOT150:
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 4000);
break;
case PWM_TYPE_DSHOT300:
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 8000);
break;
// Although DSHOT 600+ support >16kHz update rate it's not practical because of increased CPU load
// It's more reasonable to use slower-speed DSHOT at higher rate for better reliability
case PWM_TYPE_DSHOT600:
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 16000);
break;
case PWM_TYPE_DSHOT1200:
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 32000);
break;
#endif
} }
#endif #endif

View file

@ -34,8 +34,9 @@
#include "drivers/light_led.h" #include "drivers/light_led.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/pwm_output.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "sensors/diagnostics.h" #include "sensors/diagnostics.h"
#include "sensors/boardalignment.h" #include "sensors/boardalignment.h"
@ -809,10 +810,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
writeMotors(); writeMotors();
} }
#ifdef USE_SDCARD
afatfs_poll();
#endif
#ifdef USE_BLACKBOX #ifdef USE_BLACKBOX
if (!cliMode && feature(FEATURE_BLACKBOX)) { if (!cliMode && feature(FEATURE_BLACKBOX)) {
blackboxUpdate(micros()); blackboxUpdate(micros());
@ -820,6 +817,21 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
#endif #endif
} }
// This function is called in a busy-loop, everything called from here should do it's own
// scheduling and avoid doing heavy calculations
void taskRunRealtimeCallbacks(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
#ifdef USE_SDCARD
afatfs_poll();
#endif
#ifdef USE_DSHOT
pwmCompleteDshotUpdate(getMotorCount(), currentTimeUs);
#endif
}
bool taskUpdateRxCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime) bool taskUpdateRxCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
{ {
UNUSED(currentDeltaTime); UNUSED(currentDeltaTime);

View file

@ -32,7 +32,7 @@ tables:
- name: blackbox_device - name: blackbox_device
values: ["SERIAL", "SPIFLASH", "SDCARD"] values: ["SERIAL", "SPIFLASH", "SDCARD"]
- name: motor_pwm_protocol - name: motor_pwm_protocol
values: ["STANDARD", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED"] values: ["STANDARD", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200"]
- name: failsafe_procedure - name: failsafe_procedure
values: ["SET-THR", "DROP", "RTH", "NONE"] values: ["SET-THR", "DROP", "RTH", "NONE"]
- name: current_sensor - name: current_sensor

View file

@ -101,6 +101,7 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
.mincommand = 1000, .mincommand = 1000,
.motorAccelTimeMs = 0, .motorAccelTimeMs = 0,
.motorDecelTimeMs = 0, .motorDecelTimeMs = 0,
.digitalIdleOffsetValue = 450 // Same scale as in Betaflight
); );
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS]; static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
@ -181,7 +182,45 @@ void mixerResetDisarmedMotors(void)
void writeMotors(void) void writeMotors(void)
{ {
for (int i = 0; i < motorCount; i++) { for (int i = 0; i < motorCount; i++) {
pwmWriteMotor(i, motor[i]); uint16_t motorValue;
#ifdef USE_DSHOT
// If we use DSHOT we need to convert motorValue to DSHOT ranges
if (isMotorProtocolDshot()) {
const float dshotMinThrottleOffset = (DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) / 10000.0f * motorConfig()->digitalIdleOffsetValue;
if (feature(FEATURE_3D)) {
if (motor[i] >= motorConfig()->minthrottle && motor[i] <= flight3DConfig()->deadband3d_low) {
motorValue = scaleRangef(motor[i], motorConfig()->minthrottle, flight3DConfig()->deadband3d_low, DSHOT_3D_DEADBAND_LOW, dshotMinThrottleOffset + DSHOT_MIN_THROTTLE);
motorValue = constrain(motorValue, DSHOT_MIN_THROTTLE, DSHOT_3D_DEADBAND_LOW);
}
else if (motor[i] >= flight3DConfig()->deadband3d_high && motor[i] <= motorConfig()->maxthrottle) {
motorValue = scaleRangef(motor[i], flight3DConfig()->deadband3d_high, motorConfig()->maxthrottle, dshotMinThrottleOffset + DSHOT_3D_DEADBAND_HIGH, DSHOT_MAX_THROTTLE);
motorValue = constrain(motorValue, DSHOT_3D_DEADBAND_HIGH, DSHOT_MAX_THROTTLE);
}
else {
motorValue = DSHOT_DISARM_COMMAND;
}
}
else {
if (motor[i] < motorConfig()->minthrottle) { // motor disarmed
motorValue = DSHOT_DISARM_COMMAND;
}
else {
motorValue = scaleRangef(motor[i], motorConfig()->minthrottle, motorConfig()->maxthrottle, (dshotMinThrottleOffset + DSHOT_MIN_THROTTLE), DSHOT_MAX_THROTTLE);
motorValue = constrain(motorValue, (dshotMinThrottleOffset + DSHOT_MIN_THROTTLE), DSHOT_MAX_THROTTLE);
}
}
}
else {
motorValue = motor[i];
}
#else
// We don't define USE_DSHOT
motorValue = motor[i];
#endif
pwmWriteMotor(i, motorValue);
} }
} }

View file

@ -30,6 +30,13 @@
#define FW_MIN_THROTTLE_DOWN_PITCH_ANGLE_MAX 450 #define FW_MIN_THROTTLE_DOWN_PITCH_ANGLE_MAX 450
// Digital protocol has fixed values
#define DSHOT_DISARM_COMMAND 0
#define DSHOT_MIN_THROTTLE 48
#define DSHOT_MAX_THROTTLE 2047
#define DSHOT_3D_DEADBAND_LOW 1047
#define DSHOT_3D_DEADBAND_HIGH 1048
typedef enum { typedef enum {
PLATFORM_MULTIROTOR = 0, PLATFORM_MULTIROTOR = 0,
PLATFORM_AIRPLANE = 1, PLATFORM_AIRPLANE = 1,
@ -83,6 +90,7 @@ typedef struct motorConfig_s {
uint8_t motorPwmProtocol; uint8_t motorPwmProtocol;
uint16_t motorAccelTimeMs; // Time limit for motor to accelerate from 0 to 100% throttle [ms] uint16_t motorAccelTimeMs; // Time limit for motor to accelerate from 0 to 100% throttle [ms]
uint16_t motorDecelTimeMs; // Time limit for motor to decelerate from 0 to 100% throttle [ms] uint16_t motorDecelTimeMs; // Time limit for motor to decelerate from 0 to 100% throttle [ms]
uint16_t digitalIdleOffsetValue;
} motorConfig_t; } motorConfig_t;
PG_DECLARE(motorConfig_t, motorConfig); PG_DECLARE(motorConfig_t, motorConfig);

View file

@ -306,7 +306,20 @@ void scheduler(void)
#endif #endif
#if defined(SCHEDULER_DEBUG) #if defined(SCHEDULER_DEBUG)
DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs - taskExecutionTime); // time spent in scheduler DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs - taskExecutionTime); // time spent in scheduler
#endif
} else { } else {
// Execute system real-time callbacks and account for them to SYSTEM account
const timeUs_t currentTimeBeforeTaskCall = micros();
taskRunRealtimeCallbacks(currentTimeBeforeTaskCall);
#ifndef SKIP_TASK_STATISTICS
selectedTask = &cfTasks[TASK_SYSTEM];
const timeUs_t taskExecutionTime = micros() - currentTimeBeforeTaskCall;
selectedTask->movingSumExecutionTime += taskExecutionTime - selectedTask->movingSumExecutionTime / TASK_MOVING_SUM_COUNT;
selectedTask->totalExecutionTime += taskExecutionTime; // time consumed by scheduler + task
selectedTask->maxExecutionTime = MAX(selectedTask->maxExecutionTime, taskExecutionTime);
#endif
#if defined(SCHEDULER_DEBUG)
DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs); DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs);
#endif #endif
} }

View file

@ -162,6 +162,7 @@ void schedulerResetTaskStatistics(cfTaskId_e taskId);
void schedulerInit(void); void schedulerInit(void);
void scheduler(void); void scheduler(void);
void taskSystem(timeUs_t currentTimeUs); void taskSystem(timeUs_t currentTimeUs);
void taskRunRealtimeCallbacks(timeUs_t currentTimeUs);
#define TASK_PERIOD_HZ(hz) (1000000 / (hz)) #define TASK_PERIOD_HZ(hz) (1000000 / (hz))
#define TASK_PERIOD_MS(ms) ((ms) * 1000) #define TASK_PERIOD_MS(ms) ((ms) * 1000)

View file

@ -26,6 +26,8 @@
#define BEEPER PB13 #define BEEPER PB13
#define BEEPER_INVERTED #define BEEPER_INVERTED
#define USE_DSHOT
// MPU6500 interrupt // MPU6500 interrupt
#define USE_EXTI #define USE_EXTI
#define GYRO_INT_EXTI PA5 #define GYRO_INT_EXTI PA5

View file

@ -33,14 +33,14 @@
const timerHardware_t timerHardware[] = { const timerHardware_t timerHardware[] = {
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S1_OUT DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S1_OUT D(1,7) U(1,2)
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S2_OUT DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S2_OUT D(1,2) U(1,2)
DEF_TIM(TIM9, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S3_OUT DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S3_OUT D(1,6) U(1,7)
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4_OUT DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4_OUT D(1,5) U(1,2)
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip D(1,0)
DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0, 0), // SS1 DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0, 0), // SS1
}; };
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -28,6 +28,8 @@
#define USBD_PRODUCT_STRING "OMNIBUS F4 FWX V2" #define USBD_PRODUCT_STRING "OMNIBUS F4 FWX V2"
#define USE_DSHOT
// Status LED // Status LED
#define LED0 PA8 #define LED0 PA8

View file

@ -209,6 +209,8 @@
#define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2)) #define TARGET_IO_PORTD (BIT(2))
#define USE_DSHOT
#define MAX_PWM_OUTPUT_PORTS 6 #define MAX_PWM_OUTPUT_PORTS 6
#define PCA9685_I2C_BUS DEFAULT_I2C_BUS #define PCA9685_I2C_BUS DEFAULT_I2C_BUS

View file

@ -175,6 +175,8 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define USE_DSHOT
// Number of available PWM outputs // Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 6 #define MAX_PWM_OUTPUT_PORTS 6
#define TARGET_MOTOR_COUNT 6 #define TARGET_MOTOR_COUNT 6

View file

@ -32,6 +32,8 @@
#define BEEPER PB4 #define BEEPER PB4
#define USE_DSHOT
// MPU6000 interrupts // MPU6000 interrupts
#define USE_EXTI #define USE_EXTI
#define MPU6000_EXTI_PIN PC4 #define MPU6000_EXTI_PIN PC4