mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: ensure ADC memory is aligned for DMA access
This commit is contained in:
parent
bb2e7a189f
commit
8b1db792ee
|
@ -60,7 +60,7 @@ const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS;
|
||||||
#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE_SIMPLE(AnalogIn::pin_config)
|
#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE_SIMPLE(AnalogIn::pin_config)
|
||||||
|
|
||||||
// samples filled in by ADC DMA engine
|
// samples filled in by ADC DMA engine
|
||||||
adcsample_t AnalogIn::samples[ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS];
|
adcsample_t *AnalogIn::samples;
|
||||||
uint32_t AnalogIn::sample_sum[ADC_GRP1_NUM_CHANNELS];
|
uint32_t AnalogIn::sample_sum[ADC_GRP1_NUM_CHANNELS];
|
||||||
uint32_t AnalogIn::sample_count;
|
uint32_t AnalogIn::sample_count;
|
||||||
|
|
||||||
|
@ -204,6 +204,9 @@ void AnalogIn::init()
|
||||||
if (ADC_GRP1_NUM_CHANNELS == 0) {
|
if (ADC_GRP1_NUM_CHANNELS == 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
samples = (adcsample_t *)hal.util->malloc_type(sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS, AP_HAL::Util::MEM_DMA_SAFE);
|
||||||
|
|
||||||
adcStart(&ADCD1, NULL);
|
adcStart(&ADCD1, NULL);
|
||||||
memset(&adcgrpcfg, 0, sizeof(adcgrpcfg));
|
memset(&adcgrpcfg, 0, sizeof(adcgrpcfg));
|
||||||
adcgrpcfg.circular = true;
|
adcgrpcfg.circular = true;
|
||||||
|
|
|
@ -88,7 +88,7 @@ private:
|
||||||
};
|
};
|
||||||
static const pin_info pin_config[];
|
static const pin_info pin_config[];
|
||||||
|
|
||||||
static adcsample_t samples[];
|
static adcsample_t *samples;
|
||||||
static uint32_t sample_sum[];
|
static uint32_t sample_sum[];
|
||||||
static uint32_t sample_count;
|
static uint32_t sample_count;
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue