cancel
Showing results for 
Search instead for 
Did you mean: 

Trigger ADC with TIM2 TRGO not showing correct timing

cristianosar
Associate II

Im using the following code that is part of a metal detector I'm building. Im trying to trigger the ADC based on TRGO of TIM2 (I need dma / adc readings every 10us after the of each TX pulse). I expect the TIM2_IRQHandler interrupt to enter 10us (ADC_DELAY_US) after the TX pulse ends (TIM1_CC_IRQHandler). I added a buffer (buffer variable) to keep track of the milliseconds of the events but when I print it on gdb (print buffer) and then subtract tx_end_micros to adc_start_micros, I dont have 10us, as expected:

This is a print of the gdb:

 {{tx_end_micros = 2573435545, adc_start_micros = 2573437222, num_pulses = 2624525, num_pulses_tim2 = 2624526}, {tx_end_micros = 2573436545, adc_start_micros = 2573436542, 
    num_pulses = 2624526, num_pulses_tim2 = 2624527}}

Below is the full code:

#include <stdio.h>
#include "stm32f4xx.h"
#include <math.h>

// Function Prototypes
void SystemClock_Config(void);
void GPIO_Init(void);
void TIM1_PWM_Init(void);
void TIM5_Init(void);
void LED_Init(void);
void TIM2_TRGO_Init(void);
void ADC1_Trigger_TIM2_Setup(void);
uint16_t adc1_read(void);
float compute_average(void);
void Delay_us(uint32_t);
void send_uart(char *msg);
uint32_t micros(void);
void toggle_led(void);
void enviar_dados_adc_serial(void);
void reset_adc(void);

// Settings
#define ADC_DELAY_US 10      // Delay after TX pulse before ADC sampling
#define NUM_SAMPLES 64       // Number of ADC samples to capture

// For alignment in memory
volatile uint16_t adc_buffer[NUM_SAMPLES] __attribute__((aligned(4)));
volatile uint32_t tx_num_pulses = 0;
volatile uint8_t adc_capture_complete = 0;

typedef struct {
    uint32_t tx_end_micros;
    uint32_t adc_start_micros;
    uint32_t num_pulses;
    uint32_t num_pulses_tim2;
} TimingData;

volatile TimingData buffer[2];
volatile uint8_t current_buffer = 0;

volatile TimingData timing;  // Global instance, accessible in both ISRs

volatile uint32_t last_time;
volatile uint32_t curr_time = 0;
volatile uint32_t delta = 0;

void delay_ms(int milliseconds) {
    volatile int i;
    for (i = 0; i < milliseconds * 1000; i++) {
        __NOP();  // No operation, just waste time
    }
}

void reset_adc() {
    // Reset DMA for next capture
    ADC1->CR2 &= ~ADC_CR2_DMA; // Desliga DMA
    ADC1->CR2 |= ADC_CR2_DMA;  // Religa DMA
    DMA2_Stream0->CR &= ~DMA_SxCR_EN;
    while (DMA2_Stream0->CR & DMA_SxCR_EN);
    
    // Clear DMA flags
    DMA2->LIFCR |= DMA_LIFCR_CTCIF0 | DMA_LIFCR_CHTIF0 |
                    DMA_LIFCR_CTEIF0 | DMA_LIFCR_CDMEIF0 | DMA_LIFCR_CFEIF0;
    
    // Reset DMA counter
    DMA2_Stream0->NDTR = NUM_SAMPLES;
    // Re-enable DMA
    DMA2_Stream0->CR |= DMA_SxCR_EN;
}

void ADC1_Trigger_TIM2_Setup(void) {
    RCC->APB2ENR |= RCC_APB2ENR_ADC1EN;
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
    GPIOA->MODER |= (3 << (1 * 2)); // PA1 analog mode

    ADC1->CR2 = 0; // rests all (not using continuous capture)
    ADC1->CR2 |= ADC_CR2_ADON;
    Delay_us(1); // Small delay for ADC stabilization

    ADC1->SMPR2 = 0; // 3 cycles sampling time (channels 0-9)
    ADC1->SQR3 = 1; // Channel 1 (PA1)
    
    // Configure for TIM2_TRGO triggering
    ADC1->CR2 &= ~(0xF << ADC_CR2_EXTSEL_Pos); // Clear EXTSEL
    ADC1->CR2 |= (6 << ADC_CR2_EXTSEL_Pos);    // TIM2_TRGO
    ADC1->CR2 |= (1 << ADC_CR2_EXTEN_Pos);     // Rising edge

    // Configure DMA
    ADC1->CR2 |= ADC_CR2_DMA;  // Enable DMA

    ADC1->CR2 &= ~ADC_CR2_CONT;  // Desativa modo contínuo
}


