mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +03:00
Implement DShot bit bang for AT32 (#12577)
* implement dshot bitbang for AT32 * fix dshot bitbang bidirectional for AT32 * AT32 target features * implement latest improvements from steve to at32 * generalize AT32 target.h * Tri-state USART TX output if load due to powered down peripheral is detected * enable LED STRIP for AT32 * at bitbang timer adjustments * revert makefile changes * revert target generalization * Update src/main/drivers/at32/platform_mcu.h Co-authored-by: Mark Haslinghuis <mark@numloq.nl> --------- Co-authored-by: Steve Evans <Steve@SCEvans.com> Co-authored-by: J Blackman <blckmn@users.noreply.github.com> Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
This commit is contained in:
parent
c243e83de2
commit
3f80b0c8bf
15 changed files with 1148 additions and 25 deletions
2
Makefile
2
Makefile
|
@ -16,7 +16,7 @@
|
||||||
#
|
#
|
||||||
|
|
||||||
# The target to build, see BASE_TARGETS below
|
# The target to build, see BASE_TARGETS below
|
||||||
DEFAULT_TARGET ?= STM32F405
|
DEFAULT_TARGET ?= STM32F405
|
||||||
TARGET ?=
|
TARGET ?=
|
||||||
CONFIG ?=
|
CONFIG ?=
|
||||||
|
|
||||||
|
|
767
src/main/drivers/at32/dshot_bitbang.c
Normal file
767
src/main/drivers/at32/dshot_bitbang.c
Normal file
|
@ -0,0 +1,767 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <math.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_BITBANG
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
#include "build/debug_pin.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/io_impl.h"
|
||||||
|
#include "drivers/dma.h"
|
||||||
|
#include "drivers/dma_reqmap.h"
|
||||||
|
#include "drivers/dshot.h"
|
||||||
|
#include "drivers/dshot_bitbang.h"
|
||||||
|
#include "drivers/dshot_bitbang_impl.h"
|
||||||
|
#include "drivers/dshot_command.h"
|
||||||
|
#include "drivers/motor.h"
|
||||||
|
#include "drivers/nvic.h"
|
||||||
|
#include "drivers/pwm_output.h" // XXX for pwmOutputPort_t motors[]; should go away with refactoring
|
||||||
|
#include "drivers/dshot_dpwm.h" // XXX for motorDmaOutput_t *getMotorDmaOutput(uint8_t index); should go away with refactoring
|
||||||
|
#include "drivers/dshot_bitbang_decode.h"
|
||||||
|
#include "drivers/time.h"
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
|
#include "pg/motor.h"
|
||||||
|
|
||||||
|
// Maximum time to wait for telemetry reception to complete
|
||||||
|
#define DSHOT_TELEMETRY_TIMEOUT 2000
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT bbPacer_t bbPacers[MAX_MOTOR_PACERS]; // TIM1 or TIM8
|
||||||
|
FAST_DATA_ZERO_INIT int usedMotorPacers = 0;
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT bbPort_t bbPorts[MAX_SUPPORTED_MOTOR_PORTS];
|
||||||
|
FAST_DATA_ZERO_INIT int usedMotorPorts;
|
||||||
|
|
||||||
|
FAST_DATA_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
|
static FAST_DATA_ZERO_INIT int motorCount;
|
||||||
|
dshotBitbangStatus_e bbStatus;
|
||||||
|
|
||||||
|
// For MCUs that use MPU to control DMA coherency, there might be a performance hit
|
||||||
|
// on manipulating input buffer content especially if it is read multiple times,
|
||||||
|
// as the buffer region is attributed as not cachable.
|
||||||
|
// If this is not desirable, we should use manual cache invalidation.
|
||||||
|
#ifdef USE_DSHOT_CACHE_MGMT
|
||||||
|
#define BB_OUTPUT_BUFFER_ATTRIBUTE DMA_RW_AXI __attribute__((aligned(32)))
|
||||||
|
#define BB_INPUT_BUFFER_ATTRIBUTE DMA_RW_AXI __attribute__((aligned(32)))
|
||||||
|
#else
|
||||||
|
#define BB_OUTPUT_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT
|
||||||
|
#define BB_INPUT_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT
|
||||||
|
#endif // USE_DSHOT_CACHE_MGMT
|
||||||
|
|
||||||
|
BB_OUTPUT_BUFFER_ATTRIBUTE uint32_t bbOutputBuffer[MOTOR_DSHOT_BUF_CACHE_ALIGN_LENGTH * MAX_SUPPORTED_MOTOR_PORTS];
|
||||||
|
BB_INPUT_BUFFER_ATTRIBUTE uint16_t bbInputBuffer[DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_LENGTH * MAX_SUPPORTED_MOTOR_PORTS];
|
||||||
|
|
||||||
|
uint8_t bbPuPdMode;
|
||||||
|
FAST_DATA_ZERO_INIT timeUs_t dshotFrameUs;
|
||||||
|
|
||||||
|
const timerHardware_t bbTimerHardware[] = {
|
||||||
|
DEF_TIM(TMR8, CH1, NONE, 0, 0, 0),
|
||||||
|
DEF_TIM(TMR8, CH2, NONE, 0, 1, 0),
|
||||||
|
DEF_TIM(TMR8, CH3, NONE, 0, 2, 0),
|
||||||
|
DEF_TIM(TMR8, CH4, NONE, 0, 3, 0),
|
||||||
|
DEF_TIM(TMR1, CH1, NONE, 0, 0, 0),
|
||||||
|
DEF_TIM(TMR1, CH2, NONE, 0, 1, 0),
|
||||||
|
DEF_TIM(TMR1, CH3, NONE, 0, 2, 0),
|
||||||
|
DEF_TIM(TMR1, CH4, NONE, 0, 3, 0),
|
||||||
|
};
|
||||||
|
|
||||||
|
static FAST_DATA_ZERO_INIT motorDevice_t bbDevice;
|
||||||
|
static FAST_DATA_ZERO_INIT timeUs_t lastSendUs;
|
||||||
|
|
||||||
|
static motorPwmProtocolTypes_e motorPwmProtocol;
|
||||||
|
|
||||||
|
// DMA GPIO output buffer formatting
|
||||||
|
|
||||||
|
static void bbOutputDataInit(uint32_t *buffer, uint16_t portMask, bool inverted)
|
||||||
|
{
|
||||||
|
uint32_t resetMask;
|
||||||
|
uint32_t setMask;
|
||||||
|
|
||||||
|
if (inverted) {
|
||||||
|
resetMask = portMask;
|
||||||
|
setMask = (portMask << 16);
|
||||||
|
} else {
|
||||||
|
resetMask = (portMask << 16);
|
||||||
|
setMask = portMask;
|
||||||
|
}
|
||||||
|
|
||||||
|
int symbol_index;
|
||||||
|
|
||||||
|
for (symbol_index = 0; symbol_index < MOTOR_DSHOT_FRAME_BITS; symbol_index++) {
|
||||||
|
buffer[symbol_index * MOTOR_DSHOT_STATE_PER_SYMBOL + 0] |= setMask ; // Always set all ports
|
||||||
|
buffer[symbol_index * MOTOR_DSHOT_STATE_PER_SYMBOL + 1] = 0; // Reset bits are port dependent
|
||||||
|
buffer[symbol_index * MOTOR_DSHOT_STATE_PER_SYMBOL + 2] |= resetMask; // Always reset all ports
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// output one more 'bit' that keeps the line level at idle to allow the ESC to sample the last bit
|
||||||
|
//
|
||||||
|
// Avoid CRC errors in the case of bi-directional d-shot. CRC errors can occur if the output is
|
||||||
|
// transitioned to an input before the signal has been sampled by the ESC as the sampled voltage
|
||||||
|
// may be somewhere between logic-high and logic-low depending on how the motor output line is
|
||||||
|
// driven or floating. On some MCUs it's observed that the voltage momentarily drops low on transition
|
||||||
|
// to input.
|
||||||
|
|
||||||
|
int hold_bit_index = MOTOR_DSHOT_FRAME_BITS * MOTOR_DSHOT_STATE_PER_SYMBOL;
|
||||||
|
buffer[hold_bit_index + 0] |= resetMask; // Always reset all ports
|
||||||
|
buffer[hold_bit_index + 1] = 0; // Never any change
|
||||||
|
buffer[hold_bit_index + 2] = 0; // Never any change
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbOutputDataSet(uint32_t *buffer, int pinNumber, uint16_t value, bool inverted)
|
||||||
|
{
|
||||||
|
uint32_t middleBit;
|
||||||
|
|
||||||
|
if (inverted) {
|
||||||
|
middleBit = (1 << (pinNumber + 0));
|
||||||
|
} else {
|
||||||
|
middleBit = (1 << (pinNumber + 16));
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int pos = 0; pos < 16; pos++) {
|
||||||
|
if (!(value & 0x8000)) {
|
||||||
|
buffer[pos * 3 + 1] |= middleBit;
|
||||||
|
}
|
||||||
|
value <<= 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbOutputDataClear(uint32_t *buffer)
|
||||||
|
{
|
||||||
|
// Middle position to no change
|
||||||
|
for (int bitpos = 0; bitpos < 16; bitpos++) {
|
||||||
|
buffer[bitpos * 3 + 1] = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// bbPacer management
|
||||||
|
|
||||||
|
static bbPacer_t *bbFindMotorPacer(TIM_TypeDef *tim)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < MAX_MOTOR_PACERS; i++) {
|
||||||
|
|
||||||
|
bbPacer_t *bbPacer = &bbPacers[i];
|
||||||
|
|
||||||
|
if (bbPacer->tim == NULL) {
|
||||||
|
bbPacer->tim = tim;
|
||||||
|
++usedMotorPacers;
|
||||||
|
return bbPacer;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (bbPacer->tim == tim) {
|
||||||
|
return bbPacer;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
// bbPort management
|
||||||
|
|
||||||
|
static bbPort_t *bbFindMotorPort(int portIndex)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < usedMotorPorts; i++) {
|
||||||
|
if (bbPorts[i].portIndex == portIndex) {
|
||||||
|
return &bbPorts[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bbPort_t *bbAllocateMotorPort(int portIndex)
|
||||||
|
{
|
||||||
|
if (usedMotorPorts >= MAX_SUPPORTED_MOTOR_PORTS) {
|
||||||
|
bbStatus = DSHOT_BITBANG_STATUS_TOO_MANY_PORTS;
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
bbPort_t *bbPort = &bbPorts[usedMotorPorts];
|
||||||
|
|
||||||
|
if (!bbPort->timhw) {
|
||||||
|
// No more pacer channel available
|
||||||
|
bbStatus = DSHOT_BITBANG_STATUS_NO_PACER;
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
bbPort->portIndex = portIndex;
|
||||||
|
bbPort->owner.owner = OWNER_DSHOT_BITBANG;
|
||||||
|
bbPort->owner.resourceIndex = RESOURCE_INDEX(portIndex);
|
||||||
|
|
||||||
|
++usedMotorPorts;
|
||||||
|
|
||||||
|
return bbPort;
|
||||||
|
}
|
||||||
|
|
||||||
|
const timerHardware_t *dshotBitbangTimerGetAllocatedByNumberAndChannel(int8_t timerNumber, uint16_t timerChannel)
|
||||||
|
{
|
||||||
|
for (int index = 0; index < usedMotorPorts; index++) {
|
||||||
|
const timerHardware_t *bitbangTimer = bbPorts[index].timhw;
|
||||||
|
if (bitbangTimer && timerGetTIMNumber(bitbangTimer->tim) == timerNumber && bitbangTimer->channel == timerChannel && bbPorts[index].owner.owner) {
|
||||||
|
return bitbangTimer;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
const resourceOwner_t *dshotBitbangTimerGetOwner(const timerHardware_t *timer)
|
||||||
|
{
|
||||||
|
for (int index = 0; index < usedMotorPorts; index++) {
|
||||||
|
const timerHardware_t *bitbangTimer = bbPorts[index].timhw;
|
||||||
|
if (bitbangTimer && bitbangTimer == timer) {
|
||||||
|
return &bbPorts[index].owner;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return &freeOwner;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Return frequency of smallest change [state/sec]
|
||||||
|
|
||||||
|
static uint32_t getDshotBaseFrequency(motorPwmProtocolTypes_e pwmProtocolType)
|
||||||
|
{
|
||||||
|
switch (pwmProtocolType) {
|
||||||
|
case(PWM_TYPE_DSHOT600):
|
||||||
|
return MOTOR_DSHOT600_SYMBOL_RATE * MOTOR_DSHOT_STATE_PER_SYMBOL;
|
||||||
|
case(PWM_TYPE_DSHOT300):
|
||||||
|
return MOTOR_DSHOT300_SYMBOL_RATE * MOTOR_DSHOT_STATE_PER_SYMBOL;
|
||||||
|
default:
|
||||||
|
case(PWM_TYPE_DSHOT150):
|
||||||
|
return MOTOR_DSHOT150_SYMBOL_RATE * MOTOR_DSHOT_STATE_PER_SYMBOL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbSetupDma(bbPort_t *bbPort)
|
||||||
|
{
|
||||||
|
const dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(bbPort->dmaResource);
|
||||||
|
dmaEnable(dmaIdentifier);
|
||||||
|
bbPort->dmaSource = timerDmaSource(bbPort->timhw->channel);
|
||||||
|
|
||||||
|
bbPacer_t *bbPacer = bbFindMotorPacer(bbPort->timhw->tim);
|
||||||
|
bbPacer->dmaSources |= bbPort->dmaSource;
|
||||||
|
|
||||||
|
dmaSetHandler(dmaIdentifier, bbDMAIrqHandler, NVIC_BUILD_PRIORITY(2, 1), (uint32_t)bbPort);
|
||||||
|
|
||||||
|
dmaMuxEnable(dmaIdentifier, bbPort->dmaChannel);
|
||||||
|
|
||||||
|
bbDMA_ITConfig(bbPort);
|
||||||
|
}
|
||||||
|
|
||||||
|
FAST_IRQ_HANDLER void bbDMAIrqHandler(dmaChannelDescriptor_t *descriptor)
|
||||||
|
{
|
||||||
|
dbgPinHi(0);
|
||||||
|
|
||||||
|
bbPort_t *bbPort = (bbPort_t *)descriptor->userParam;
|
||||||
|
|
||||||
|
bbDMA_Cmd(bbPort, FALSE);
|
||||||
|
|
||||||
|
bbTIM_DMACmd(bbPort->timhw->tim, bbPort->dmaSource, FALSE);
|
||||||
|
|
||||||
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF)) {
|
||||||
|
while (1) {};
|
||||||
|
}
|
||||||
|
|
||||||
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
if (bbPort->direction == DSHOT_BITBANG_DIRECTION_INPUT) {
|
||||||
|
#ifdef DEBUG_COUNT_INTERRUPT
|
||||||
|
bbPort->inputIrq++;
|
||||||
|
#endif
|
||||||
|
// Disable DMA as telemetry reception is complete
|
||||||
|
bbDMA_Cmd(bbPort, FALSE);
|
||||||
|
} else {
|
||||||
|
#ifdef DEBUG_COUNT_INTERRUPT
|
||||||
|
bbPort->outputIrq++;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Switch to input
|
||||||
|
|
||||||
|
bbSwitchToInput(bbPort);
|
||||||
|
|
||||||
|
bbTIM_DMACmd(bbPort->timhw->tim, bbPort->dmaSource, TRUE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
dbgPinLo(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Setup bbPorts array elements so that they each have a TIM1 or TIM8 channel
|
||||||
|
// in timerHardware array for BB-DShot.
|
||||||
|
|
||||||
|
static void bbFindPacerTimer(void)
|
||||||
|
{
|
||||||
|
for (int bbPortIndex = 0; bbPortIndex < MAX_SUPPORTED_MOTOR_PORTS; bbPortIndex++) {
|
||||||
|
for (unsigned timerIndex = 0; timerIndex < ARRAYLEN(bbTimerHardware); timerIndex++) {
|
||||||
|
const timerHardware_t *timer = &bbTimerHardware[timerIndex];
|
||||||
|
int timNumber = timerGetTIMNumber(timer->tim);
|
||||||
|
if ((motorConfig()->dev.useDshotBitbangedTimer == DSHOT_BITBANGED_TIMER_TIM1 && timNumber != 1)
|
||||||
|
|| (motorConfig()->dev.useDshotBitbangedTimer == DSHOT_BITBANGED_TIMER_TIM8 && timNumber != 8)) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
bool timerConflict = false;
|
||||||
|
for (int channel = 0; channel < CC_CHANNELS_PER_TIMER; channel++) {
|
||||||
|
const timerHardware_t *timer = timerGetAllocatedByNumberAndChannel(timNumber, CC_CHANNEL_FROM_INDEX(channel));
|
||||||
|
const resourceOwner_e timerOwner = timerGetOwner(timer)->owner;
|
||||||
|
if (timerOwner != OWNER_FREE && timerOwner != OWNER_DSHOT_BITBANG) {
|
||||||
|
timerConflict = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int index = 0; index < bbPortIndex; index++) {
|
||||||
|
const timerHardware_t* t = bbPorts[index].timhw;
|
||||||
|
if (timerGetTIMNumber(t->tim) == timNumber && timer->channel == t->channel) {
|
||||||
|
timerConflict = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (timerConflict) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_DMA_SPEC
|
||||||
|
dmaoptValue_t dmaopt = dmaGetOptionByTimer(timer);
|
||||||
|
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpecByTimerValue(timer->tim, timer->channel, dmaopt);
|
||||||
|
dmaResource_t *dma = dmaChannelSpec->ref;
|
||||||
|
#else
|
||||||
|
dmaResource_t *dma = timer->dmaRef;
|
||||||
|
#endif
|
||||||
|
dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(dma);
|
||||||
|
if (dmaGetOwner(dmaIdentifier)->owner == OWNER_FREE) {
|
||||||
|
bbPorts[bbPortIndex].timhw = timer;
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbTimebaseSetup(bbPort_t *bbPort, motorPwmProtocolTypes_e dshotProtocolType)
|
||||||
|
{
|
||||||
|
uint32_t timerclock = timerClock(bbPort->timhw->tim);
|
||||||
|
|
||||||
|
uint32_t outputFreq = getDshotBaseFrequency(dshotProtocolType);
|
||||||
|
dshotFrameUs = 1000000 * 17 * 3 / outputFreq;
|
||||||
|
bbPort->outputARR = timerclock / outputFreq - 1;
|
||||||
|
|
||||||
|
// XXX Explain this formula
|
||||||
|
uint32_t inputFreq = outputFreq * 5 * 2 * DSHOT_BITBANG_TELEMETRY_OVER_SAMPLE / 24;
|
||||||
|
bbPort->inputARR = timerclock / inputFreq - 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// bb only use pin info associated with timerHardware entry designated as TIM_USE_MOTOR;
|
||||||
|
// it does not use the timer channel associated with the pin.
|
||||||
|
//
|
||||||
|
|
||||||
|
static bool bbMotorConfig(IO_t io, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
|
||||||
|
{
|
||||||
|
int pinIndex = IO_GPIOPinIdx(io);
|
||||||
|
int portIndex = IO_GPIOPortIdx(io);
|
||||||
|
|
||||||
|
bbPort_t *bbPort = bbFindMotorPort(portIndex);
|
||||||
|
|
||||||
|
if (!bbPort) {
|
||||||
|
|
||||||
|
// New port group
|
||||||
|
|
||||||
|
bbPort = bbAllocateMotorPort(portIndex);
|
||||||
|
|
||||||
|
if (bbPort) {
|
||||||
|
const timerHardware_t *timhw = bbPort->timhw;
|
||||||
|
|
||||||
|
#ifdef USE_DMA_SPEC
|
||||||
|
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpecByTimerValue(timhw->tim, timhw->channel, dmaGetOptionByTimer(timhw));
|
||||||
|
bbPort->dmaResource = dmaChannelSpec->ref;
|
||||||
|
bbPort->dmaChannel = dmaChannelSpec->dmaMuxId;
|
||||||
|
#else
|
||||||
|
bbPort->dmaResource = timhw->dmaRef;
|
||||||
|
bbPort->dmaChannel = timhw->dmaChannel;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!bbPort || !dmaAllocate(dmaGetIdentifier(bbPort->dmaResource), bbPort->owner.owner, bbPort->owner.resourceIndex)) {
|
||||||
|
bbDevice.vTable.write = motorWriteNull;
|
||||||
|
bbDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull;
|
||||||
|
bbDevice.vTable.updateComplete = motorUpdateCompleteNull;
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bbPort->gpio = IO_GPIO(io);
|
||||||
|
|
||||||
|
bbPort->portOutputCount = MOTOR_DSHOT_BUF_LENGTH;
|
||||||
|
bbPort->portOutputBuffer = &bbOutputBuffer[(bbPort - bbPorts) * MOTOR_DSHOT_BUF_CACHE_ALIGN_LENGTH];
|
||||||
|
|
||||||
|
bbPort->portInputCount = DSHOT_BB_PORT_IP_BUF_LENGTH;
|
||||||
|
bbPort->portInputBuffer = &bbInputBuffer[(bbPort - bbPorts) * DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_LENGTH];
|
||||||
|
|
||||||
|
bbTimebaseSetup(bbPort, pwmProtocolType);
|
||||||
|
bbTIM_TimeBaseInit(bbPort, bbPort->outputARR);
|
||||||
|
bbTimerChannelInit(bbPort);
|
||||||
|
|
||||||
|
bbSetupDma(bbPort);
|
||||||
|
bbDMAPreconfigure(bbPort, DSHOT_BITBANG_DIRECTION_OUTPUT);
|
||||||
|
bbDMAPreconfigure(bbPort, DSHOT_BITBANG_DIRECTION_INPUT);
|
||||||
|
|
||||||
|
bbDMA_ITConfig(bbPort);
|
||||||
|
}
|
||||||
|
|
||||||
|
bbMotors[motorIndex].pinIndex = pinIndex;
|
||||||
|
bbMotors[motorIndex].io = io;
|
||||||
|
bbMotors[motorIndex].output = output;
|
||||||
|
bbMotors[motorIndex].bbPort = bbPort;
|
||||||
|
|
||||||
|
IOInit(io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
|
|
||||||
|
// Setup GPIO_MODER and GPIO_ODR register manipulation values
|
||||||
|
|
||||||
|
bbGpioSetup(&bbMotors[motorIndex]);
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_INVERTED);
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_NONINVERTED);
|
||||||
|
}
|
||||||
|
|
||||||
|
bbSwitchToOutput(bbPort);
|
||||||
|
|
||||||
|
bbMotors[motorIndex].configured = true;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool bbTelemetryWait(void)
|
||||||
|
{
|
||||||
|
// Wait for telemetry reception to complete
|
||||||
|
bool telemetryPending;
|
||||||
|
bool telemetryWait = false;
|
||||||
|
const timeUs_t startTimeUs = micros();
|
||||||
|
|
||||||
|
do {
|
||||||
|
telemetryPending = false;
|
||||||
|
for (int i = 0; i < usedMotorPorts; i++) {
|
||||||
|
telemetryPending |= bbPorts[i].telemetryPending;
|
||||||
|
}
|
||||||
|
|
||||||
|
telemetryWait |= telemetryPending;
|
||||||
|
|
||||||
|
if (cmpTimeUs(micros(), startTimeUs) > DSHOT_TELEMETRY_TIMEOUT) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} while (telemetryPending);
|
||||||
|
|
||||||
|
if (telemetryWait) {
|
||||||
|
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 2, debug[2] + 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
return telemetryWait;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbUpdateInit(void)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < usedMotorPorts; i++) {
|
||||||
|
bbOutputDataClear(bbPorts[i].portOutputBuffer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool bbDecodeTelemetry(void)
|
||||||
|
{
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||||
|
const timeMs_t currentTimeMs = millis();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_CACHE_MGMT
|
||||||
|
for (int i = 0; i < usedMotorPorts; i++) {
|
||||||
|
bbPort_t *bbPort = &bbPorts[i];
|
||||||
|
SCB_InvalidateDCache_by_Addr((uint32_t *)bbPort->portInputBuffer, DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||||
|
|
||||||
|
uint32_t rawValue = decode_bb_bitband(
|
||||||
|
bbMotors[motorIndex].bbPort->portInputBuffer,
|
||||||
|
bbMotors[motorIndex].bbPort->portInputCount,
|
||||||
|
bbMotors[motorIndex].pinIndex);
|
||||||
|
|
||||||
|
if (rawValue == DSHOT_TELEMETRY_NOEDGE) {
|
||||||
|
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 1, debug[1] + 1);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 0, debug[0] + 1);
|
||||||
|
dshotTelemetryState.readCount++;
|
||||||
|
|
||||||
|
if (rawValue != DSHOT_TELEMETRY_INVALID) {
|
||||||
|
// Check EDT enable or store raw value
|
||||||
|
if ((rawValue == 0x0E00) && (dshotCommandGetCurrent(motorIndex) == DSHOT_CMD_EXTENDED_TELEMETRY_ENABLE)) {
|
||||||
|
dshotTelemetryState.motorState[motorIndex].telemetryTypes = 1 << DSHOT_TELEMETRY_TYPE_STATE_EVENTS;
|
||||||
|
} else {
|
||||||
|
dshotTelemetryState.motorState[motorIndex].rawValue = rawValue;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
dshotTelemetryState.invalidPacketCount++;
|
||||||
|
}
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||||
|
updateDshotTelemetryQuality(&dshotTelemetryQuality[motorIndex], rawValue != DSHOT_TELEMETRY_INVALID, currentTimeMs);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbWriteInt(uint8_t motorIndex, uint16_t value)
|
||||||
|
{
|
||||||
|
bbMotor_t *const bbmotor = &bbMotors[motorIndex];
|
||||||
|
|
||||||
|
if (!bbmotor->configured) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// fetch requestTelemetry from motors. Needs to be refactored.
|
||||||
|
motorDmaOutput_t * const motor = getMotorDmaOutput(motorIndex);
|
||||||
|
bbmotor->protocolControl.requestTelemetry = motor->protocolControl.requestTelemetry;
|
||||||
|
motor->protocolControl.requestTelemetry = false;
|
||||||
|
|
||||||
|
// If there is a command ready to go overwrite the value and send that instead
|
||||||
|
if (dshotCommandIsProcessing()) {
|
||||||
|
value = dshotCommandGetCurrent(motorIndex);
|
||||||
|
if (value) {
|
||||||
|
bbmotor->protocolControl.requestTelemetry = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bbmotor->protocolControl.value = value;
|
||||||
|
|
||||||
|
uint16_t packet = prepareDshotPacket(&bbmotor->protocolControl);
|
||||||
|
|
||||||
|
bbPort_t *bbPort = bbmotor->bbPort;
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_INVERTED);
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_NONINVERTED);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbWrite(uint8_t motorIndex, float value)
|
||||||
|
{
|
||||||
|
bbWriteInt(motorIndex, lrintf(value));
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbUpdateComplete(void)
|
||||||
|
{
|
||||||
|
// If there is a dshot command loaded up, time it correctly with motor update
|
||||||
|
|
||||||
|
if (!dshotCommandQueueEmpty()) {
|
||||||
|
if (!dshotCommandOutputIsEnabled(bbDevice.count)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_CACHE_MGMT
|
||||||
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; 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++) {
|
||||||
|
if (bbMotors[motorIndex].bbPort->portOutputBuffer == bbMotors[i].bbPort->portOutputBuffer) {
|
||||||
|
clean = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (!clean) {
|
||||||
|
SCB_CleanDCache_by_Addr(bbMotors[motorIndex].bbPort->portOutputBuffer, MOTOR_DSHOT_BUF_CACHE_ALIGN_BYTES);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
for (int i = 0; i < usedMotorPorts; i++) {
|
||||||
|
bbPort_t *bbPort = &bbPorts[i];
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
if (bbPort->direction == DSHOT_BITBANG_DIRECTION_INPUT) {
|
||||||
|
bbPort->inputActive = false;
|
||||||
|
bbSwitchToOutput(bbPort);
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
bbSwitchToOutput(bbPort);
|
||||||
|
}
|
||||||
|
|
||||||
|
bbDMA_Cmd(bbPort, TRUE);
|
||||||
|
}
|
||||||
|
|
||||||
|
lastSendUs = micros();
|
||||||
|
for (int i = 0; i < usedMotorPacers; i++) {
|
||||||
|
bbPacer_t *bbPacer = &bbPacers[i];
|
||||||
|
bbTIM_DMACmd(bbPacer->tim, bbPacer->dmaSources, TRUE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool bbEnableMotors(void)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < motorCount; i++) {
|
||||||
|
if (bbMotors[i].configured) {
|
||||||
|
IOConfigGPIO(bbMotors[i].io, bbMotors[i].iocfg);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbDisableMotors(void)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbShutdown(void)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool bbIsMotorEnabled(uint8_t index)
|
||||||
|
{
|
||||||
|
return bbMotors[index].enabled;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbPostInit(void)
|
||||||
|
{
|
||||||
|
bbFindPacerTimer();
|
||||||
|
|
||||||
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||||
|
|
||||||
|
if (!bbMotorConfig(bbMotors[motorIndex].io, motorIndex, motorPwmProtocol, bbMotors[motorIndex].output)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
bbMotors[motorIndex].enabled = true;
|
||||||
|
|
||||||
|
// Fill in motors structure for 4way access (XXX Should be refactored)
|
||||||
|
|
||||||
|
motors[motorIndex].enabled = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static motorVTable_t bbVTable = {
|
||||||
|
.postInit = bbPostInit,
|
||||||
|
.enable = bbEnableMotors,
|
||||||
|
.disable = bbDisableMotors,
|
||||||
|
.isMotorEnabled = bbIsMotorEnabled,
|
||||||
|
.telemetryWait = bbTelemetryWait,
|
||||||
|
.decodeTelemetry = bbDecodeTelemetry,
|
||||||
|
.updateInit = bbUpdateInit,
|
||||||
|
.write = bbWrite,
|
||||||
|
.writeInt = bbWriteInt,
|
||||||
|
.updateComplete = bbUpdateComplete,
|
||||||
|
.convertExternalToMotor = dshotConvertFromExternal,
|
||||||
|
.convertMotorToExternal = dshotConvertToExternal,
|
||||||
|
.shutdown = bbShutdown,
|
||||||
|
};
|
||||||
|
|
||||||
|
dshotBitbangStatus_e dshotBitbangGetStatus(void)
|
||||||
|
{
|
||||||
|
return bbStatus;
|
||||||
|
}
|
||||||
|
|
||||||
|
motorDevice_t *dshotBitbangDevInit(const motorDevConfig_t *motorConfig, uint8_t count)
|
||||||
|
{
|
||||||
|
dbgPinLo(0);
|
||||||
|
dbgPinLo(1);
|
||||||
|
|
||||||
|
motorPwmProtocol = motorConfig->motorPwmProtocol;
|
||||||
|
bbDevice.vTable = bbVTable;
|
||||||
|
motorCount = count;
|
||||||
|
bbStatus = DSHOT_BITBANG_STATUS_OK;
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
useDshotTelemetry = motorConfig->useDshotTelemetry;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
memset(bbOutputBuffer, 0, sizeof(bbOutputBuffer));
|
||||||
|
|
||||||
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||||
|
const unsigned reorderedMotorIndex = motorConfig->motorOutputReordering[motorIndex];
|
||||||
|
const timerHardware_t *timerHardware = timerGetConfiguredByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
||||||
|
const IO_t io = IOGetByTag(motorConfig->ioTags[reorderedMotorIndex]);
|
||||||
|
|
||||||
|
uint8_t output = motorConfig->motorPwmInversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output;
|
||||||
|
bbPuPdMode = (output & TIMER_OUTPUT_INVERTED) ? BB_GPIO_PULLDOWN : BB_GPIO_PULLUP;
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
output ^= TIMER_OUTPUT_INVERTED;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (!IOIsFreeOrPreinit(io)) {
|
||||||
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
|
bbDevice.vTable.write = motorWriteNull;
|
||||||
|
bbDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull;
|
||||||
|
bbDevice.vTable.updateComplete = motorUpdateCompleteNull;
|
||||||
|
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
int pinIndex = IO_GPIOPinIdx(io);
|
||||||
|
|
||||||
|
bbMotors[motorIndex].pinIndex = pinIndex;
|
||||||
|
bbMotors[motorIndex].io = io;
|
||||||
|
bbMotors[motorIndex].output = output;
|
||||||
|
bbMotors[motorIndex].iocfg = IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, bbPuPdMode);
|
||||||
|
|
||||||
|
IOInit(io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
|
IOConfigGPIO(io, bbMotors[motorIndex].iocfg);
|
||||||
|
if (output & TIMER_OUTPUT_INVERTED) {
|
||||||
|
IOLo(io);
|
||||||
|
} else {
|
||||||
|
IOHi(io);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Fill in motors structure for 4way access (XXX Should be refactored)
|
||||||
|
motors[motorIndex].io = bbMotors[motorIndex].io;
|
||||||
|
}
|
||||||
|
|
||||||
|
return &bbDevice;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // USE_DSHOT_BB
|
295
src/main/drivers/at32/dshot_bitbang_stdperiph.c
Normal file
295
src/main/drivers/at32/dshot_bitbang_stdperiph.c
Normal file
|
@ -0,0 +1,295 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Betaflight.
|
||||||
|
*
|
||||||
|
* Betaflight is free software. You can redistribute this software
|
||||||
|
* and/or modify this software under the terms of the GNU General
|
||||||
|
* Public License as published by the Free Software Foundation,
|
||||||
|
* either version 3 of the License, or (at your option) any later
|
||||||
|
* version.
|
||||||
|
*
|
||||||
|
* Betaflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
*
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public
|
||||||
|
* License along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <math.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_BITBANG
|
||||||
|
|
||||||
|
#include "build/atomic.h"
|
||||||
|
#include "build/debug.h"
|
||||||
|
#include "build/debug_pin.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/io_impl.h"
|
||||||
|
#include "drivers/dma.h"
|
||||||
|
#include "drivers/dma_reqmap.h"
|
||||||
|
#include "drivers/dshot.h"
|
||||||
|
#include "drivers/dshot_bitbang_impl.h"
|
||||||
|
#include "drivers/dshot_command.h"
|
||||||
|
#include "drivers/motor.h"
|
||||||
|
#include "drivers/nvic.h"
|
||||||
|
#include "drivers/pwm_output.h" // XXX for pwmOutputPort_t motors[]; should go away with refactoring
|
||||||
|
#include "drivers/time.h"
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
|
#include "pg/motor.h"
|
||||||
|
|
||||||
|
void bbGpioSetup(bbMotor_t *bbMotor)
|
||||||
|
{
|
||||||
|
bbPort_t *bbPort = bbMotor->bbPort;
|
||||||
|
int pinIndex = bbMotor->pinIndex;
|
||||||
|
|
||||||
|
bbPort->gpioModeMask |= (0x03 << (pinIndex * 2));
|
||||||
|
bbPort->gpioModeInput |= (GPIO_MODE_INPUT << (pinIndex * 2));
|
||||||
|
bbPort->gpioModeOutput |= (GPIO_MODE_OUTPUT << (pinIndex * 2));
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
bbPort->gpioIdleBSRR |= (1 << pinIndex); // BS (lower half)
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
bbPort->gpioIdleBSRR |= (1 << (pinIndex + 16)); // BR (higher half)
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
IOWrite(bbMotor->io, 1);
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
IOWrite(bbMotor->io, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// is this needed here?
|
||||||
|
IOConfigGPIO(bbMotor->io, IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, bbPuPdMode));
|
||||||
|
}
|
||||||
|
|
||||||
|
void bbTimerChannelInit(bbPort_t *bbPort)
|
||||||
|
{
|
||||||
|
const timerHardware_t *timhw = bbPort->timhw;
|
||||||
|
|
||||||
|
TIM_OCInitTypeDef TIM_OCStruct;
|
||||||
|
|
||||||
|
TIM_OCStructInit(&TIM_OCStruct);
|
||||||
|
|
||||||
|
TIM_OCStruct.oc_mode = TMR_OUTPUT_CONTROL_PWM_MODE_A;
|
||||||
|
TIM_OCStruct.oc_idle_state = TRUE;
|
||||||
|
TIM_OCStruct.oc_output_state = TRUE;
|
||||||
|
TIM_OCStruct.oc_polarity = TMR_OUTPUT_ACTIVE_LOW;
|
||||||
|
|
||||||
|
// TIM_OCStruct.TIM_Pulse = 10; // Duty doesn't matter, but too value small would make monitor output invalid
|
||||||
|
|
||||||
|
tmr_channel_value_set(timhw->tim, TIM_CH_TO_SELCHANNEL(timhw->channel), 10);
|
||||||
|
|
||||||
|
TIM_Cmd(timhw->tim, FALSE);
|
||||||
|
|
||||||
|
timerOCInit(timhw->tim, timhw->channel, &TIM_OCStruct);
|
||||||
|
|
||||||
|
tmr_channel_enable(timhw->tim, TIM_CH_TO_SELCHANNEL(timhw->channel), TRUE);
|
||||||
|
|
||||||
|
timerOCPreloadConfig(timhw->tim, timhw->channel, TRUE);
|
||||||
|
|
||||||
|
#ifdef DEBUG_MONITOR_PACER
|
||||||
|
if (timhw->tag) {
|
||||||
|
IO_t io = IOGetByTag(timhw->tag);
|
||||||
|
IOConfigGPIOAF(io, IOCFG_AF_PP, timhw->alternateFunction);
|
||||||
|
IOInit(io, OWNER_DSHOT_BITBANG, 0);
|
||||||
|
TIM_CtrlPWMOutputs(timhw->tim, TRUE);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable and keep it running
|
||||||
|
|
||||||
|
TIM_Cmd(timhw->tim, TRUE);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_DMA_REGISTER_CACHE
|
||||||
|
|
||||||
|
void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache)
|
||||||
|
{
|
||||||
|
((DMA_ARCH_TYPE *)dmaResource)->ctrl = dmaRegCache->CCR;
|
||||||
|
((DMA_ARCH_TYPE *)dmaResource)->dtcnt = dmaRegCache->CNDTR;
|
||||||
|
((DMA_ARCH_TYPE *)dmaResource)->paddr = dmaRegCache->CPAR;
|
||||||
|
((DMA_ARCH_TYPE *)dmaResource)->maddr = dmaRegCache->CMAR;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbSaveDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache)
|
||||||
|
{
|
||||||
|
dmaRegCache->CCR = ((DMA_ARCH_TYPE *)dmaResource)->ctrl;
|
||||||
|
dmaRegCache->CNDTR = ((DMA_ARCH_TYPE *)dmaResource)->dtcnt;
|
||||||
|
dmaRegCache->CPAR = ((DMA_ARCH_TYPE *)dmaResource)->paddr ;
|
||||||
|
dmaRegCache->CMAR = ((DMA_ARCH_TYPE *)dmaResource)->maddr ;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void bbSwitchToOutput(bbPort_t * bbPort)
|
||||||
|
{
|
||||||
|
dbgPinHi(1);
|
||||||
|
// Output idle level before switching to output
|
||||||
|
// Use BSRR register for this
|
||||||
|
// Normal: Use BR (higher half)
|
||||||
|
// Inverted: Use BS (lower half)
|
||||||
|
|
||||||
|
WRITE_REG(bbPort->gpio->scr, bbPort->gpioIdleBSRR);
|
||||||
|
|
||||||
|
// Set GPIO to output
|
||||||
|
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||||
|
MODIFY_REG(bbPort->gpio->cfgr, bbPort->gpioModeMask, bbPort->gpioModeOutput);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Reinitialize port group DMA for output
|
||||||
|
|
||||||
|
dmaResource_t *dmaResource = bbPort->dmaResource;
|
||||||
|
#ifdef USE_DMA_REGISTER_CACHE
|
||||||
|
bbLoadDMARegs(dmaResource, &bbPort->dmaRegOutput);
|
||||||
|
#else
|
||||||
|
xDMA_DeInit(dmaResource);
|
||||||
|
xDMA_Init(dmaResource, &bbPort->outputDmaInit);
|
||||||
|
// Needs this, as it is DeInit'ed above...
|
||||||
|
xDMA_ITConfig(dmaResource, DMA_IT_TC, ENABLE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Reinitialize pacer timer for output
|
||||||
|
|
||||||
|
bbPort->timhw->tim->pr = bbPort->outputARR;
|
||||||
|
|
||||||
|
bbPort->direction = DSHOT_BITBANG_DIRECTION_OUTPUT;
|
||||||
|
|
||||||
|
dbgPinLo(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
void bbSwitchToInput(bbPort_t *bbPort)
|
||||||
|
{
|
||||||
|
dbgPinHi(1);
|
||||||
|
|
||||||
|
// Set GPIO to input
|
||||||
|
|
||||||
|
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||||
|
MODIFY_REG(bbPort->gpio->cfgr, bbPort->gpioModeMask, bbPort->gpioModeInput);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Reinitialize port group DMA for input
|
||||||
|
|
||||||
|
dmaResource_t *dmaResource = bbPort->dmaResource;
|
||||||
|
#ifdef USE_DMA_REGISTER_CACHE
|
||||||
|
bbLoadDMARegs(dmaResource, &bbPort->dmaRegInput);
|
||||||
|
#else
|
||||||
|
xDMA_DeInit(dmaResource);
|
||||||
|
xDMA_Init(dmaResource, &bbPort->inputDmaInit);
|
||||||
|
// Needs this, as it is DeInit'ed above...
|
||||||
|
xDMA_ITConfig(dmaResource, DMA_IT_TC, ENABLE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Reinitialize pacer timer for input
|
||||||
|
|
||||||
|
bbPort->timhw->tim->cval = 0;
|
||||||
|
bbPort->timhw->tim->pr = bbPort->inputARR;
|
||||||
|
|
||||||
|
bbDMA_Cmd(bbPort, TRUE);
|
||||||
|
|
||||||
|
bbPort->direction = DSHOT_BITBANG_DIRECTION_INPUT;
|
||||||
|
|
||||||
|
dbgPinLo(1);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void bbDMAPreconfigure(bbPort_t *bbPort, uint8_t direction)
|
||||||
|
{
|
||||||
|
DMA_InitTypeDef *dmainit = (direction == DSHOT_BITBANG_DIRECTION_OUTPUT) ? &bbPort->outputDmaInit : &bbPort->inputDmaInit;
|
||||||
|
|
||||||
|
dma_default_para_init(dmainit);
|
||||||
|
|
||||||
|
dmainit->loop_mode_enable = FALSE;
|
||||||
|
// dmainit->DMA_Channel = bbPort->dmaChannel;
|
||||||
|
dmainit->peripheral_inc_enable = FALSE;
|
||||||
|
dmainit->memory_inc_enable = TRUE;
|
||||||
|
/* dmainit->DMA_FIFOMode = DMA_FIFOMode_Enable ;
|
||||||
|
dmainit->DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
|
||||||
|
dmainit->DMA_MemoryBurst = DMA_MemoryBurst_Single ;
|
||||||
|
dmainit->DMA_PeripheralBurst = DMA_PeripheralBurst_Single; */
|
||||||
|
|
||||||
|
if (direction == DSHOT_BITBANG_DIRECTION_OUTPUT) {
|
||||||
|
dmainit->priority = DMA_PRIORITY_VERY_HIGH;
|
||||||
|
dmainit->direction = DMA_DIR_MEMORY_TO_PERIPHERAL;
|
||||||
|
dmainit->buffer_size = bbPort->portOutputCount;
|
||||||
|
dmainit->peripheral_base_addr = (uint32_t)&bbPort->gpio->scr;
|
||||||
|
dmainit->peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_WORD;
|
||||||
|
dmainit->memory_base_addr = (uint32_t)bbPort->portOutputBuffer;
|
||||||
|
dmainit->memory_data_width = DMA_MEMORY_DATA_WIDTH_WORD;
|
||||||
|
|
||||||
|
#ifdef USE_DMA_REGISTER_CACHE
|
||||||
|
xDMA_Init(bbPort->dmaResource, dmainit);
|
||||||
|
bbSaveDMARegs(bbPort->dmaResource, &bbPort->dmaRegOutput);
|
||||||
|
#endif
|
||||||
|
} else {
|
||||||
|
dmainit->priority = DMA_PRIORITY_VERY_HIGH;
|
||||||
|
dmainit->direction = DMA_DIR_PERIPHERAL_TO_MEMORY;
|
||||||
|
dmainit->buffer_size = bbPort->portInputCount;
|
||||||
|
|
||||||
|
dmainit->peripheral_base_addr = (uint32_t)&bbPort->gpio->idt;
|
||||||
|
dmainit->peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_HALFWORD;
|
||||||
|
dmainit->memory_base_addr = (uint32_t)bbPort->portInputBuffer;
|
||||||
|
dmainit->memory_data_width = DMA_MEMORY_DATA_WIDTH_HALFWORD;
|
||||||
|
|
||||||
|
#ifdef USE_DMA_REGISTER_CACHE
|
||||||
|
xDMA_Init(bbPort->dmaResource, dmainit);
|
||||||
|
bbSaveDMARegs(bbPort->dmaResource, &bbPort->dmaRegInput);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void bbTIM_TimeBaseInit(bbPort_t *bbPort, uint16_t period)
|
||||||
|
{
|
||||||
|
/*TIM_TimeBaseInitTypeDef *init = &bbPort->timeBaseInit;
|
||||||
|
|
||||||
|
init->TIM_Prescaler = 0; // Feed raw timerClock
|
||||||
|
init->TIM_ClockDivision = TMR_CLOCK_DIV1;
|
||||||
|
init->TIM_CounterMode = TMR_COUNT_UP;
|
||||||
|
init->TIM_Period = period; */
|
||||||
|
|
||||||
|
tmr_base_init(bbPort->timhw->tim, period, 0);
|
||||||
|
tmr_clock_source_div_set(bbPort->timhw->tim, TMR_CLOCK_DIV1);
|
||||||
|
tmr_cnt_dir_set(bbPort->timhw->tim, TMR_COUNT_UP);
|
||||||
|
tmr_period_buffer_enable(bbPort->timhw->tim, TRUE);
|
||||||
|
|
||||||
|
//TIM_TimeBaseInit(bbPort->timhw->tim, init, DISABLE);
|
||||||
|
|
||||||
|
tmr_period_buffer_enable(bbPort->timhw->tim, TRUE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void bbTIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, confirm_state NewState)
|
||||||
|
{
|
||||||
|
// TIM_DMACmd(TIMx, TIM_DMASource, NewState);
|
||||||
|
tmr_dma_request_enable(TIMx, TIM_DMASource, NewState);
|
||||||
|
}
|
||||||
|
|
||||||
|
void bbDMA_ITConfig(bbPort_t *bbPort)
|
||||||
|
{
|
||||||
|
xDMA_ITConfig(bbPort->dmaResource, DMA_IT_TCIF, TRUE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void bbDMA_Cmd(bbPort_t *bbPort, confirm_state NewState)
|
||||||
|
{
|
||||||
|
xDMA_Cmd(bbPort->dmaResource, NewState);
|
||||||
|
}
|
||||||
|
|
||||||
|
int bbDMA_Count(bbPort_t *bbPort)
|
||||||
|
{
|
||||||
|
return xDMA_GetCurrDataCounter(bbPort->dmaResource);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // USE_DSHOT_BB
|
|
@ -42,6 +42,11 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||||
#define USART_TypeDef usart_type
|
#define USART_TypeDef usart_type
|
||||||
#define TIM_OCInitTypeDef tmr_output_config_type
|
#define TIM_OCInitTypeDef tmr_output_config_type
|
||||||
#define TIM_ICInitTypeDef tmr_input_config_type
|
#define TIM_ICInitTypeDef tmr_input_config_type
|
||||||
|
#define TIM_OCStructInit tmr_output_default_para_init
|
||||||
|
#define TIM_Cmd tmr_counter_enable
|
||||||
|
#define TIM_CtrlPWMOutputs tmr_output_enable
|
||||||
|
#define TIM_TimeBaseInit tmr_base_init
|
||||||
|
#define TIM_ARRPreloadConfig tmr_period_buffer_enable
|
||||||
#define SystemCoreClock system_core_clock
|
#define SystemCoreClock system_core_clock
|
||||||
#define EXTI_TypeDef exint_type
|
#define EXTI_TypeDef exint_type
|
||||||
#define EXTI_InitTypeDef exint_init_type
|
#define EXTI_InitTypeDef exint_init_type
|
||||||
|
@ -82,7 +87,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||||
#define SCHEDULER_DELAY_LIMIT 100
|
#define SCHEDULER_DELAY_LIMIT 100
|
||||||
|
|
||||||
#define DEFAULT_CPU_OVERCLOCK 0
|
#define DEFAULT_CPU_OVERCLOCK 0
|
||||||
#define FAST_IRQ_HANDLER
|
#define FAST_IRQ_HANDLER FAST_CODE
|
||||||
|
|
||||||
#define DMA_DATA_ZERO_INIT
|
#define DMA_DATA_ZERO_INIT
|
||||||
#define DMA_DATA
|
#define DMA_DATA
|
||||||
|
@ -95,3 +100,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||||
#define DMA_RAM_RW
|
#define DMA_RAM_RW
|
||||||
|
|
||||||
#define USE_LATE_TASK_STATISTICS
|
#define USE_LATE_TASK_STATISTICS
|
||||||
|
|
||||||
|
#define USE_RPM_FILTER
|
||||||
|
#define USE_DYN_IDLE
|
||||||
|
#define USE_DYN_NOTCH_FILTER
|
||||||
|
|
|
@ -30,6 +30,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
#ifdef USE_UART
|
#ifdef USE_UART
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
@ -312,6 +314,9 @@ void uartIrqHandler(uartPort_t *s)
|
||||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||||
} else {
|
} else {
|
||||||
usart_interrupt_enable(s->USARTx, USART_TDBE_INT, FALSE);
|
usart_interrupt_enable(s->USARTx, USART_TDBE_INT, FALSE);
|
||||||
|
|
||||||
|
// Switch TX to an input with pullup so it's state can be monitored
|
||||||
|
uartTxMonitor(s);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -54,8 +54,6 @@
|
||||||
|
|
||||||
#define TIM_IT_CCx(ch) (TMR_C1_INT << ((ch)-1))
|
#define TIM_IT_CCx(ch) (TMR_C1_INT << ((ch)-1))
|
||||||
|
|
||||||
#define TIM_CH_TO_SELCHANNEL(ch) (( ch -1)*2)
|
|
||||||
|
|
||||||
typedef struct timerConfig_s {
|
typedef struct timerConfig_s {
|
||||||
timerOvrHandlerRec_t *updateCallback;
|
timerOvrHandlerRec_t *updateCallback;
|
||||||
|
|
||||||
|
@ -144,6 +142,9 @@ static uint8_t lookupTimerIndex(const tmr_type *tim)
|
||||||
#endif
|
#endif
|
||||||
#if USED_TIMERS & TIM_N(17)
|
#if USED_TIMERS & TIM_N(17)
|
||||||
_CASE(17);
|
_CASE(17);
|
||||||
|
#endif
|
||||||
|
#if USED_TIMERS & TIM_N(20)
|
||||||
|
_CASE(20);
|
||||||
#endif
|
#endif
|
||||||
default: return ~1; // make sure final index is out of range
|
default: return ~1; // make sure final index is out of range
|
||||||
}
|
}
|
||||||
|
@ -508,13 +509,13 @@ void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned
|
||||||
volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
|
volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
|
||||||
{
|
{
|
||||||
|
|
||||||
if(timHw->channel ==1)
|
if(timHw->channel == 1)
|
||||||
return (volatile timCCR_t*)(&timHw->tim->c1dt);
|
return (volatile timCCR_t*)(&timHw->tim->c1dt);
|
||||||
else if(timHw->channel ==2)
|
else if(timHw->channel == 2)
|
||||||
return (volatile timCCR_t*)(&timHw->tim->c2dt);
|
return (volatile timCCR_t*)(&timHw->tim->c2dt);
|
||||||
else if(timHw->channel ==3)
|
else if(timHw->channel == 3)
|
||||||
return (volatile timCCR_t*)(&timHw->tim->c3dt);
|
return (volatile timCCR_t*)(&timHw->tim->c3dt);
|
||||||
else if(timHw->channel ==4)
|
else if(timHw->channel == 4)
|
||||||
return (volatile timCCR_t*)(&timHw->tim->c4dt);
|
return (volatile timCCR_t*)(&timHw->tim->c4dt);
|
||||||
else
|
else
|
||||||
return (volatile timCCR_t*)((volatile char*)&timHw->tim->c1dt + (timHw->channel-1)*0x04); //for 32bit need to debug
|
return (volatile timCCR_t*)((volatile char*)&timHw->tim->c1dt + (timHw->channel-1)*0x04); //for 32bit need to debug
|
||||||
|
|
|
@ -58,7 +58,6 @@ typedef struct bitBandWord_s {
|
||||||
uint32_t junk[15];
|
uint32_t junk[15];
|
||||||
} bitBandWord_t;
|
} bitBandWord_t;
|
||||||
|
|
||||||
|
|
||||||
#ifdef DEBUG_BBDECODE
|
#ifdef DEBUG_BBDECODE
|
||||||
uint32_t sequence[MAX_GCR_EDGES];
|
uint32_t sequence[MAX_GCR_EDGES];
|
||||||
int sequenceIndex = 0;
|
int sequenceIndex = 0;
|
||||||
|
|
|
@ -79,6 +79,9 @@
|
||||||
#ifdef USE_HAL_DRIVER
|
#ifdef USE_HAL_DRIVER
|
||||||
#define BB_GPIO_PULLDOWN GPIO_PULLDOWN
|
#define BB_GPIO_PULLDOWN GPIO_PULLDOWN
|
||||||
#define BB_GPIO_PULLUP GPIO_PULLUP
|
#define BB_GPIO_PULLUP GPIO_PULLUP
|
||||||
|
#elif defined(AT32F435)
|
||||||
|
#define BB_GPIO_PULLDOWN GPIO_PULL_DOWN
|
||||||
|
#define BB_GPIO_PULLUP GPIO_PULL_UP
|
||||||
#else
|
#else
|
||||||
#define BB_GPIO_PULLDOWN GPIO_PuPd_DOWN
|
#define BB_GPIO_PULLDOWN GPIO_PuPd_DOWN
|
||||||
#define BB_GPIO_PULLUP GPIO_PuPd_UP
|
#define BB_GPIO_PULLUP GPIO_PuPd_UP
|
||||||
|
@ -92,7 +95,7 @@ typedef struct dmaRegCache_s {
|
||||||
uint32_t NDTR;
|
uint32_t NDTR;
|
||||||
uint32_t PAR;
|
uint32_t PAR;
|
||||||
uint32_t M0AR;
|
uint32_t M0AR;
|
||||||
#elif defined(STM32G4)
|
#elif defined(STM32G4) || defined(AT32F435)
|
||||||
uint32_t CCR;
|
uint32_t CCR;
|
||||||
uint32_t CNDTR;
|
uint32_t CNDTR;
|
||||||
uint32_t CPAR;
|
uint32_t CPAR;
|
||||||
|
@ -110,6 +113,17 @@ typedef struct bbPacer_s {
|
||||||
uint16_t dmaSources;
|
uint16_t dmaSources;
|
||||||
} bbPacer_t;
|
} bbPacer_t;
|
||||||
|
|
||||||
|
#ifdef AT32F435
|
||||||
|
|
||||||
|
typedef struct tmr_base_init_s {
|
||||||
|
uint32_t TIM_Prescaler;
|
||||||
|
uint32_t TIM_ClockDivision;
|
||||||
|
uint32_t TIM_CounterMode;
|
||||||
|
uint32_t TIM_Period;
|
||||||
|
} tmr_base_init_type;
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
// Per GPIO port and timer channel
|
// Per GPIO port and timer channel
|
||||||
|
|
||||||
typedef struct bbPort_s {
|
typedef struct bbPort_s {
|
||||||
|
@ -143,6 +157,8 @@ typedef struct bbPort_s {
|
||||||
|
|
||||||
#ifdef USE_HAL_DRIVER
|
#ifdef USE_HAL_DRIVER
|
||||||
LL_TIM_InitTypeDef timeBaseInit;
|
LL_TIM_InitTypeDef timeBaseInit;
|
||||||
|
#elif defined(AT32F435)
|
||||||
|
tmr_base_init_type timeBaseInit;
|
||||||
#else
|
#else
|
||||||
TIM_TimeBaseInitTypeDef timeBaseInit;
|
TIM_TimeBaseInitTypeDef timeBaseInit;
|
||||||
#endif
|
#endif
|
||||||
|
@ -241,7 +257,15 @@ void bbSwitchToOutput(bbPort_t * bbPort);
|
||||||
void bbSwitchToInput(bbPort_t * bbPort);
|
void bbSwitchToInput(bbPort_t * bbPort);
|
||||||
|
|
||||||
void bbTIM_TimeBaseInit(bbPort_t *bbPort, uint16_t period);
|
void bbTIM_TimeBaseInit(bbPort_t *bbPort, uint16_t period);
|
||||||
|
#ifdef AT32F435
|
||||||
|
void bbTIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, confirm_state NewState);
|
||||||
|
#else
|
||||||
void bbTIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState);
|
void bbTIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState);
|
||||||
|
#endif
|
||||||
void bbDMA_ITConfig(bbPort_t *bbPort);
|
void bbDMA_ITConfig(bbPort_t *bbPort);
|
||||||
|
#ifdef AT32F435
|
||||||
|
void bbDMA_Cmd(bbPort_t *bbPort, confirm_state NewState);
|
||||||
|
#else
|
||||||
void bbDMA_Cmd(bbPort_t *bbPort, FunctionalState NewState);
|
void bbDMA_Cmd(bbPort_t *bbPort, FunctionalState NewState);
|
||||||
|
#endif
|
||||||
int bbDMA_Count(bbPort_t *bbPort);
|
int bbDMA_Count(bbPort_t *bbPort);
|
||||||
|
|
|
@ -30,6 +30,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
#ifdef USE_UART
|
#ifdef USE_UART
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
|
@ -30,6 +30,8 @@
|
||||||
|
|
||||||
#ifdef USE_UART
|
#ifdef USE_UART
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
|
@ -387,6 +389,9 @@ void uartIrqHandler(uartPort_t *s)
|
||||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||||
} else {
|
} else {
|
||||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||||
|
|
||||||
|
// Switch TX to an input with pullup so it's state can be monitored
|
||||||
|
uartTxMonitor(s);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -33,8 +33,15 @@
|
||||||
#include "pg/timerio.h"
|
#include "pg/timerio.h"
|
||||||
|
|
||||||
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
|
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
|
||||||
#define CC_INDEX_FROM_CHANNEL(x) ((uint8_t)((x) >> 2))
|
#ifdef AT32F435
|
||||||
|
#define CC_INDEX_FROM_CHANNEL(x) ((uint8_t)(x) - 1)
|
||||||
|
#define CC_CHANNEL_FROM_INDEX(x) ((uint16_t)(x) + 1)
|
||||||
|
#else
|
||||||
#define CC_CHANNEL_FROM_INDEX(x) ((uint16_t)(x) << 2)
|
#define CC_CHANNEL_FROM_INDEX(x) ((uint16_t)(x) << 2)
|
||||||
|
#define CC_INDEX_FROM_CHANNEL(x) ((uint8_t)((x) >> 2))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define TIM_CH_TO_SELCHANNEL(ch) ((ch - 1) * 2)
|
||||||
|
|
||||||
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)
|
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)
|
||||||
|
|
||||||
|
|
|
@ -37,12 +37,19 @@
|
||||||
#define USE_UART1
|
#define USE_UART1
|
||||||
#define USE_UART2
|
#define USE_UART2
|
||||||
#define USE_UART3
|
#define USE_UART3
|
||||||
|
#define USE_UART4
|
||||||
|
#define USE_UART5
|
||||||
|
#define USE_UART6
|
||||||
|
#define USE_UART7
|
||||||
|
#define USE_UART8
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3)
|
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3)
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
#define TARGET_IO_PORTD 0xffff
|
#define TARGET_IO_PORTD 0xffff
|
||||||
|
#define TARGET_IO_PORTH 0xffff
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
|
@ -63,7 +70,7 @@
|
||||||
#define USE_PERSISTENT_MSC_RTC
|
#define USE_PERSISTENT_MSC_RTC
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
||||||
#define UNIFIED_SERIAL_PORT_COUNT 1
|
#define UNIFIED_SERIAL_PORT_COUNT 6
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
|
@ -71,17 +78,17 @@
|
||||||
|
|
||||||
// Remove these undefines as support is added
|
// Remove these undefines as support is added
|
||||||
//#undef USE_BEEPER
|
//#undef USE_BEEPER
|
||||||
#undef USE_LED_STRIP
|
//#undef USE_LED_STRIP
|
||||||
#undef USE_TRANSPONDER
|
#undef USE_TRANSPONDER
|
||||||
|
|
||||||
// #undef USE_DSHOT
|
// #undef USE_DSHOT
|
||||||
// #undef USE_DSHOT_TELEMETRY
|
// #undef USE_DSHOT_TELEMETRY
|
||||||
// bitbang not implemented yet
|
// bitbang not implemented yet
|
||||||
#undef USE_DSHOT_BITBANG
|
// #undef USE_DSHOT_BITBANG
|
||||||
// burst mode not implemented yet
|
// burst mode not implemented yet
|
||||||
#undef USE_DSHOT_DMAR
|
#undef USE_DSHOT_DMAR
|
||||||
|
|
||||||
|
#define USE_BEEPER
|
||||||
#undef USE_CAMERA_CONTROL
|
#undef USE_CAMERA_CONTROL
|
||||||
#undef USE_RX_PPM
|
#undef USE_RX_PPM
|
||||||
#undef USE_RX_PWM
|
#undef USE_RX_PWM
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
TARGET_MCU := AT32F435
|
TARGET_MCU := AT32F435
|
||||||
MCU_FLASH_SIZE := 1024
|
MCU_FLASH_SIZE := 1024
|
||||||
DEVICE_FLAGS = -D$(TARGET_MCU) -DAT32F435RGT7
|
DEVICE_FLAGS = -D$(TARGET_MCU) -DAT32F435Rx -DAT32F435RGT7
|
||||||
TARGET_MCU_FAMILY := AT32F4
|
TARGET_MCU_FAMILY := AT32F4
|
||||||
#error
|
#error
|
||||||
|
|
|
@ -37,18 +37,20 @@
|
||||||
#define USE_UART1
|
#define USE_UART1
|
||||||
#define USE_UART2
|
#define USE_UART2
|
||||||
#define USE_UART3
|
#define USE_UART3
|
||||||
|
#define USE_UART4
|
||||||
|
#define USE_UART5
|
||||||
|
#define USE_UART6
|
||||||
|
#define USE_UART7
|
||||||
|
#define USE_UART8
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3)
|
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3)
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
#define TARGET_IO_PORTD 0xffff
|
#define TARGET_IO_PORTD 0xffff
|
||||||
#define TARGET_IO_PORTE 0xffff
|
|
||||||
#define TARGET_IO_PORTF 0xffff
|
|
||||||
#define TARGET_IO_PORTG 0xffff
|
|
||||||
#define TARGET_IO_PORTH 0xffff
|
#define TARGET_IO_PORTH 0xffff
|
||||||
|
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
@ -68,7 +70,7 @@
|
||||||
#define USE_PERSISTENT_MSC_RTC
|
#define USE_PERSISTENT_MSC_RTC
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
||||||
#define UNIFIED_SERIAL_PORT_COUNT 1
|
#define UNIFIED_SERIAL_PORT_COUNT 6
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
|
@ -76,17 +78,17 @@
|
||||||
|
|
||||||
// Remove these undefines as support is added
|
// Remove these undefines as support is added
|
||||||
//#undef USE_BEEPER
|
//#undef USE_BEEPER
|
||||||
#undef USE_LED_STRIP
|
//#undef USE_LED_STRIP
|
||||||
#undef USE_TRANSPONDER
|
#undef USE_TRANSPONDER
|
||||||
|
|
||||||
// #undef USE_DSHOT
|
// #undef USE_DSHOT
|
||||||
// #undef USE_DSHOT_TELEMETRY
|
// #undef USE_DSHOT_TELEMETRY
|
||||||
// bitbang not implemented yet
|
// bitbang not implemented yet
|
||||||
#undef USE_DSHOT_BITBANG
|
// #undef USE_DSHOT_BITBANG
|
||||||
// burst mode not implemented yet
|
// burst mode not implemented yet
|
||||||
#undef USE_DSHOT_DMAR
|
#undef USE_DSHOT_DMAR
|
||||||
|
|
||||||
|
#define USE_BEEPER
|
||||||
#undef USE_CAMERA_CONTROL
|
#undef USE_CAMERA_CONTROL
|
||||||
#undef USE_RX_PPM
|
#undef USE_RX_PPM
|
||||||
#undef USE_RX_PWM
|
#undef USE_RX_PWM
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
TARGET_MCU := AT32F435
|
TARGET_MCU := AT32F435
|
||||||
MCU_FLASH_SIZE := 4096
|
MCU_FLASH_SIZE := 4096
|
||||||
DEVICE_FLAGS = -D$(TARGET_MCU) -DAT32F435ZMT7
|
DEVICE_FLAGS = -D$(TARGET_MCU) -DAT32F435Zx -DAT32F435ZMT7
|
||||||
TARGET_MCU_FAMILY := AT32F4
|
TARGET_MCU_FAMILY := AT32F4
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue