Пример #1
0
void ledInit(bool alternative_led)
{
    uint32_t i;

#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
    if (alternative_led)
        ledOffset = LED_NUMBER;
#else
    UNUSED(alternative_led);
#endif

    LED0_OFF;
    LED1_OFF;
    LED2_OFF;

    for (i = 0; i < LED_NUMBER; i++) {
        if (leds[i + ledOffset]) {
            IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
            IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
        }
    }

    LED0_OFF;
    LED1_OFF;
    LED2_OFF;
}
Пример #2
0
void servoInit(const servoConfig_t *servoConfig)
{
    for (uint8_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
        const ioTag_t tag = servoConfig->ioTags[servoIndex];

        if (!tag) {
            break;
        }

        servos[servoIndex].io = IOGetByTag(tag);

        IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_INDEX(servoIndex));
        IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP);

        const timerHardware_t *timer = timerGetByTag(tag, TIM_USE_ANY);

        if (timer == NULL) {
            /* flag failure and disable ability to arm */
            break;
        }

        pwmOutConfig(&servos[servoIndex], timer, PWM_TIMER_MHZ, 1000000 / servoConfig->servoPwmRate, servoConfig->servoCenterPulse);
        servos[servoIndex].enabled = true;
    }
}
Пример #3
0
void serialInputPortConfig(ioTag_t pin, uint8_t portIndex)
{
    IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex));
#ifdef STM32F1
    IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU);
#else
    IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP);
#endif
}
Пример #4
0
void pwmRxInit(const pwmConfig_t *pwmConfig)
{
    inputFilteringMode = pwmConfig->inputFilteringMode;

    for (int channel = 0; channel < PWM_INPUT_PORT_COUNT; channel++) {

        pwmInputPort_t *port = &pwmInputPorts[channel];

        const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel], TIM_USE_ANY);

        if (!timer) {
            /* TODO: maybe fail here if not enough channels? */
            continue;
        }

        port->state = 0;
        port->missedEvents = 0;
        port->channel = channel;
        port->mode = INPUT_MODE_PWM;
        port->timerHardware = timer;

        IO_t io = IOGetByTag(pwmConfig->ioTags[channel]);
        IOInit(io, OWNER_PWMINPUT, RESOURCE_INDEX(channel));
#ifdef STM32F1
        IOConfigGPIO(io, IOCFG_IPD);
#else
        IOConfigGPIOAF(io, IOCFG_AF_PP, timer->alternateFunction);
#endif
        timerConfigure(timer, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_1MHZ);
        timerChCCHandlerInit(&port->edgeCb, pwmEdgeCallback);
        timerChOvrHandlerInit(&port->overflowCb, pwmOverflowCallback);
        timerChConfigCallbacks(timer, &port->edgeCb, &port->overflowCb);

#if defined(USE_HAL_DRIVER)
        pwmICConfig(timer->tim, timer->channel, TIM_ICPOLARITY_RISING);
#else
        pwmICConfig(timer->tim, timer->channel, TIM_ICPolarity_Rising);
#endif

    }
}
Пример #5
0
void ledInit(const statusLedConfig_t *statusLedConfig)
{
    LED0_OFF;
    LED1_OFF;
    LED2_OFF;

    ledPolarity = statusLedConfig->polarity;
    for (int i = 0; i < LED_NUMBER; i++) {
        if (statusLedConfig->ledTags[i]) {
            leds[i] = IOGetByTag(statusLedConfig->ledTags[i]);
            IOInit(leds[i], OWNER_LED, RESOURCE_INDEX(i));
            IOConfigGPIO(leds[i], IOCFG_OUT_PP);
        } else {
            leds[i] = IO_NONE;
        }
    }

    LED0_OFF;
    LED1_OFF;
    LED2_OFF;
}
Пример #6
0
void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)
{
    pwmInputPort_t *self = &pwmInputPorts[channel];

    self->state = 0;
    self->missedEvents = 0;
    self->channel = channel;
    self->mode = INPUT_MODE_PWM;
    self->timerHardware = timerHardwarePtr;

    IO_t io = IOGetByTag(timerHardwarePtr->tag);
    IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel));
    IOConfigGPIO(io, timerHardwarePtr->ioMode);

    pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);

    timerConfigure(timerHardwarePtr, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_MHZ);

    timerChCCHandlerInit(&self->edgeCb, pwmEdgeCallback);
    timerChOvrHandlerInit(&self->overflowCb, pwmOverflowCallback);
    timerChConfigCallbacks(timerHardwarePtr, &self->edgeCb, &self->overflowCb);
}
Пример #7
0
void i2cInit(I2CDevice device)
{
    if (device == I2CINVALID)
        return;

    i2cDevice_t *i2c;
    i2c = &(i2cHardwareMap[device]);

    NVIC_InitTypeDef nvic;
    I2C_InitTypeDef i2cInit;

    IO_t scl = IOGetByTag(i2c->scl);
    IO_t sda = IOGetByTag(i2c->sda);

    IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
    IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));

    // Enable RCC
    RCC_ClockCmd(i2c->rcc, ENABLE);

    I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE);

    i2cUnstick(scl, sda);

    // Init pins