void TIM2_TRGO_Init(void) {
    RCC->APB1ENR |= RCC_APB1ENR_TIM2EN;

    TIM2->PSC = 84 - 1;       // 1 µs per tick
    TIM2->ARR = ADC_DELAY_US - 1;  // Count to delay value
    TIM2->CNT = 0;

    // Configure TIM2 to generate TRGO on Update event
    TIM2->CR2 &= ~TIM_CR2_MMS;
    TIM2->CR2 |= TIM_CR2_MMS_1; // MMS = 010 = Update Event

    // Configure TIM2 as slave of TIM1 in Trigger mode (starts when receiving trigger)
    TIM2->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_TS);  // Clear all
    TIM2->SMCR |= (0x6 << TIM_SMCR_SMS_Pos);      // SMS=110 (Trigger Mode)
    TIM2->SMCR |= (0x0 << TIM_SMCR_TS_Pos);       // TS=000 (ITR0 = TIM1)
    TIM2->SMCR |= (0x6 << TIM_SMCR_SMS_Pos); // SMS=110 (Trigger Mode)

    // Enable one-pulse mode so TIM2 stops after one cycle (form dma in non circular mode)
    // TIM2->CR1 |= TIM_CR1_OPM;

    // Enable update interrupt for TIM2
    TIM2->DIER |= TIM_DIER_UIE;
    NVIC_EnableIRQ(TIM2_IRQn);
}

void DMA2_Stream0_ADC_Config(void) {
    RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; // Enable DMA2 clock

    // Make sure stream is disabled
    DMA2_Stream0->CR &= ~DMA_SxCR_EN;
    while (DMA2_Stream0->CR & DMA_SxCR_EN); // Wait for deactivation

    // Clear interrupt flags
    DMA2->LIFCR |= DMA_LIFCR_CTCIF0 | DMA_LIFCR_CHTIF0 |
                   DMA_LIFCR_CTEIF0 | DMA_LIFCR_CDMEIF0 | DMA_LIFCR_CFEIF0;

    // Configure peripheral address (ADC1_DR)
    DMA2_Stream0->PAR = (uint32_t)&ADC1->DR;
    // Buffer address in memory
    DMA2_Stream0->M0AR = (uint32_t)&adc_buffer;
    // Number of transfers
    DMA2_Stream0->NDTR = NUM_SAMPLES;
    
    // Configure for channel 0 (ADC1)
    DMA2_Stream0->CR =
        (0 << DMA_SxCR_CHSEL_Pos) |  // Channel 0
        (1 << DMA_SxCR_MSIZE_Pos) |  // Memory 16 bits
        (1 << DMA_SxCR_PSIZE_Pos) |  // Peripheral 16 bits
        (1 << DMA_SxCR_MINC_Pos)  |  // Increment memory
        (0 << DMA_SxCR_PINC_Pos)  |  // Don't increment peripheral
        (0 << DMA_SxCR_CIRC_Pos)  |  // Normal mode (not circular) circular 1
        (0 << DMA_SxCR_DIR_Pos)   |  // Peripheral -> Memory
        (1 << DMA_SxCR_TCIE_Pos);    // Transfer complete interrupt

    // Enable DMA interrupt
    NVIC_EnableIRQ(DMA2_Stream0_IRQn);
}

void toggle_led() {
    GPIOD->ODR |= (1 << 12);  // Turn LED on
    Delay_us(10);
    GPIOD->ODR &= ~(1 << 12); // Turn LED off
}

