ADC integriert mit TIM-als Trigger und DMA zum Datenübertragen
This commit is contained in:
199
Source/ADC.cpp
Normal file
199
Source/ADC.cpp
Normal file
@@ -0,0 +1,199 @@
|
||||
/*
|
||||
* ADC.cpp
|
||||
*
|
||||
* Created on: Jul 1, 2023
|
||||
* Author: Carst
|
||||
*/
|
||||
#include <cstdint>
|
||||
#include <stm32g0xx_ll_adc.h>
|
||||
#include <stm32g0xx_ll_dma.h>
|
||||
#include <stm32g0xx_ll_gpio.h>
|
||||
#include <stm32g0xx_ll_tim.h>
|
||||
#include "ADC.hpp"
|
||||
#include <stdio.h>
|
||||
|
||||
typedef struct
|
||||
{
|
||||
std::uint16_t current;
|
||||
std::uint16_t temperature;
|
||||
}ADC_Samples_t;
|
||||
|
||||
static ADC_Samples_t samples[10];
|
||||
static std::uint16_t current;
|
||||
static std::uint16_t temperature;
|
||||
|
||||
extern "C" void DMA1_Channel1_IRQHandler(void) /* DMA1 Channel 1 */
|
||||
{
|
||||
uint32_t tmp_current = 0U;
|
||||
uint32_t tmp_temp = 0U;
|
||||
if(LL_DMA_IsActiveFlag_HT1(DMA1))
|
||||
{
|
||||
LL_DMA_ClearFlag_HT1(DMA1);
|
||||
for(uint32_t i = 0U; i < (sizeof(samples)/sizeof(samples[0])) / 2U; i++)
|
||||
{
|
||||
tmp_current += samples[i].current;
|
||||
tmp_temp += samples[i].temperature;
|
||||
}
|
||||
}
|
||||
else if(LL_DMA_IsActiveFlag_TC1(DMA1))
|
||||
{
|
||||
LL_DMA_ClearFlag_TC1(DMA1);
|
||||
for(uint32_t i = (sizeof(samples)/sizeof(samples[0])) / 2U; i < (sizeof(samples)/sizeof(samples[0])); i++)
|
||||
{
|
||||
tmp_current += samples[i].current;
|
||||
tmp_temp += samples[i].temperature;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* error */
|
||||
__asm("bkpt #0");
|
||||
}
|
||||
tmp_current /= ((sizeof(samples)/sizeof(samples[0])) / 2U);
|
||||
tmp_temp /= ((sizeof(samples)/sizeof(samples[0])) / 2U);
|
||||
current = (current + tmp_current) / 2U;
|
||||
temperature = (temperature + tmp_temp) / 2U;
|
||||
}
|
||||
|
||||
namespace ElektronischeLast
|
||||
{
|
||||
iADC::iADC(void)
|
||||
{
|
||||
/**ADC1 GPIO Configuration
|
||||
PA0 ------> ADC1_IN0
|
||||
PA1 ------> ADC1_IN1
|
||||
*/
|
||||
LL_GPIO_InitTypeDef GPIO_InitStruct =
|
||||
{
|
||||
.Pin = LL_GPIO_PIN_0,
|
||||
.Mode = LL_GPIO_MODE_ANALOG,
|
||||
.Pull = LL_GPIO_PULL_NO,
|
||||
};
|
||||
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = LL_GPIO_PIN_1;
|
||||
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
LL_DMA_SetPeriphRequest(DMA1, LL_DMA_CHANNEL_1, LL_DMAMUX_REQ_ADC1);
|
||||
LL_DMA_SetDataTransferDirection(DMA1, LL_DMA_CHANNEL_1, LL_DMA_DIRECTION_PERIPH_TO_MEMORY);
|
||||
LL_DMA_SetChannelPriorityLevel(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PRIORITY_HIGH);
|
||||
LL_DMA_SetMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MODE_CIRCULAR);
|
||||
LL_DMA_SetPeriphIncMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PERIPH_NOINCREMENT);
|
||||
LL_DMA_SetMemoryIncMode(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MEMORY_INCREMENT);
|
||||
LL_DMA_SetPeriphSize(DMA1, LL_DMA_CHANNEL_1, LL_DMA_PDATAALIGN_HALFWORD);
|
||||
LL_DMA_SetMemorySize(DMA1, LL_DMA_CHANNEL_1, LL_DMA_MDATAALIGN_HALFWORD);
|
||||
LL_DMA_SetPeriphAddress(DMA1, LL_DMA_CHANNEL_1, reinterpret_cast<std::uint32_t>(&ADC1->DR));
|
||||
/* Select ADC as DMA transfer request */
|
||||
LL_DMAMUX_SetRequestID(DMAMUX1, LL_DMAMUX_CHANNEL_0, LL_DMAMUX_REQ_ADC1);
|
||||
/* Set DMA transfer addresses of source and destination */
|
||||
LL_DMA_ConfigAddresses(DMA1, LL_DMA_CHANNEL_1,
|
||||
LL_ADC_DMA_GetRegAddr(ADC1, LL_ADC_DMA_REG_REGULAR_DATA),
|
||||
(uint32_t)&samples, LL_DMA_DIRECTION_PERIPH_TO_MEMORY);
|
||||
/* Set DMA transfer size */
|
||||
LL_DMA_SetDataLength(DMA1, LL_DMA_CHANNEL_1, sizeof(samples)/(sizeof(uint16_t)));
|
||||
/* Enable DMA transfer interruption: transfer complete */
|
||||
LL_DMA_EnableIT_TC(DMA1, LL_DMA_CHANNEL_1);
|
||||
/* Enable DMA transfer interruption: half transfer */
|
||||
LL_DMA_EnableIT_HT(DMA1, LL_DMA_CHANNEL_1);
|
||||
/* Enable DMA transfer interruption: transfer error */
|
||||
LL_DMA_EnableIT_TE(DMA1, LL_DMA_CHANNEL_1);
|
||||
/* Enable the DMA transfer */
|
||||
LL_DMA_EnableChannel(DMA1, LL_DMA_CHANNEL_1);
|
||||
|
||||
/** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
|
||||
*/
|
||||
LL_ADC_InitTypeDef ADC_InitStruct =
|
||||
{
|
||||
.Clock = LL_ADC_CLOCK_SYNC_PCLK_DIV2,
|
||||
.Resolution = LL_ADC_RESOLUTION_12B,
|
||||
.DataAlignment = LL_ADC_DATA_ALIGN_RIGHT,
|
||||
.LowPowerMode = LL_ADC_LP_MODE_NONE,
|
||||
};
|
||||
LL_ADC_Init(ADC1, &ADC_InitStruct);
|
||||
LL_ADC_REG_SetSequencerConfigurable(ADC1, LL_ADC_REG_SEQ_CONFIGURABLE);
|
||||
|
||||
/* Poll for ADC channel configuration ready */
|
||||
while (LL_ADC_IsActiveFlag_CCRDY(ADC1) == 0)
|
||||
{
|
||||
}
|
||||
/* Clear flag ADC channel configuration ready */
|
||||
LL_ADC_ClearFlag_CCRDY(ADC1);
|
||||
LL_ADC_REG_InitTypeDef ADC_REG_InitStruct =
|
||||
{
|
||||
.TriggerSource = LL_ADC_REG_TRIG_EXT_TIM1_TRGO2,
|
||||
.SequencerLength = LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS,
|
||||
.SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE,
|
||||
.ContinuousMode = LL_ADC_REG_CONV_SINGLE,
|
||||
.DMATransfer = LL_ADC_REG_DMA_TRANSFER_UNLIMITED,
|
||||
.Overrun = LL_ADC_REG_OVR_DATA_PRESERVED,
|
||||
};
|
||||
LL_ADC_REG_Init(ADC1, &ADC_REG_InitStruct);
|
||||
LL_ADC_SetOverSamplingScope(ADC1, LL_ADC_OVS_DISABLE);
|
||||
LL_ADC_SetTriggerFrequencyMode(ADC1, LL_ADC_CLOCK_FREQ_MODE_HIGH);
|
||||
LL_ADC_REG_SetTriggerEdge(ADC1, LL_ADC_REG_TRIG_EXT_RISING);
|
||||
LL_ADC_SetSamplingTimeCommonChannels(ADC1, LL_ADC_SAMPLINGTIME_COMMON_1, LL_ADC_SAMPLINGTIME_12CYCLES_5);
|
||||
|
||||
/* Enable ADC internal voltage regulator */
|
||||
LL_ADC_EnableInternalRegulator(ADC1);
|
||||
/* Delay for ADC internal voltage regulator stabilization. */
|
||||
/* Compute number of CPU cycles to wait for, from delay in us. */
|
||||
/* Note: Variable divided by 2 to compensate partially */
|
||||
/* CPU processing cycles (depends on compilation optimization). */
|
||||
/* Note: If system core clock frequency is below 200kHz, wait time */
|
||||
/* is only a few CPU processing cycles. */
|
||||
uint32_t wait_loop_index;
|
||||
wait_loop_index = ((LL_ADC_DELAY_INTERNAL_REGUL_STAB_US * (SystemCoreClock / (100000 * 2))) / 10);
|
||||
while(wait_loop_index != 0)
|
||||
{
|
||||
wait_loop_index--;
|
||||
}
|
||||
|
||||
/** Configure Regular Channel
|
||||
*/
|
||||
LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_1, LL_ADC_CHANNEL_0);
|
||||
LL_ADC_SetChannelSamplingTime(ADC1, LL_ADC_CHANNEL_0, LL_ADC_SAMPLINGTIME_COMMON_1);
|
||||
|
||||
/** Configure Regular Channel
|
||||
*/
|
||||
LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_2, LL_ADC_CHANNEL_1);
|
||||
|
||||
/* Poll for ADC channel configuration ready */
|
||||
while (LL_ADC_IsActiveFlag_CCRDY(ADC1) == 0)
|
||||
{
|
||||
}
|
||||
/* Clear flag ADC channel configuration ready */
|
||||
LL_ADC_ClearFlag_CCRDY(ADC1);
|
||||
LL_ADC_SetChannelSamplingTime(ADC1, LL_ADC_CHANNEL_1, LL_ADC_SAMPLINGTIME_COMMON_1);
|
||||
|
||||
LL_TIM_InitTypeDef TIM_InitStruct =
|
||||
{
|
||||
.Prescaler = 32,
|
||||
.CounterMode = LL_TIM_COUNTERMODE_UP,
|
||||
.Autoreload = 490,
|
||||
.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1,
|
||||
.RepetitionCounter = 0,
|
||||
};
|
||||
LL_TIM_Init(TIM1, &TIM_InitStruct);
|
||||
LL_TIM_DisableARRPreload(TIM1);
|
||||
LL_TIM_SetClockSource(TIM1, LL_TIM_CLOCKSOURCE_INTERNAL);
|
||||
LL_TIM_SetTriggerOutput(TIM1, LL_TIM_TRGO_RESET);
|
||||
LL_TIM_SetTriggerOutput2(TIM1, LL_TIM_TRGO2_UPDATE);
|
||||
LL_TIM_DisableMasterSlaveMode(TIM1);
|
||||
|
||||
LL_ADC_StartCalibration(ADC1);
|
||||
while(LL_ADC_IsCalibrationOnGoing(ADC1))
|
||||
{
|
||||
}
|
||||
LL_ADC_Enable(ADC1);
|
||||
LL_ADC_REG_StartConversion(ADC1);
|
||||
LL_TIM_EnableCounter(TIM1);
|
||||
|
||||
/* DMA1_Channel1_IRQn interrupt configuration */
|
||||
NVIC_SetPriority(DMA1_Channel1_IRQn, 0);
|
||||
NVIC_EnableIRQ(DMA1_Channel1_IRQn);
|
||||
}
|
||||
iADC::~iADC(void)
|
||||
{
|
||||
|
||||
}
|
||||
}
|
22
Source/ADC.hpp
Normal file
22
Source/ADC.hpp
Normal file
@@ -0,0 +1,22 @@
|
||||
/*
|
||||
* ADC.hpp
|
||||
*
|
||||
* Created on: Jul 1, 2023
|
||||
* Author: Carst
|
||||
*/
|
||||
|
||||
#ifndef ADC_HPP_
|
||||
#define ADC_HPP_
|
||||
|
||||
namespace ElektronischeLast
|
||||
{
|
||||
class iADC
|
||||
{
|
||||
public:
|
||||
iADC(void);
|
||||
~iADC(void);
|
||||
private:
|
||||
};
|
||||
}
|
||||
|
||||
#endif /* ADC_HPP_ */
|
@@ -6,10 +6,13 @@
|
||||
*/
|
||||
|
||||
#include <cstdint>
|
||||
#include <cstdio>
|
||||
#include <stm32g0xx.h>
|
||||
#include "STM32G071KBT6.hpp"
|
||||
#include "LED.hpp"
|
||||
#include "DAC.hpp"
|
||||
#include "ADC.hpp"
|
||||
#include "serial.hpp"
|
||||
|
||||
using namespace ElektronischeLast;
|
||||
|
||||
@@ -575,15 +578,19 @@ static const std::uint16_t wave[] = {
|
||||
int main (void)
|
||||
{
|
||||
__enable_irq();
|
||||
serial_init();
|
||||
LED led = LED(500U);
|
||||
iDAC dac = iDAC();
|
||||
iADC adc = iADC();
|
||||
|
||||
std::uint32_t dac_value = 0U;
|
||||
|
||||
printf("Init done\r\n");
|
||||
|
||||
while(1)
|
||||
{
|
||||
led.blink();
|
||||
dac.write(iDAC::CHANNEL_1, wave[dac_value]);
|
||||
dac_value = (dac_value + 1U) % (sizeof(wave)/sizeof(std::uint16_t));
|
||||
dac_value = (dac_value + 1U) % (sizeof(wave)/sizeof(wave[0]));
|
||||
}
|
||||
}
|
||||
|
@@ -12,6 +12,9 @@
|
||||
#include <stm32g0xx_ll_system.h>
|
||||
#include <stm32g0xx_ll_utils.h>
|
||||
|
||||
#include <stm32g0xx_ll_gpio.h>
|
||||
#include <stm32g0xx_ll_tim.h>
|
||||
|
||||
extern "C" void Reset_Handler(void);
|
||||
extern "C" void NMI_Handler(void);
|
||||
extern "C" void HardFault_Handler(void);
|
||||
@@ -51,6 +54,8 @@ extern "C" void USART3_4_LPUART1_IRQHandler(void); /* USART3, USART4 and L
|
||||
extern "C" void CEC_IRQHandler(void); /* CEC */
|
||||
|
||||
extern std::uint32_t _estack;
|
||||
const uint32_t AHBPrescTable[16UL] = {0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 1UL, 2UL, 3UL, 4UL, 6UL, 7UL, 8UL, 9UL};
|
||||
const uint32_t APBPrescTable[8UL] = {0UL, 0UL, 0UL, 0UL, 1UL, 2UL, 3UL, 4UL};
|
||||
std::uint32_t systick;
|
||||
|
||||
const std::uintptr_t interruptVectorTable[] __attribute__((section(".isr_vector")))
|
||||
@@ -155,7 +160,7 @@ extern "C" void EXTI0_1_IRQHandler(void){} /* EXTI Line 0 and 1
|
||||
extern "C" void EXTI2_3_IRQHandler(void){} /* EXTI Line 2 and 3 */
|
||||
extern "C" void EXTI4_15_IRQHandler(void){} /* EXTI Line 4 to 15 */
|
||||
extern "C" void UCPD1_2_IRQHandler(void){} /* UCPD1, UCPD2 */
|
||||
extern "C" void DMA1_Channel1_IRQHandler(void){} /* DMA1 Channel 1 */
|
||||
|
||||
extern "C" void DMA1_Channel2_3_IRQHandler(void){} /* DMA1 Channel 2 and Channel 3 */
|
||||
extern "C" void DMA1_Ch4_7_DMAMUX1_OVR_IRQHandler(void){} /* DMA1 Channel 4 to Channel 7, DMAMUX1 overrun */
|
||||
extern "C" void ADC1_COMP_IRQHandler(void){} /* ADC1, COMP1 and COMP2 */
|
||||
@@ -232,11 +237,17 @@ extern "C" void SystemInit(void)
|
||||
/* Update CMSIS variable (which can be updated also through SystemCoreClockUpdate function) */
|
||||
LL_SetSystemCoreClock(64000000);
|
||||
|
||||
/* Clock-Sources*/
|
||||
LL_RCC_SetLPUARTClockSource(LL_RCC_LPUART1_CLKSOURCE_PCLK1);
|
||||
LL_RCC_SetTIMClockSource(LL_RCC_TIM1_CLKSOURCE_PCLK1);
|
||||
|
||||
/* Enable Clocks for all Peripherals*/
|
||||
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
|
||||
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOB);
|
||||
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOC);
|
||||
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_LPUART1);
|
||||
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_ADC);
|
||||
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_TIM1);
|
||||
LL_AHB1_GRP1_EnableClock(LL_AHB1_GRP1_PERIPH_DMA1);
|
||||
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_DAC1);
|
||||
}
|
||||
|
@@ -6,6 +6,8 @@
|
||||
*/
|
||||
|
||||
#include <cstdint>
|
||||
#include <sys/stat.h>
|
||||
#include <stm32g0xx_ll_gpio.h>
|
||||
#include "stm32g0xx_ll_lpuart.h"
|
||||
|
||||
extern "C" int _write(int file, char *ptr, int len)
|
||||
@@ -54,6 +56,19 @@ extern "C" int _read(int file, char *ptr, int len)
|
||||
#endif
|
||||
}
|
||||
|
||||
extern "C" int _fstat(int file, struct stat *st)
|
||||
{
|
||||
(void)file;
|
||||
st->st_mode = S_IFCHR;
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" int _isatty(int file)
|
||||
{
|
||||
(void)file;
|
||||
return 1;
|
||||
}
|
||||
|
||||
extern "C" void USART3_4_LPUART1_IRQHandler(void)
|
||||
{
|
||||
if(LL_LPUART_IsActiveFlag_RXNE_RXFNE(LPUART1))
|
||||
@@ -62,3 +77,50 @@ extern "C" void USART3_4_LPUART1_IRQHandler(void)
|
||||
}
|
||||
}
|
||||
|
||||
extern "C" void serial_init(void)
|
||||
{
|
||||
/**LPUART1 GPIO Configuration
|
||||
PA2 ------> LPUART1_TX
|
||||
PA3 ------> LPUART1_RX
|
||||
*/
|
||||
LL_GPIO_InitTypeDef GPIO_InitStruct =
|
||||
{
|
||||
.Pin = LL_GPIO_PIN_2,
|
||||
.Mode = LL_GPIO_MODE_ALTERNATE,
|
||||
.Speed = LL_GPIO_SPEED_FREQ_LOW,
|
||||
.OutputType = LL_GPIO_OUTPUT_PUSHPULL,
|
||||
.Pull = LL_GPIO_PULL_NO,
|
||||
.Alternate = LL_GPIO_AF_6,
|
||||
};
|
||||
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = LL_GPIO_PIN_3;
|
||||
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
|
||||
LL_LPUART_InitTypeDef LPUART_InitStruct =
|
||||
{
|
||||
.PrescalerValue = LL_LPUART_PRESCALER_DIV1,
|
||||
.BaudRate = 115200,
|
||||
.DataWidth = LL_LPUART_DATAWIDTH_8B,
|
||||
.StopBits = LL_LPUART_STOPBITS_1,
|
||||
.Parity = LL_LPUART_PARITY_NONE,
|
||||
.TransferDirection = LL_LPUART_DIRECTION_TX_RX,
|
||||
.HardwareFlowControl = LL_LPUART_HWCONTROL_NONE,
|
||||
};
|
||||
LL_LPUART_Init(LPUART1, &LPUART_InitStruct);
|
||||
LL_LPUART_SetTXFIFOThreshold(LPUART1, LL_LPUART_FIFOTHRESHOLD_1_8);
|
||||
LL_LPUART_SetRXFIFOThreshold(LPUART1, LL_LPUART_FIFOTHRESHOLD_1_8);
|
||||
LL_LPUART_EnableFIFO(LPUART1);
|
||||
|
||||
LL_LPUART_Enable(LPUART1);
|
||||
|
||||
/* LPUART1 interrupt Init */
|
||||
NVIC_SetPriority(USART3_4_LPUART1_IRQn, 2);
|
||||
NVIC_EnableIRQ(USART3_4_LPUART1_IRQn);
|
||||
|
||||
/* Polling LPUART1 initialisation */
|
||||
while((!(LL_LPUART_IsActiveFlag_TEACK(LPUART1))) || (!(LL_LPUART_IsActiveFlag_REACK(LPUART1))))
|
||||
{
|
||||
}
|
||||
}
|
||||
|
13
Source/serial.hpp
Normal file
13
Source/serial.hpp
Normal file
@@ -0,0 +1,13 @@
|
||||
/*
|
||||
* serial.hpp
|
||||
*
|
||||
* Created on: Jul 1, 2023
|
||||
* Author: Carst
|
||||
*/
|
||||
|
||||
#ifndef SERIAL_HPP_
|
||||
#define SERIAL_HPP_
|
||||
|
||||
extern "C" void serial_init(void);
|
||||
|
||||
#endif /* SERIAL_HPP_ */
|
Reference in New Issue
Block a user