#ifdef STM32F4
    IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);
    IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C);
#else
    IOConfigGPIO(scl, IOCFG_I2C);
    IOConfigGPIO(sda, IOCFG_I2C);
#endif

    I2C_DeInit(i2c->dev);
    I2C_StructInit(&i2cInit);

    I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE);               // Disable EVT and ERR interrupts - they are enabled by the first request
    i2cInit.I2C_Mode = I2C_Mode_I2C;
    i2cInit.I2C_DutyCycle = I2C_DutyCycle_2;
    i2cInit.I2C_OwnAddress1 = 0;
    i2cInit.I2C_Ack = I2C_Ack_Enable;
    i2cInit.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;

    if (i2c->overClock) {
        i2cInit.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues
    } else {
        i2cInit.I2C_ClockSpeed = 400000; // 400khz Operation according specs
    }

    I2C_Cmd(i2c->dev, ENABLE);
    I2C_Init(i2c->dev, &i2cInit);

    I2C_StretchClockCmd(i2c->dev, ENABLE);


    // I2C ER Interrupt
    nvic.NVIC_IRQChannel = i2c->er_irq;
    nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER);
    nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER);
    nvic.NVIC_IRQChannelCmd = ENABLE;
    NVIC_Init(&nvic);

    // I2C EV Interrupt
    nvic.NVIC_IRQChannel = i2c->ev_irq;
    nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV);
    nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV);
    NVIC_Init(&nvic);
}
Пример #8
0
serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, uint32_t baud, portMode_t mode, portOptions_t options)
{
    softSerial_t *softSerial = &(softSerialPorts[portIndex]);

    int pinCfgIndex = portIndex + RESOURCE_SOFT_OFFSET;

    ioTag_t tagRx = serialPinConfig()->ioTagRx[pinCfgIndex];
    ioTag_t tagTx = serialPinConfig()->ioTagTx[pinCfgIndex];

    const timerHardware_t *timerRx = timerGetByTag(tagRx, TIM_USE_ANY);
    const timerHardware_t *timerTx = timerGetByTag(tagTx, TIM_USE_ANY);

    IO_t rxIO = IOGetByTag(tagRx);
    IO_t txIO = IOGetByTag(tagTx);

    if (options & SERIAL_BIDIR) {
        // If RX and TX pins are both assigned, we CAN use either with a timer.
        // However, for consistency with hardware UARTs, we only use TX pin,
        // and this pin must have a timer.
        if (!timerTx)
            return NULL;

        softSerial->timerHardware = timerTx;
        softSerial->txIO = txIO;
        softSerial->rxIO = txIO;
        IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex) + RESOURCE_SOFT_OFFSET);
    } else {
        if (mode & MODE_RX) {
            // Need a pin & a timer on RX
            if (!(tagRx && timerRx))
                return NULL;

            softSerial->rxIO = rxIO;
            softSerial->timerHardware = timerRx;
            IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(portIndex) + RESOURCE_SOFT_OFFSET);
        }

        if (mode & MODE_TX) {
            // Need a pin on TX
            if (!tagTx)
                return NULL;

            softSerial->txIO = txIO;

            if (!(mode & MODE_RX)) {
                // TX Simplex, must have a timer
                if (!timerTx)
                    return NULL;
                softSerial->timerHardware = timerTx;
            } else {
                // Duplex
                softSerial->exTimerHardware = timerTx;
            }
            IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex) + RESOURCE_SOFT_OFFSET);
        }
    }

    softSerial->port.vTable = &softSerialVTable;
    softSerial->port.baudRate = baud;
    softSerial->port.mode = mode;
    softSerial->port.options = options;
    softSerial->port.rxCallback = rxCallback;

    resetBuffers(softSerial);

    softSerial->softSerialPortIndex = portIndex;

    softSerial->transmissionErrors = 0;
    softSerial->receiveErrors = 0;

    softSerial->rxActive = false;
    softSerial->isTransmittingData = false;

    // Configure master timer (on RX); time base and input capture

    serialTimerConfigureTimebase(softSerial->timerHardware, baud);
    timerChConfigIC(softSerial->timerHardware, (options & SERIAL_INVERTED) ? ICPOLARITY_RISING : ICPOLARITY_FALLING, 0);

    // Initialize callbacks
    timerChCCHandlerInit(&softSerial->edgeCb, onSerialRxPinChange);
    timerChOvrHandlerInit(&softSerial->overCb, onSerialTimerOverflow);

    // Configure bit clock interrupt & handler.
    // If we have an extra timer (on TX), it is initialized and configured
    // for overflow interrupt.
    // Receiver input capture is configured when input is activated.

    if ((mode & MODE_TX) && softSerial->exTimerHardware && softSerial->exTimerHardware->tim != softSerial->timerHardware->tim) {
        softSerial->timerMode = TIMER_MODE_DUAL;
        serialTimerConfigureTimebase(softSerial->exTimerHardware, baud);
        timerChConfigCallbacks(softSerial->exTimerHardware, NULL, &softSerial->overCb);
        timerChConfigCallbacks(softSerial->timerHardware, &softSerial->edgeCb, NULL);
    } else {
        softSerial->timerMode = TIMER_MODE_SINGLE;
        timerChConfigCallbacks(softSerial->timerHardware, &softSerial->edgeCb, &softSerial->overCb);
    }