void uart_init(void) {
    // Enable clocks for GPIOA and USART1
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
    RCC->APB2ENR |= RCC_APB2ENR_USART1EN;

    // Configure PA9 and PA10 for alternate function (AF7)
    // TX = PA9, RX = PA10
    GPIOA->MODER &= ~((3 << (9 * 2)) | (3 << (10 * 2)));  // clear bits
    GPIOA->MODER |=  (2 << (9 * 2)) | (2 << (10 * 2));    // alternate function mode

    GPIOA->AFR[1] &= ~((0xF << ((9 - 8) * 4)) | (0xF << ((10 - 8) * 4)));
    GPIOA->AFR[1] |=  (7 << ((9 - 8) * 4)) | (7 << ((10 - 8) * 4));  // AF7 (USART1)

    // Configure USART1: 115200 baud, 8N1
    USART1->BRR = 0x2D9;  // For 115200 baud with PCLK2 = 84 MHz
    USART1->CR1 = USART_CR1_TE | USART_CR1_UE;  // Enable transmitter and USART
}

void send_uart(char *msg) {
    while (*msg) {
        while (!(USART1->SR & USART_SR_TXE));  // wait for empty buffer
        USART1->DR = *msg++;
    }
}

int main(void) {
    // Configure system clock
    SystemClock_Config();

    // Initialize UART for debug via serial
    uart_init();

    // Initialize GPIO (PE13 as TIM1_CH3 Alternate Function)
    GPIO_Init();

    LED_Init();

    TIM5_Init();

    // Initialize TIM1 for PWM on PE13
    TIM1_PWM_Init();

    // Initialize TIM2 for ADC triggering
    TIM2_TRGO_Init();

    // Configure ADC and DMA
    DMA2_Stream0_ADC_Config();
    ADC1_Trigger_TIM2_Setup();

    while (1) {
        if (adc_capture_complete) {            
            // Reset flag
            adc_capture_complete = 0;
            
            /* // Reset DMA for next capture
            ADC1->CR2 &= ~ADC_CR2_DMA; // Desliga DMA
            ADC1->CR2 |= ADC_CR2_DMA;  // Religa DMA
            DMA2_Stream0->CR &= ~DMA_SxCR_EN;
            while (DMA2_Stream0->CR & DMA_SxCR_EN);
            
            // Clear DMA flags
            DMA2->LIFCR |= DMA_LIFCR_CTCIF0 | DMA_LIFCR_CHTIF0 |
                          DMA_LIFCR_CTEIF0 | DMA_LIFCR_CDMEIF0 | DMA_LIFCR_CFEIF0;
            
            // Reset DMA counter
            DMA2_Stream0->NDTR = NUM_SAMPLES;
            // Re-enable DMA
            DMA2_Stream0->CR |= DMA_SxCR_EN; */
        }
    }
}

void SystemClock_Config(void) {
    // 1. Enable HSE (High-Speed External Clock, typically 8 MHz)
    RCC->CR |= RCC_CR_HSEON;  
    while (!(RCC->CR & RCC_CR_HSERDY));  // Wait for HSE to stabilize
    
    // 2. Configure PLL to multiply frequency
    RCC->PLLCFGR = (8 << RCC_PLLCFGR_PLLM_Pos)  |  // HSE 8MHz /8 = 1MHz
                   (336 << RCC_PLLCFGR_PLLN_Pos) | // 1MHz × 336 = 336MHz
                   (0 << RCC_PLLCFGR_PLLP_Pos)  |  // 00 = divide by 2 → 168MHz
                   (7 << RCC_PLLCFGR_PLLQ_Pos)  |  // USB clock = 336/7 = 48MHz
                   RCC_PLLCFGR_PLLSRC_HSE;         // Use HSE as source

    // 3. Activate PLL
    RCC->CR |= RCC_CR_PLLON;
    while (!(RCC->CR & RCC_CR_PLLRDY));  // Wait for PLL to stabilize
    
    // 4. Configure bus frequencies to avoid overclock
    RCC->CFGR |= RCC_CFGR_HPRE_DIV1;   // AHB Prescaler = 1 (168 MHz)
    RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;  // APB1 Prescaler = 4 (42 MHz)
    RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;  // APB2 Prescaler = 2 (84 MHz)
    
    FLASH->ACR |= FLASH_ACR_LATENCY_5WS | FLASH_ACR_PRFTEN | FLASH_ACR_ICEN | FLASH_ACR_DCEN;

    // 6. Switch System Clock to PLL
    RCC->CFGR |= RCC_CFGR_SW_PLL;
    while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL);  // Wait for switch

    // Configure ADC clock
    ADC->CCR &= ~ADC_CCR_ADCPRE;       // Clear ADCPRE bits
    ADC->CCR |= (3 << ADC_CCR_ADCPRE_Pos);  // 11b → divide APB2 por 8 → ADCCLK = 84 / 8 = 10.5 MHz :white_heavy_check_mark:

    SystemCoreClockUpdate();
}

