1#if defined(ARDUINO_ARCH_SILABS)
2#include <pinDefinitions.h>
3#include <pins_arduino.h>
8#include "../../../drivers/hardware_specific/silabs/efr32_mcu.h"
11#define _ADC_VOLTAGE 3.3f
14#ifndef _ADC_RESOLUTION
15#define _ADC_RESOLUTION 4095.0f
18#ifndef _CLK_SRC_ADC_FREQ
19#define _CLK_SRC_ADC_FREQ 20000000
23#define _CLK_ADC_FREQ 10000000
26extern void _getPrsSourceAndUnderflowSignal(
31static void _adcBusAllocate(
36#if (GPIO_PA_COUNT > 0)
39 if ((GPIO->ABUSALLOC & _GPIO_ABUSALLOC_AEVEN0_MASK) == GPIO_ABUSALLOC_AEVEN0_TRISTATE) {
40 GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AEVEN0_ADC0;
41 }
else if ((GPIO->ABUSALLOC & _GPIO_ABUSALLOC_AEVEN1_MASK) == GPIO_ABUSALLOC_AEVEN1_TRISTATE) {
42 GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AEVEN1_ADC0;
45 if ((GPIO->ABUSALLOC & _GPIO_ABUSALLOC_AODD0_MASK) == GPIO_ABUSALLOC_AODD0_TRISTATE) {
46 GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AODD0_ADC0;
47 }
else if ((GPIO->ABUSALLOC & _GPIO_ABUSALLOC_AODD1_MASK) == GPIO_ABUSALLOC_AODD1_TRISTATE) {
48 GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AODD1_ADC0;
56#if (GPIO_PB_COUNT > 0)
59 if ((GPIO->BBUSALLOC & _GPIO_BBUSALLOC_BEVEN0_MASK) == GPIO_BBUSALLOC_BEVEN0_TRISTATE) {
60 GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BEVEN0_ADC0;
61 }
else if ((GPIO->BBUSALLOC & _GPIO_BBUSALLOC_BEVEN1_MASK) == GPIO_BBUSALLOC_BEVEN1_TRISTATE) {
62 GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BEVEN1_ADC0;
67 if ((GPIO->BBUSALLOC & _GPIO_BBUSALLOC_BODD0_MASK) == GPIO_BBUSALLOC_BODD0_TRISTATE) {
68 GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BODD0_ADC0;
69 }
else if ((GPIO->BBUSALLOC & _GPIO_BBUSALLOC_BODD1_MASK) == GPIO_BBUSALLOC_BODD1_TRISTATE) {
70 GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BODD1_ADC0;
78#if (GPIO_PC_COUNT > 0 || GPIO_PD_COUNT > 0)
82 if ((GPIO->CDBUSALLOC & _GPIO_CDBUSALLOC_CDEVEN0_MASK) == GPIO_CDBUSALLOC_CDEVEN0_TRISTATE) {
83 GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDEVEN0_ADC0;
84 }
else if ((GPIO->CDBUSALLOC & _GPIO_CDBUSALLOC_CDEVEN1_MASK) == GPIO_CDBUSALLOC_CDEVEN1_TRISTATE) {
85 GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDEVEN1_ADC0;
90 if ((GPIO->CDBUSALLOC & _GPIO_CDBUSALLOC_CDODD0_MASK) == GPIO_CDBUSALLOC_CDODD0_TRISTATE) {
91 GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDODD0_ADC0;
92 }
else if ((GPIO->CDBUSALLOC & _GPIO_CDBUSALLOC_CDODD1_MASK) == GPIO_CDBUSALLOC_CDODD1_TRISTATE) {
93 GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDODD1_ADC0;
103static void _adcConfig(
104 EFR32AdcInstance *inst,
108 inst->port = getSilabsPortFromArduinoPin(pinToPinName(pin));
109 inst->pin = getSilabsPinFromArduinoPin(pinToPinName(pin));
112static float _readAdc(
113 EFR32CurrentSenseParams *
params,
118 for (uint8_t i = 0; i < SILABS_MAX_ANALOG; ++i) {
127static bool _dmaTransferFinishedCb(
128 unsigned int channel,
129 unsigned int sequenceNo,
134 EFR32CurrentSenseParams *
params = (EFR32CurrentSenseParams *) data;
138 CORE_DECLARE_IRQ_STATE;
146static void _currentSenseInitDMA(
147 EFR32CurrentSenseParams *
params,
148 DMADRV_Callback_t fn,
156 DMADRV_AllocateChannel(&
params->dmaChannel, NULL);
159 LDMA_TransferCfg_t transferCfg =
160 LDMA_TRANSFER_CFG_PERIPHERAL(ldmaPeripheralSignal_IADC0_IADC_SCAN);
163 (LDMA_Descriptor_t)LDMA_DESCRIPTOR_LINKREL_P2M_WORD(&(
params->adc->SCANFIFODATA),
168 DMADRV_LdmaStartTransfer(
params->dmaChannel,
175static void _currentSenseInitScan(
176 EFR32CurrentSenseParams *
params
181 CMU_ClockEnable(cmuClock_IADC0,
true);
182 CMU_ClockEnable(cmuClock_GPIO,
true);
185 CMU_ClockSelectSet(cmuClock_IADCCLK, cmuSelect_FSRCO);
187 for (uint8_t i = 0; i <
params->noAdcChannels; ++i) {
188 GPIO_PinModeSet(
params->inst[i].port,
params->inst[i].pin, gpioModeDisabled, 0);
191 IADC_Init_t init = IADC_INIT_DEFAULT;
192 init.warmup = iadcWarmupKeepWarm;
193 init.srcClkPrescale = IADC_calcSrcClkPrescale(
params->adc, _CLK_SRC_ADC_FREQ, 0);
195 IADC_CfgReference_t adcRef;
197 case 1200: adcRef = iadcCfgReferenceInt1V2;
break;
198 case 1250: adcRef = iadcCfgReferenceExt1V25;
break;
199 case 3300: adcRef = iadcCfgReferenceVddx;
break;
200 case 2640: adcRef = iadcCfgReferenceVddX0P8Buf;
break;
204 IADC_AllConfigs_t allConfigs = IADC_ALLCONFIGS_DEFAULT;
205 allConfigs.configs[0].reference = adcRef;
206 allConfigs.configs[0].vRef =
params->vRef;
207 allConfigs.configs[0].adcClkPrescale = IADC_calcAdcClkPrescale(
params->adc,
211 init.srcClkPrescale);
217 if (
params->adc->CTRL == _IADC_CTRL_RESETVALUE) {
218 IADC_init(
params->adc, &init, &allConfigs);
221 IADC_InitScan_t initScan = IADC_INITSCAN_DEFAULT;
222 if ((
params->mode == CS_LO_SIDE) || (
params->mode == CS_HI_SIDE)) {
224 initScan.triggerSelect = iadcTriggerSelPrs0PosEdge;
226 initScan.fifoDmaWakeup =
true;
228 IADC_ScanTable_t scanTable = IADC_SCANTABLE_DEFAULT;
229 for (uint8_t i = 0; i <
params->noAdcChannels; ++i) {
230 scanTable.entries[i].posInput = IADC_portPinToPosInput(
params->inst[i].port,
params->inst[i].pin);
231 scanTable.entries[i].negInput = iadcNegInputGnd;
232 scanTable.entries[i].includeInScan =
true;
236 IADC_init(
params->adc, &init, &allConfigs);
239 IADC_initScan(
params->adc, &initScan, &scanTable);
242 for (uint8_t i = 0; i <
params->noAdcChannels; ++i) {
243 _adcBusAllocate(
params->inst[i].port,
params->inst[i].pin);
247static void _currentSenseConfig(
248 EFR32CurrentSenseParams *
params,
249 int adcPins[SILABS_MAX_ANALOG]
253 uint8_t noAdcChannels = 0;
254 for (
int i = 0; i < SILABS_MAX_ANALOG; ++i) {
255 if (!
_isset(adcPins[i]))
continue;
257 _adcConfig(&
params->inst[noAdcChannels], adcPins[i]);
262 params->noAdcChannels = noAdcChannels;
265static void _currentSenseDeinit(
266 EFR32CurrentSenseParams *
params
270 DMADRV_StopTransfer(
params->dmaChannel);
271 DMADRV_FreeChannel(
params->dmaChannel);
276static void _currentSenseStartScan(
277 EFR32CurrentSenseParams *
params
281 IADC_command(
params->adc, iadcCmdStartScan);
284static void _currentSenseStopScan(
285 EFR32CurrentSenseParams *
params
289 IADC_command(
params->adc, iadcCmdStopScan);
292static void _currentSenseStopTranfer(
293 EFR32CurrentSenseParams *
params
297 DMADRV_PauseTransfer(
params->dmaChannel);
300static void _currentSenseStartTranfer(
301 EFR32CurrentSenseParams *
params
305 DMADRV_ResumeTransfer(
params->dmaChannel);
316 EFR32CurrentSenseParams *
params = (EFR32CurrentSenseParams *)
cs_params;
319 return _readAdc(
params, pin);
323 const void* driver_params,
330 EFR32CurrentSenseParams *
params =
new EFR32CurrentSenseParams {
334 .vRef = SILABS_ADC_VREF,
335 .prsChannel = SILABS_ADC_PRS_CHANNEL,
337 .adc = SILABS_DEFAULT_ADC_PERPHERAL,
344 _currentSenseConfig(
params, adcPins);
345 _currentSenseInitScan(
params);
347 _currentSenseStartScan(
params);
356 EFR32DriverParams *driver = (EFR32DriverParams *) driver_params;
357 EFR32CurrentSenseParams *
params = (EFR32CurrentSenseParams *)
cs_params;
361 uint32_t prsSource, prsSignal;
363 CMU_ClockEnable(cmuClock_PRS,
true);
365 _getPrsSourceAndUnderflowSignal(driver->inst[0].h.timer, &prsSource, &prsSignal);
366 PRS_SourceAsyncSignalSet(
params->prsChannel, prsSource, prsSignal);
367 PRS_ConnectConsumer(
params->prsChannel, prsTypeAsync, prsConsumerIADC0_SCANTRIGGER);
380 EFR32CurrentSenseParams *
params = (EFR32CurrentSenseParams *)
cs_params;
384 CORE_DECLARE_IRQ_STATE;
386 params->dataReady =
false;
389 _currentSenseStartScan(
params);
391 while (!
params->dataReady) {}
394 return _readAdc(
params, pin);
398 const void* driver_params,
405 EFR32CurrentSenseParams *
params =
new EFR32CurrentSenseParams {
409 .vRef = SILABS_ADC_VREF,
410 .prsChannel = SILABS_ADC_PRS_CHANNEL,
412 .adc = SILABS_DEFAULT_ADC_PERPHERAL,
419 _currentSenseConfig(
params, adcPins);
420 _currentSenseInitScan(
params);
421 _currentSenseInitDMA(
params, _dmaTransferFinishedCb,
params);
void * _configureADCInline(const void *driver_params, const int pinA, const int pinB, const int pinC=NOT_SET)
float _readADCVoltageInline(const int pinA, const void *cs_params)
void * _driverSyncLowSide(void *driver_params, void *cs_params)
#define SIMPLEFOC_CURRENT_SENSE_INIT_FAILED
void * _configureADCLowSide(const void *driver_params, const int pinA, const int pinB, const int pinC=NOT_SET)
float _readADCVoltageLowSide(const int pinA, const void *cs_params)
const int const int const int pinC
GenericCurrentSenseParams * params