#ifdef USE_HAL_DRIVER
    softSerial->timerHandle = timerFindTimerHandle(softSerial->timerHardware->tim);
#endif

    if (!(options & SERIAL_BIDIR)) {
        serialOutputPortActivate(softSerial);
        setTxSignal(softSerial, ENABLE);
    }

    serialInputPortActivate(softSerial);

    return &softSerial->port;
}
Пример #9
0
void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType)
{
    motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
    motor->timerHardware = timerHardware;

    TIM_TypeDef *timer = timerHardware->tim;
    const IO_t motorIO = IOGetByTag(timerHardware->tag);

    const uint8_t timerIndex = getTimerIndex(timer);
    const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);

    IOInit(motorIO, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
    IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction);

    __DMA1_CLK_ENABLE();

    if (configureTimer) {
        RCC_ClockCmd(timerRCC(timer), ENABLE);

        uint32_t hz;
        switch (pwmProtocolType) {
            case(PWM_TYPE_DSHOT600):
                hz = MOTOR_DSHOT600_MHZ * 1000000;
                break;
            case(PWM_TYPE_DSHOT300):
                hz = MOTOR_DSHOT300_MHZ * 1000000;
                break;
            default:
            case(PWM_TYPE_DSHOT150):
                hz = MOTOR_DSHOT150_MHZ * 1000000;
        }

        motor->TimHandle.Instance = timerHardware->tim;
        motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / hz) - 1;;
        motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
        motor->TimHandle.Init.RepetitionCounter = 0;
        motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
        motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
        if(HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK)
        {
            /* Initialization Error */
            return;
        }

    }
    else
    {
        motor->TimHandle = dmaMotors[timerIndex].TimHandle;
    }

    switch (timerHardware->channel) {
        case TIM_CHANNEL_1:
            motor->timerDmaSource = TIM_DMA_ID_CC1;
            break;
        case TIM_CHANNEL_2:
            motor->timerDmaSource = TIM_DMA_ID_CC2;
            break;
        case TIM_CHANNEL_3:
            motor->timerDmaSource = TIM_DMA_ID_CC3;
            break;
        case TIM_CHANNEL_4:
            motor->timerDmaSource = TIM_DMA_ID_CC4;
            break;
    }

    dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource;

    /* Set the parameters to be configured */
    motor->hdma_tim.Init.Channel  = timerHardware->dmaChannel;
    motor->hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH;
    motor->hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE;
    motor->hdma_tim.Init.MemInc = DMA_MINC_ENABLE;
    motor->hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
    motor->hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
    motor->hdma_tim.Init.Mode = DMA_NORMAL;
    motor->hdma_tim.Init.Priority = DMA_PRIORITY_HIGH;
    motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
    motor->hdma_tim.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
    motor->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE;
    motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;

    /* Set hdma_tim instance */
    if(timerHardware->dmaStream == NULL)
    {
        /* Initialization Error */
        return;
    }
    motor->hdma_tim.Instance = timerHardware->dmaStream;

    /* Link hdma_tim to hdma[x] (channelx) */
    __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], motor->hdma_tim);

    dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
    dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);

    /* Initialize TIMx DMA handle */
    if(HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK)
    {
        /* Initialization Error */
        return;
    }

    TIM_OC_InitTypeDef TIM_OCInitStructure;

    /* PWM1 Mode configuration: Channel1 */
    TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1;
    TIM_OCInitStructure.OCPolarity = TIM_OCPOLARITY_HIGH;
    TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET;
    TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
    TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
    TIM_OCInitStructure.Pulse = 0;

    if(HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK)
    {
        /* Configuration Error */
        return;
    }
}
Пример #10
0
void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
{
    motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
    motor->timerHardware = timerHardware;

    TIM_TypeDef *timer = timerHardware->tim;
    const IO_t motorIO = IOGetByTag(timerHardware->tag);

    const uint8_t timerIndex = getTimerIndex(timer);

    IOInit(motorIO, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
    IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction);

    __DMA1_CLK_ENABLE();

    RCC_ClockCmd(timerRCC(timer), ENABLE);

    motor->TimHandle.Instance = timerHardware->tim;
    motor->TimHandle.Init.Prescaler = (timerClock(timer) / getDshotHz(pwmProtocolType)) - 1;
    motor->TimHandle.Init.Period = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
    motor->TimHandle.Init.RepetitionCounter = 0;
    motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
    motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
    motor->TimHandle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
    if (HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK) {
        /* Initialization Error */
        return;
    }

    motor->timerDmaSource = timerDmaSource(timerHardware->channel);
    dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource;

    /* Set the parameters to be configured */
    motor->hdma_tim.Init.Channel = timerHardware->dmaChannel;
    motor->hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH;
    motor->hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE;
    motor->hdma_tim.Init.MemInc = DMA_MINC_ENABLE;
    motor->hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
    motor->hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
    motor->hdma_tim.Init.Mode = DMA_NORMAL;
    motor->hdma_tim.Init.Priority = DMA_PRIORITY_HIGH;
    motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
    motor->hdma_tim.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
    motor->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE;
    motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;

    /* Set hdma_tim instance */
    if (timerHardware->dmaRef == NULL) {
        /* Initialization Error */
        return;
    }
    motor->hdma_tim.Instance = timerHardware->dmaRef;

    /* Link hdma_tim to hdma[x] (channelx) */
    __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], motor->hdma_tim);

    dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
    dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);

    /* Initialize TIMx DMA handle */
    if (HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK) {
        /* Initialization Error */
        return;
    }

    TIM_OC_InitTypeDef TIM_OCInitStructure;

    /* PWM1 Mode configuration: Channel1 */
    TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1;
    if (output & TIMER_OUTPUT_N_CHANNEL) {
        TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET;
        TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_HIGH : TIM_OCPOLARITY_LOW;
        TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
        TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_HIGH : TIM_OCNPOLARITY_LOW;
    } else {
        TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_SET;
        TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_LOW : TIM_OCPOLARITY_HIGH;
        TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_SET;
        TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_LOW : TIM_OCNPOLARITY_HIGH;
    }
    TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
    TIM_OCInitStructure.Pulse = 0;

    if (HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK) {
        /* Configuration Error */
        return;
    }
}
Пример #11
0
void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount)
{
    uint32_t timerMhzCounter = 0;
    pwmWriteFuncPtr pwmWritePtr;
    bool useUnsyncedPwm = motorConfig->useUnsyncedPwm;
    bool isDigital = false;

    switch (motorConfig->motorPwmProtocol) {
    default:
    case PWM_TYPE_ONESHOT125:
        timerMhzCounter = ONESHOT125_TIMER_MHZ;
        pwmWritePtr = pwmWriteOneShot125;
        break;
    case PWM_TYPE_ONESHOT42:
        timerMhzCounter = ONESHOT42_TIMER_MHZ;
        pwmWritePtr = pwmWriteOneShot42;
        break;
    case PWM_TYPE_MULTISHOT:
        timerMhzCounter = MULTISHOT_TIMER_MHZ;
        pwmWritePtr = pwmWriteMultiShot;
        break;
    case PWM_TYPE_BRUSHED:
        timerMhzCounter = PWM_BRUSHED_TIMER_MHZ;
        pwmWritePtr = pwmWriteBrushed;
        useUnsyncedPwm = true;
        idlePulse = 0;
        break;
    case PWM_TYPE_STANDARD:
        timerMhzCounter = PWM_TIMER_MHZ;
        pwmWritePtr = pwmWriteStandard;
        useUnsyncedPwm = true;
        idlePulse = 0;
        break;
#ifdef USE_DSHOT
    case PWM_TYPE_DSHOT600:
    case PWM_TYPE_DSHOT300:
    case PWM_TYPE_DSHOT150:
        pwmCompleteWritePtr = pwmCompleteDigitalMotorUpdate;
        isDigital = true;
        break;
#endif
    }

    if (!useUnsyncedPwm && !isDigital) {
        pwmCompleteWritePtr = pwmCompleteOneshotMotorUpdate;
    }

    for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
        const ioTag_t tag = motorConfig->ioTags[motorIndex];

        if (!tag) {
            break;
        }

        const timerHardware_t *timerHardware = timerGetByTag(tag, TIM_USE_ANY);

        if (timerHardware == NULL) {
            /* flag failure and disable ability to arm */
            break;
        }

        motors[motorIndex].io = IOGetByTag(tag);

#ifdef USE_DSHOT
        if (isDigital) {
            pwmDigitalMotorHardwareConfig(timerHardware, motorIndex, motorConfig->motorPwmProtocol);
            motors[motorIndex].pwmWritePtr = pwmWriteDigital;
            motors[motorIndex].enabled = true;
            continue;
        }
#endif

        IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
        IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP);

        motors[motorIndex].pwmWritePtr = pwmWritePtr;
        if (useUnsyncedPwm) {
            const uint32_t hz = timerMhzCounter * 1000000;
            pwmOutConfig(&motors[motorIndex], timerHardware, timerMhzCounter, hz / motorConfig->motorPwmRate, idlePulse);
        } else {
            pwmOutConfig(&motors[motorIndex], timerHardware, timerMhzCounter, 0xFFFF, 0);
        }
        motors[motorIndex].enabled = true;
    }
}
Пример #12
0
void spiInitDevice(SPIDevice device)
{
    spiDevice_t *spi = &(spiHardwareMap[device]);

#ifdef SDCARD_SPI_INSTANCE
    if (spi->dev == SDCARD_SPI_INSTANCE) {
        spi->leadingEdge = true;
    }
#endif
#ifdef RX_SPI_INSTANCE
    if (spi->dev == RX_SPI_INSTANCE) {
        spi->leadingEdge = true;
    }
#endif

    // Enable SPI clock
    RCC_ClockCmd(spi->rcc, ENABLE);
    RCC_ResetCmd(spi->rcc, ENABLE);

    IOInit(IOGetByTag(spi->sck),  OWNER_SPI_SCK,  RESOURCE_INDEX(device));
    IOInit(IOGetByTag(spi->miso), OWNER_SPI_MISO, RESOURCE_INDEX(device));
    IOInit(IOGetByTag(spi->mosi), OWNER_SPI_MOSI, RESOURCE_INDEX(device));

#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
    IOConfigGPIOAF(IOGetByTag(spi->sck),  SPI_IO_AF_CFG, spi->af);
    IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af);
    IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);

    if (spi->nss) {
        IOInit(IOGetByTag(spi->nss), OWNER_SPI_CS, RESOURCE_INDEX(device));
        IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af);
    }