void GPIO_Init(void) {
    // Enable clocks for GPIOs A and E
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;  // Enable GPIOA clock (for PA8)
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIOEEN;  // Enable GPIOE clock

    // Configure PE13 as alternate function (TIM1_CH3)
    GPIOE->MODER &= ~(3 << (13 * 2));
    GPIOE->MODER |= (2 << (13 * 2));      // Alternate function mode
    GPIOE->OSPEEDR |= (3 << (13 * 2));    // High speed for PE13
    
    GPIOE->AFR[1] &= ~(0xF << ((13 - 8) * 4)); // Clear AFR[1] bits for PE13
    GPIOE->AFR[1] |= (1 << ((13 - 8) * 4));    // Set AF1 for PE13 (TIM1_CH3)

    // Configure PA8 as alternate function (TIM1_CH1)
    GPIOA->MODER &= ~(3 << (8 * 2));
    GPIOA->MODER |= (2 << (8 * 2));       // Alternate function mode
    GPIOA->OSPEEDR |= (3 << (8 * 2));     // High speed
    GPIOA->AFR[1] &= ~(0xF << ((8 - 8) * 4)); // Clear AF bits
    GPIOA->AFR[1] |= (1 << ((8 - 8) * 4));    // AF1 (TIM1_CH1)

    // Configure PA1 as analog input for ADC
    GPIOA->MODER |= GPIO_MODER_MODER1;  // Analog mode (0b11)

    // Debug pin (set PE1 as debug pin)
    GPIOE->MODER |= (1 << (1 * 2));  // PE1 as output
    GPIOE->ODR &= ~(1 << 1);         // Start low
}

// Timer used only for debug timing
void TIM5_Init(void) {
    // Enable clock for TIM5
    RCC->APB1ENR |= RCC_APB1ENR_TIM5EN;
    // APB1 is 42MHz, but timer clock is 2x that (84MHz)
    // For 1 µs resolution: 84MHz / 84 = 1MHz
    TIM5->PSC = 84 - 1;
    // Max auto-reload (32 bits)
    TIM5->ARR = 0xFFFFFFFF;
    // Start counting
    TIM5->CR1 |= TIM_CR1_CEN;
    // Reset TIM5 counter
    TIM5->CNT = 0;
}

uint32_t micros(void) {
    return TIM5->CNT;
}

