mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
HAL_ChibiOS: cope with having no ADC inputs
This commit is contained in:
parent
87389e0fdc
commit
d191b37520
@ -178,7 +178,7 @@ AnalogIn::AnalogIn() :
|
|||||||
*/
|
*/
|
||||||
void AnalogIn::adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
|
void AnalogIn::adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
|
||||||
{
|
{
|
||||||
if (buffer != &samples[0]) {
|
if (buffer != samples) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
|
for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
|
||||||
@ -194,6 +194,9 @@ void AnalogIn::adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
|
|||||||
*/
|
*/
|
||||||
void AnalogIn::init()
|
void AnalogIn::init()
|
||||||
{
|
{
|
||||||
|
if (ADC_GRP1_NUM_CHANNELS == 0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
adcStart(&ADCD1, NULL);
|
adcStart(&ADCD1, NULL);
|
||||||
memset(&adcgrpcfg, 0, sizeof(adcgrpcfg));
|
memset(&adcgrpcfg, 0, sizeof(adcgrpcfg));
|
||||||
adcgrpcfg.circular = true;
|
adcgrpcfg.circular = true;
|
||||||
@ -219,7 +222,7 @@ void AnalogIn::init()
|
|||||||
adcgrpcfg.sqr1 |= chan << (5*(i-12));
|
adcgrpcfg.sqr1 |= chan << (5*(i-12));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
adcStartConversion(&ADCD1, &adcgrpcfg, &samples[0], ADC_DMA_BUF_DEPTH);
|
adcStartConversion(&ADCD1, &adcgrpcfg, samples, ADC_DMA_BUF_DEPTH);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user