#endif
#if defined(STM32F10X)
    IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG);
    IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG);
    IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG);

    if (spi->nss) {
        IOInit(IOGetByTag(spi->nss), OWNER_SPI_CS, RESOURCE_INDEX(device));
        IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG);
    }
#endif
    spiHardwareMap[device].hspi.Instance = spi->dev;
    // Init SPI hardware
    HAL_SPI_DeInit(&spiHardwareMap[device].hspi);

    spiHardwareMap[device].hspi.Init.Mode = SPI_MODE_MASTER;
    spiHardwareMap[device].hspi.Init.Direction = SPI_DIRECTION_2LINES;
    spiHardwareMap[device].hspi.Init.DataSize = SPI_DATASIZE_8BIT;
    spiHardwareMap[device].hspi.Init.NSS = SPI_NSS_SOFT;
    spiHardwareMap[device].hspi.Init.FirstBit = SPI_FIRSTBIT_MSB;
    spiHardwareMap[device].hspi.Init.CRCPolynomial = 7;
    spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
    spiHardwareMap[device].hspi.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
    spiHardwareMap[device].hspi.Init.TIMode = SPI_TIMODE_DISABLED;

    if (spi->leadingEdge) {
        spiHardwareMap[device].hspi.Init.CLKPolarity = SPI_POLARITY_LOW;
        spiHardwareMap[device].hspi.Init.CLKPhase = SPI_PHASE_1EDGE;
    }
    else {
        spiHardwareMap[device].hspi.Init.CLKPolarity = SPI_POLARITY_HIGH;
        spiHardwareMap[device].hspi.Init.CLKPhase = SPI_PHASE_2EDGE;
    }

    if (HAL_SPI_Init(&spiHardwareMap[device].hspi) == HAL_OK)
    {
        if (spi->nss) {
            IOHi(IOGetByTag(spi->nss));
        }
    }
}
Пример #13
0
static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex)
{
    IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex));
    IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP);
}
Пример #14
0
void i2cInit(I2CDevice device)
{
    if (device == I2CINVALID) {
        return;
    }

    i2cDevice_t *pDev = &i2cDevice[device];

    const i2cHardware_t *hardware = pDev->hardware;

    if (!hardware) {
        return;
    }

    IO_t scl = pDev->scl;
    IO_t sda = pDev->sda;

    IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
    IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));

    // Enable RCC
    RCC_ClockCmd(hardware->rcc, ENABLE);

    i2cUnstick(scl, sda);

    // Init pins