void TIM1_PWM_Init(void) {
    // Enable TIM1 clock on APB2 bus
    RCC->APB2ENR |= RCC_APB2ENR_TIM1EN;

    // Set timer frequency (reduce clock to 1 MHz, so 1 tick = 1 µs)
    TIM1->PSC = 168-1;    // Prescaler (divides timer clock)
    // Set PWM period (1ms = 1000 µs)
    TIM1->ARR = 1000 - 1;  // Define maximum count (PWM period)
    // Set duty cycle (100 µs)
    TIM1->CCR3 = 100; // TX pulse width
    TIM1->CCR1 = 500; // 500µs pulse width (for PA8)

    // Configure TIM1 Channel 3 for PWM1 mode
    TIM1->CCMR2 &= ~TIM_CCMR2_OC3M; // Clear output mode bits for Channel 3
    TIM1->CCMR2 |= (6 << TIM_CCMR2_OC3M_Pos); // Set Channel 3 to PWM1 mode
    TIM1->CCMR2 |= TIM_CCMR2_OC3PE; // Enable Preload for CCR3
    // Configure polarity (active high)
    TIM1->CCER &= ~TIM_CCER_CC3P;
    TIM1->CCER |= TIM_CCER_CC3E; // Enable PWM output on Channel 3

    // Configure Channel 1 (for PA8 charge pump pulse) as PWM Mode 1
    TIM1->CCMR1 &= ~TIM_CCMR1_OC1M;
    TIM1->CCMR1 |= (6 << TIM_CCMR1_OC1M_Pos); // PWM Mode 1
    TIM1->CCMR1 |= TIM_CCMR1_OC1PE;           // Enable preload
    // Configure polarity (active high) and enable output
    TIM1->CCER &= ~TIM_CCER_CC1P;             // Active high
    TIM1->CCER |= TIM_CCER_CC1E;              // Enable output
    
    // Configure TIM1 to generate TRGO on OC3REF signal (when TX pulse ends)
    TIM1->CR2 &= ~TIM_CR2_MMS;
    //TIM1->CR2 |= TIM_CR2_MMS_1 | TIM_CR2_MMS_0; // MMS = 011 = OC3REF as trigger
    // TIM1->CR2 |= (TIM_CR2_MMS_1 | TIM_CR2_MMS_0);
    TIM1->CR2 |= (0x3 << TIM_CR2_MMS_Pos);  // MMS=011 (OC3REF = PWM end)

    // Enable interrupt at compare match (when CCR3 is reached)
    TIM1->DIER |= TIM_DIER_CC3IE;
    
    // Enable both compare and update interrupts
    TIM1->DIER |= TIM_DIER_CC3IE | TIM_DIER_UIE;
    NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn); // Enable update interrupt
    NVIC_EnableIRQ(TIM1_CC_IRQn);       // Enable compare interrupt

    // Start TIM1 counter, generating PWM
    TIM1->CR1 |= TIM_CR1_CEN;
    // Enable PWM output on physical pins (only for advanced timers like TIM1 and TIM8)
    TIM1->BDTR |= TIM_BDTR_MOE;
}

void LED_Init(void) {
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN;
    GPIOD->MODER |= (1 << (12 * 2));
    GPIOD->ODR &= ~(1 << 12);  // Ensure LED starts off
}

uint16_t adc1_read(void) {
    ADC1->CR2 |= ADC_CR2_SWSTART;          // Start conversion
    while (!(ADC1->SR & ADC_SR_EOC));      // Wait until conversion complete
    return ADC1->DR;                       // Read result
}

/* === Interrupt Handlers === */

// TIM1 update interrupt handler (debug: used only for debug of TX pulse start with LED)
void TIM1_UP_TIM10_IRQHandler(void) {
    if (TIM1->SR & TIM_SR_UIF) {
        TIM1->SR &= ~TIM_SR_UIF;
        // TX pulse start logic here if needed
    }
}

// TIM1 compare interrupt handler (at end of TX pulse)
void TIM1_CC_IRQHandler(void) {
    if (TIM1->SR & TIM_SR_CC3IF) {
        TIM1->SR &= ~TIM_SR_CC3IF;
        tx_num_pulses++;
        
        buffer[current_buffer].tx_end_micros = micros();
        buffer[current_buffer].num_pulses = tx_num_pulses;
        uint8_t buf = current_buffer ^ 1;
        current_buffer = buf;
    }
}

void TIM2_IRQHandler(void) {
    // Check if update interrupt occurred
    if (TIM2->SR & TIM_SR_UIF) {
        TIM2->SR &= ~TIM_SR_UIF;  // Clear interrupt flag
        
        buffer[current_buffer].adc_start_micros = micros();
        buffer[current_buffer].num_pulses_tim2 = tx_num_pulses;
    }
}

void DMA2_Stream0_IRQHandler(void) {
    if (DMA2->LISR & DMA_LISR_TCIF0) {
        // Clear the transfer complete flag
        DMA2->LIFCR |= DMA_LIFCR_CTCIF0;
        adc_capture_complete = 1;
    }
}

// --- Utilities ---
void Delay_us(uint32_t us) {
    volatile uint32_t count = us * (SystemCoreClock / 1000000) / 5;
    while (count--);
}

 

0 REPLIES 0