#ifdef STM32F7
    IOConfigGPIOAF(scl, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF4_I2C);
    IOConfigGPIOAF(sda, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF4_I2C);
#else
    IOConfigGPIO(scl, IOCFG_AF_OD);
    IOConfigGPIO(sda, IOCFG_AF_OD);
#endif

    // Init I2C peripheral

    I2C_HandleTypeDef *pHandle = &pDev->handle;

    memset(pHandle, 0, sizeof(*pHandle));

    pHandle->Instance = pDev->hardware->reg;

    /// TODO: HAL check if I2C timing is correct

    if (pDev->overClock) {
        // 800khz Maximum speed tested on various boards without issues
        pHandle->Init.Timing = 0x00500D1D;
    } else {
        pHandle->Init.Timing = 0x00500C6F;
    }

    pHandle->Init.OwnAddress1 = 0x0;
    pHandle->Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
    pHandle->Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
    pHandle->Init.OwnAddress2 = 0x0;
    pHandle->Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
    pHandle->Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;

    HAL_I2C_Init(pHandle);

    // Enable the Analog I2C Filter
    HAL_I2CEx_ConfigAnalogFilter(pHandle, I2C_ANALOGFILTER_ENABLE);

    // Setup interrupt handlers
    HAL_NVIC_SetPriority(hardware->er_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER));
    HAL_NVIC_EnableIRQ(hardware->er_irq);
    HAL_NVIC_SetPriority(hardware->ev_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV));
    HAL_NVIC_EnableIRQ(hardware->ev_irq);
}
Пример #15
0
void i2cInit(I2CDevice device)
{
    /*## Configure the I2C clock source. The clock is derived from the SYSCLK #*/
//    RCC_PeriphCLKInitTypeDef  RCC_PeriphCLKInitStruct;
//    RCC_PeriphCLKInitStruct.PeriphClockSelection = i2cHardwareMap[device].clk;
//    RCC_PeriphCLKInitStruct.I2c1ClockSelection = i2cHardwareMap[device].clk_src;
//    HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphCLKInitStruct);

    switch (device) {
    case I2CDEV_1:
        __HAL_RCC_I2C1_CLK_ENABLE();
        break;
    case I2CDEV_2:
        __HAL_RCC_I2C2_CLK_ENABLE();
        break;
    case I2CDEV_3:
        __HAL_RCC_I2C3_CLK_ENABLE();
        break;
    case I2CDEV_4:
        __HAL_RCC_I2C4_CLK_ENABLE();
        break;
    default:
        break;
    }
    if (device == I2CINVALID)
        return;

    i2cDevice_t *i2c;
    i2c = &(i2cHardwareMap[device]);

    //I2C_InitTypeDef i2cInit;

    IO_t scl = IOGetByTag(i2c->scl);
    IO_t sda = IOGetByTag(i2c->sda);

    IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
    IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));

    // Enable RCC
    RCC_ClockCmd(i2c->rcc, ENABLE);


    i2cUnstick(scl, sda);

    // Init pins
#ifdef STM32F7
    IOConfigGPIOAF(scl, IOCFG_I2C, i2c->af);
    IOConfigGPIOAF(sda, IOCFG_I2C, i2c->af);
#else
    IOConfigGPIO(scl, IOCFG_AF_OD);
    IOConfigGPIO(sda, IOCFG_AF_OD);
#endif
    // Init I2C peripheral
    HAL_I2C_DeInit(&i2cHandle[device].Handle);

    i2cHandle[device].Handle.Instance             = i2cHardwareMap[device].dev;
    /// TODO: HAL check if I2C timing is correct
    i2cHandle[device].Handle.Init.Timing          = 0x00B01B59;
    //i2cHandle[device].Handle.Init.Timing          = 0x00D00E28; /* (Rise time = 120ns, Fall time = 25ns) */
    i2cHandle[device].Handle.Init.OwnAddress1     = 0x0;
    i2cHandle[device].Handle.Init.AddressingMode  = I2C_ADDRESSINGMODE_7BIT;
    i2cHandle[device].Handle.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
    i2cHandle[device].Handle.Init.OwnAddress2     = 0x0;
    i2cHandle[device].Handle.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
    i2cHandle[device].Handle.Init.NoStretchMode   = I2C_NOSTRETCH_DISABLE;


    HAL_I2C_Init(&i2cHandle[device].Handle);
    /* Enable the Analog I2C Filter */
    HAL_I2CEx_ConfigAnalogFilter(&i2cHandle[device].Handle,I2C_ANALOGFILTER_ENABLE);

    HAL_NVIC_SetPriority(i2cHardwareMap[device].er_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER));
    HAL_NVIC_EnableIRQ(i2cHardwareMap[device].er_irq);
    HAL_NVIC_SetPriority(i2cHardwareMap[device].ev_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV));
    HAL_NVIC_EnableIRQ(i2cHardwareMap[device].ev_irq);
}
Пример #16
0
void i2cInit(I2CDevice device)
{

    i2cDevice_t *i2c;
    i2c = &(i2cHardwareMap[device]);

    I2C_TypeDef *I2Cx;
    I2Cx = i2c->dev;
  
    IO_t scl = IOGetByTag(i2c->scl);
    IO_t sda = IOGetByTag(i2c->sda);

    RCC_ClockCmd(i2c->rcc, ENABLE);
    RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);

    IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
    IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);

    IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
    IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);

    I2C_InitTypeDef i2cInit = {
        .I2C_Mode = I2C_Mode_I2C,
        .I2C_AnalogFilter = I2C_AnalogFilter_Enable,
        .I2C_DigitalFilter = 0x00,
        .I2C_OwnAddress1 = 0x00,
        .I2C_Ack = I2C_Ack_Enable,
        .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
        .I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING)
    };

    I2C_Init(I2Cx, &i2cInit);

    I2C_StretchClockCmd(I2Cx, ENABLE);
 
    I2C_Cmd(I2Cx, ENABLE);
}

uint16_t i2cGetErrorCounter(void)
{
    return i2cErrorCount;
}

bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
{
    addr_ <<= 1;

    I2C_TypeDef *I2Cx;
    I2Cx = i2cHardwareMap[device].dev;

    /* Test on BUSY Flag */
    i2cTimeout = I2C_LONG_TIMEOUT;
    while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
        if ((i2cTimeout--) == 0) {
            return i2cTimeoutUserCallback();
        }
    }

        /* Configure slave address, nbytes, reload, end mode and start or stop generation */
    I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);

        /* Wait until TXIS flag is set */
    i2cTimeout = I2C_LONG_TIMEOUT;
    while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
        if ((i2cTimeout--) == 0) {
            return i2cTimeoutUserCallback();
        }
    }

        /* Send Register address */
    I2C_SendData(I2Cx, (uint8_t) reg);

        /* Wait until TCR flag is set */
    i2cTimeout = I2C_LONG_TIMEOUT;
    while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
    {
        if ((i2cTimeout--) == 0) {
            return i2cTimeoutUserCallback();
        }
    }

        /* Configure slave address, nbytes, reload, end mode and start or stop generation */
    I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);

        /* Wait until TXIS flag is set */
    i2cTimeout = I2C_LONG_TIMEOUT;
    while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
        if ((i2cTimeout--) == 0) {
            return i2cTimeoutUserCallback();
        }
    }

        /* Write data to TXDR */
    I2C_SendData(I2Cx, data);

        /* Wait until STOPF flag is set */
    i2cTimeout = I2C_LONG_TIMEOUT;
    while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
        if ((i2cTimeout--) == 0) {
            return i2cTimeoutUserCallback();
        }
    }

        /* Clear STOPF flag */
    I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);

    return true;
}
Пример #17
0
void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType)
{
    TIM_OCInitTypeDef TIM_OCInitStructure;
    DMA_InitTypeDef DMA_InitStructure;

    motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
    motor->timerHardware = timerHardware;

    TIM_TypeDef *timer = timerHardware->tim;
    const IO_t motorIO = IOGetByTag(timerHardware->tag);

    const uint8_t timerIndex = getTimerIndex(timer);
    const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);

    IOInit(motorIO, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
    IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction);

    if (configureTimer) {
        TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
        TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);

        RCC_ClockCmd(timerRCC(timer), ENABLE);
        TIM_Cmd(timer, DISABLE);

        uint32_t hz;
        switch (pwmProtocolType) {
            case(PWM_TYPE_DSHOT600):
                hz = MOTOR_DSHOT600_MHZ * 1000000;
                break;
            case(PWM_TYPE_DSHOT300):
                hz = MOTOR_DSHOT300_MHZ * 1000000;
                break;
            default:
            case(PWM_TYPE_DSHOT150):
                hz = MOTOR_DSHOT150_MHZ * 1000000;
        }

        TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((SystemCoreClock / timerClockDivisor(timer) / hz) - 1);
        TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH;
        TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
        TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
        TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
        TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
    }

    TIM_OCStructInit(&TIM_OCInitStructure);
    TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
    if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
        TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
        TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
        TIM_OCInitStructure.TIM_OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_Low : TIM_OCNPolarity_High;
    } else {
        TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
        TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
        TIM_OCInitStructure.TIM_OCPolarity =  (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
    }
    TIM_OCInitStructure.TIM_Pulse = 0;

    timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure);
    timerOCPreloadConfig(timer, timerHardware->channel, TIM_OCPreload_Enable);
    motor->timerDmaSource = timerDmaSource(timerHardware->channel);
    dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource;

    TIM_CCxCmd(timer, timerHardware->channel, TIM_CCx_Enable);

    if (configureTimer) {
        TIM_CtrlPWMOutputs(timer, ENABLE);
        TIM_ARRPreloadConfig(timer, ENABLE);
        TIM_Cmd(timer, ENABLE);
    }

    DMA_Channel_TypeDef *channel = timerHardware->dmaChannel;

    if (channel == NULL) {
        /* trying to use a non valid channel */
        return;
    }

    dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
    dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);

    DMA_Cmd(channel, DISABLE);
    DMA_DeInit(channel);
    DMA_StructInit(&DMA_InitStructure);
    DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware);
    DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)motor->dmaBuffer;
    DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
    DMA_InitStructure.DMA_BufferSize = MOTOR_DMA_BUFFER_SIZE;
    DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
    DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
    DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
    DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
    DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
    DMA_InitStructure.DMA_Priority = DMA_Priority_High;
    DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;

    DMA_Init(channel, &DMA_InitStructure);

    DMA_ITConfig(channel, DMA_IT_TC, ENABLE);
}