2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
2019-10-20 10:31:12 -03:00
|
|
|
*
|
2018-01-05 02:19:51 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2018-03-06 18:41:03 -04:00
|
|
|
#include "ch.h"
|
|
|
|
#include "hal.h"
|
|
|
|
|
2018-10-28 20:24:01 -03:00
|
|
|
#if HAL_USE_ADC == TRUE && !defined(HAL_DISABLE_ADC_DRIVER)
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
#include "AnalogIn.h"
|
|
|
|
|
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
#include <AP_IOMCU/AP_IOMCU.h>
|
|
|
|
extern AP_IOMCU iomcu;
|
|
|
|
#endif
|
|
|
|
|
2018-05-30 01:22:49 -03:00
|
|
|
#include "hwdef/common/stm32_util.h"
|
|
|
|
|
2019-09-24 22:25:55 -03:00
|
|
|
// MAVLink is included as we send a mavlink message as part of debug,
|
|
|
|
// and also use the MAV_POWER flags below in update_power_flags
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
#define ANLOGIN_DEBUGGING 0
|
|
|
|
|
|
|
|
// base voltage scaling for 12 bit 3.3V ADC
|
2021-09-28 13:40:08 -03:00
|
|
|
#define VOLTAGE_SCALING (3.3f / ((1 << 12) - 1))
|
|
|
|
|
|
|
|
// voltage divider is usually 1/(10/(20+10))
|
|
|
|
#ifndef HAL_IOMCU_VSERVO_SCALAR
|
|
|
|
#define HAL_IOMCU_VSERVO_SCALAR 3
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// voltage divider is usually not present
|
|
|
|
#ifndef HAL_IOMCU_VRSSI_SCALAR
|
|
|
|
#define HAL_IOMCU_VRSSI_SCALAR 1
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
#if ANLOGIN_DEBUGGING
|
|
|
|
# define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
|
|
|
#else
|
|
|
|
# define Debug(fmt, args ...)
|
|
|
|
#endif
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2018-01-07 23:37:25 -04:00
|
|
|
using namespace ChibiOS;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-09-15 02:43:54 -03:00
|
|
|
// special pins
|
|
|
|
#define ANALOG_SERVO_VRSSI_PIN 103
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
scaling table between ADC count and actual input voltage, to account
|
2019-10-20 10:31:12 -03:00
|
|
|
for voltage dividers on the board.
|
2018-01-05 02:19:51 -04:00
|
|
|
*/
|
2018-01-13 00:48:43 -04:00
|
|
|
const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-08-02 20:27:17 -03:00
|
|
|
#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config)
|
2018-01-07 23:37:25 -04:00
|
|
|
|
2021-04-13 22:21:28 -03:00
|
|
|
#if defined(ADC_CFGR_RES_16BITS)
|
2021-04-04 17:47:46 -03:00
|
|
|
// on H7 we use 16 bit ADC transfers, giving us more resolution. We
|
|
|
|
// need to scale by 1/16 to match the 12 bit scale factors in hwdef.dat
|
|
|
|
#define ADC_BOARD_SCALING (1.0/16)
|
|
|
|
#else
|
|
|
|
#define ADC_BOARD_SCALING 1
|
|
|
|
#endif
|
|
|
|
|
2018-01-07 23:37:25 -04:00
|
|
|
// samples filled in by ADC DMA engine
|
2018-05-31 19:35:09 -03:00
|
|
|
adcsample_t *AnalogIn::samples;
|
2018-01-13 00:02:05 -04:00
|
|
|
uint32_t AnalogIn::sample_sum[ADC_GRP1_NUM_CHANNELS];
|
|
|
|
uint32_t AnalogIn::sample_count;
|
2018-01-07 23:37:25 -04:00
|
|
|
|
2020-05-08 03:46:57 -03:00
|
|
|
AnalogSource::AnalogSource(int16_t pin) :
|
|
|
|
_pin(pin)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2019-10-20 10:31:12 -03:00
|
|
|
float AnalogSource::read_average()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-10-11 20:35:32 -03:00
|
|
|
WITH_SEMAPHORE(_semaphore);
|
|
|
|
|
|
|
|
if (_sum_count == 0) {
|
|
|
|
return _value;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-10-11 20:35:32 -03:00
|
|
|
_value = _sum_value / _sum_count;
|
|
|
|
_value_ratiometric = _sum_ratiometric / _sum_count;
|
|
|
|
_sum_value = 0;
|
|
|
|
_sum_ratiometric = 0;
|
|
|
|
_sum_count = 0;
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
return _value;
|
|
|
|
}
|
|
|
|
|
2019-10-20 10:31:12 -03:00
|
|
|
float AnalogSource::read_latest()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
return _latest_value;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return scaling from ADC count to Volts
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
float AnalogSource::_pin_scaler(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
float scaling = VOLTAGE_SCALING;
|
2018-01-07 23:37:25 -04:00
|
|
|
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
|
2018-01-13 00:02:05 -04:00
|
|
|
if (AnalogIn::pin_config[i].channel == _pin) {
|
|
|
|
scaling = AnalogIn::pin_config[i].scaling;
|
2018-01-05 02:19:51 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return scaling;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return voltage in Volts
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
float AnalogSource::voltage_average()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
return _pin_scaler() * read_average();
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return voltage in Volts, assuming a ratiometric sensor powered by
|
|
|
|
the 5V rail
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
float AnalogSource::voltage_average_ratiometric()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
voltage_average();
|
|
|
|
return _pin_scaler() * _value_ratiometric;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return voltage in Volts
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
float AnalogSource::voltage_latest()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
return _pin_scaler() * read_latest();
|
|
|
|
}
|
|
|
|
|
2021-09-22 16:47:38 -03:00
|
|
|
bool AnalogSource::set_pin(uint8_t pin)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (_pin == pin) {
|
2021-09-22 16:47:38 -03:00
|
|
|
return true;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2021-09-22 16:47:38 -03:00
|
|
|
bool found_pin = false;
|
2022-05-08 07:31:59 -03:00
|
|
|
if (pin == ANALOG_SERVO_VRSSI_PIN) {
|
2021-09-22 16:47:38 -03:00
|
|
|
found_pin = true;
|
|
|
|
} else {
|
|
|
|
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
|
|
|
|
if (AnalogIn::pin_config[i].channel == pin) {
|
|
|
|
found_pin = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (!found_pin) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2018-10-11 20:35:32 -03:00
|
|
|
WITH_SEMAPHORE(_semaphore);
|
|
|
|
_pin = pin;
|
|
|
|
_sum_value = 0;
|
|
|
|
_sum_ratiometric = 0;
|
|
|
|
_sum_count = 0;
|
|
|
|
_latest_value = 0;
|
|
|
|
_value = 0;
|
|
|
|
_value_ratiometric = 0;
|
2021-09-22 16:47:38 -03:00
|
|
|
return true;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
apply a reading in ADC counts
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void AnalogSource::_add_value(float v, float vcc5V)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-10-11 20:35:32 -03:00
|
|
|
WITH_SEMAPHORE(_semaphore);
|
|
|
|
|
|
|
|
_latest_value = v;
|
|
|
|
_sum_value += v;
|
|
|
|
if (vcc5V < 3.0f) {
|
|
|
|
_sum_ratiometric += v;
|
|
|
|
} else {
|
|
|
|
// this compensates for changes in the 5V rail relative to the
|
|
|
|
// 3.3V reference used by the ADC.
|
|
|
|
_sum_ratiometric += v * 5.0f / vcc5V;
|
|
|
|
}
|
|
|
|
_sum_count++;
|
|
|
|
if (_sum_count == 254) {
|
|
|
|
_sum_value /= 2;
|
|
|
|
_sum_ratiometric /= 2;
|
|
|
|
_sum_count /= 2;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2018-01-07 23:37:25 -04:00
|
|
|
/*
|
|
|
|
callback from ADC driver when sample buffer is filled
|
|
|
|
*/
|
2019-02-01 21:47:46 -04:00
|
|
|
void AnalogIn::adccallback(ADCDriver *adcp)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2019-02-01 21:47:46 -04:00
|
|
|
const adcsample_t *buffer = samples;
|
2019-02-13 18:25:29 -04:00
|
|
|
|
2019-08-02 07:57:01 -03:00
|
|
|
stm32_cacheBufferInvalidate(buffer, sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS);
|
2018-01-07 23:37:25 -04:00
|
|
|
for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
|
2019-10-20 10:31:12 -03:00
|
|
|
for (uint8_t j = 0; j < ADC_GRP1_NUM_CHANNELS; j++) {
|
2018-01-07 23:37:25 -04:00
|
|
|
sample_sum[j] += *buffer++;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
2018-01-07 23:37:25 -04:00
|
|
|
sample_count += ADC_DMA_BUF_DEPTH;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-01-07 23:37:25 -04:00
|
|
|
/*
|
|
|
|
setup adc peripheral to capture samples with DMA into a buffer
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void AnalogIn::init()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2021-08-24 02:22:55 -03:00
|
|
|
static_assert(sizeof(uint16_t) == sizeof(adcsample_t), "adcsample_t must be uint16_t");
|
|
|
|
|
2018-02-04 05:36:36 -04:00
|
|
|
if (ADC_GRP1_NUM_CHANNELS == 0) {
|
|
|
|
return;
|
|
|
|
}
|
2018-05-31 19:35:09 -03:00
|
|
|
|
|
|
|
samples = (adcsample_t *)hal.util->malloc_type(sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS, AP_HAL::Util::MEM_DMA_SAFE);
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
adcStart(&ADCD1, NULL);
|
|
|
|
memset(&adcgrpcfg, 0, sizeof(adcgrpcfg));
|
|
|
|
adcgrpcfg.circular = true;
|
|
|
|
adcgrpcfg.num_channels = ADC_GRP1_NUM_CHANNELS;
|
|
|
|
adcgrpcfg.end_cb = adccallback;
|
2021-04-13 22:21:28 -03:00
|
|
|
#if defined(ADC_CFGR_RES_16BITS)
|
2021-04-04 17:47:46 -03:00
|
|
|
// use 16 bit resolution
|
|
|
|
adcgrpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_16BITS;
|
2021-04-13 22:21:28 -03:00
|
|
|
#elif defined(ADC_CFGR_RES_12BITS)
|
2021-04-04 17:47:46 -03:00
|
|
|
// use 12 bit resolution
|
2021-04-13 22:21:28 -03:00
|
|
|
adcgrpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_12BITS;
|
|
|
|
#else
|
|
|
|
// use 12 bit resolution with ADCv1 or ADCv2
|
2018-01-07 23:37:25 -04:00
|
|
|
adcgrpcfg.sqr1 = ADC_SQR1_NUM_CH(ADC_GRP1_NUM_CHANNELS);
|
2019-02-07 22:19:59 -04:00
|
|
|
adcgrpcfg.cr2 = ADC_CR2_SWSTART;
|
|
|
|
#endif
|
2018-01-07 23:37:25 -04:00
|
|
|
|
|
|
|
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
|
|
|
|
uint8_t chan = pin_config[i].channel;
|
|
|
|
// setup cycles per sample for the channel
|
2019-02-07 22:19:59 -04:00
|
|
|
#if defined(STM32H7)
|
2019-02-13 18:25:29 -04:00
|
|
|
adcgrpcfg.pcsel |= (1<<chan);
|
|
|
|
adcgrpcfg.smpr[chan/10] |= ADC_SMPR_SMP_384P5 << (3*(chan%10));
|
|
|
|
if (i < 4) {
|
|
|
|
adcgrpcfg.sqr[0] |= chan << (6*(i+1));
|
|
|
|
} else if (i < 9) {
|
|
|
|
adcgrpcfg.sqr[1] |= chan << (6*(i-4));
|
|
|
|
} else {
|
|
|
|
adcgrpcfg.sqr[2] |= chan << (6*(i-9));
|
|
|
|
}
|
2023-04-12 00:41:35 -03:00
|
|
|
#elif defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
|
|
|
#if defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
2021-03-14 01:02:42 -04:00
|
|
|
adcgrpcfg.smpr[chan/10] |= ADC_SMPR_SMP_640P5 << (3*(chan%10));
|
|
|
|
#else
|
2021-02-04 19:22:41 -04:00
|
|
|
adcgrpcfg.smpr[chan/10] |= ADC_SMPR_SMP_601P5 << (3*(chan%10));
|
2021-03-14 01:02:42 -04:00
|
|
|
#endif
|
2021-02-04 19:22:41 -04:00
|
|
|
// setup channel sequence
|
|
|
|
if (i < 4) {
|
|
|
|
adcgrpcfg.sqr[0] |= chan << (6*(i+1));
|
|
|
|
} else if (i < 9) {
|
|
|
|
adcgrpcfg.sqr[1] |= chan << (6*(i-4));
|
|
|
|
} else {
|
|
|
|
adcgrpcfg.sqr[2] |= chan << (6*(i-9));
|
|
|
|
}
|
2019-02-07 22:19:59 -04:00
|
|
|
#else
|
2018-01-07 23:37:25 -04:00
|
|
|
if (chan < 10) {
|
|
|
|
adcgrpcfg.smpr2 |= ADC_SAMPLE_480 << (3*chan);
|
|
|
|
} else {
|
|
|
|
adcgrpcfg.smpr1 |= ADC_SAMPLE_480 << (3*(chan-10));
|
|
|
|
}
|
|
|
|
// setup channel sequence
|
|
|
|
if (i < 6) {
|
|
|
|
adcgrpcfg.sqr3 |= chan << (5*i);
|
|
|
|
} else if (i < 12) {
|
|
|
|
adcgrpcfg.sqr2 |= chan << (5*(i-6));
|
|
|
|
} else {
|
|
|
|
adcgrpcfg.sqr1 |= chan << (5*(i-12));
|
|
|
|
}
|
2019-02-07 22:19:59 -04:00
|
|
|
#endif
|
2018-01-07 23:37:25 -04:00
|
|
|
}
|
2018-02-04 05:36:36 -04:00
|
|
|
adcStartConversion(&ADCD1, &adcgrpcfg, samples, ADC_DMA_BUF_DEPTH);
|
2021-08-20 21:19:16 -03:00
|
|
|
|
|
|
|
#if HAL_WITH_MCU_MONITORING
|
|
|
|
setup_adc3();
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-01-07 23:37:25 -04:00
|
|
|
/*
|
|
|
|
calculate average sample since last read for all channels
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void AnalogIn::read_adc(uint32_t *val)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-07 23:37:25 -04:00
|
|
|
chSysLock();
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t i = 0; i < ADC_GRP1_NUM_CHANNELS; i++) {
|
2018-01-07 23:37:25 -04:00
|
|
|
val[i] = sample_sum[i] / sample_count;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-01-07 23:37:25 -04:00
|
|
|
memset(sample_sum, 0, sizeof(sample_sum));
|
|
|
|
sample_count = 0;
|
|
|
|
chSysUnlock();
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-01-07 23:37:25 -04:00
|
|
|
|
2021-08-20 21:19:16 -03:00
|
|
|
|
|
|
|
#if HAL_WITH_MCU_MONITORING
|
|
|
|
/*
|
|
|
|
on H7 we can support monitoring MCU temperature and voltage using ADC3
|
|
|
|
*/
|
|
|
|
#define ADC3_GRP1_NUM_CHANNELS 3
|
|
|
|
|
|
|
|
// internal ADC channels (from H7 reference manual)
|
|
|
|
#define ADC3_VSENSE_CHAN 18
|
|
|
|
#define ADC3_VREFINT_CHAN 19
|
|
|
|
#define ADC3_VBAT4_CHAN 17
|
|
|
|
|
|
|
|
// samples filled in by ADC DMA engine
|
|
|
|
adcsample_t *AnalogIn::samples_adc3;
|
|
|
|
uint32_t AnalogIn::sample_adc3_sum[ADC3_GRP1_NUM_CHANNELS];
|
|
|
|
// we also keep min and max so we can report the range of voltages
|
|
|
|
// seen, to give an idea of supply stability
|
|
|
|
uint16_t AnalogIn::sample_adc3_max[ADC3_GRP1_NUM_CHANNELS];
|
|
|
|
uint16_t AnalogIn::sample_adc3_min[ADC3_GRP1_NUM_CHANNELS];
|
|
|
|
uint32_t AnalogIn::sample_adc3_count;
|
|
|
|
|
|
|
|
/*
|
|
|
|
callback from ADC3 driver when sample buffer is filled
|
|
|
|
*/
|
|
|
|
void AnalogIn::adc3callback(ADCDriver *adcp)
|
|
|
|
{
|
|
|
|
const adcsample_t *buffer = samples_adc3;
|
|
|
|
|
|
|
|
stm32_cacheBufferInvalidate(buffer, sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC3_GRP1_NUM_CHANNELS);
|
|
|
|
for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
|
|
|
|
for (uint8_t j = 0; j < ADC3_GRP1_NUM_CHANNELS; j++) {
|
|
|
|
const uint16_t v = *buffer++;
|
|
|
|
sample_adc3_sum[j] += v;
|
|
|
|
if (sample_adc3_min[j] == 0 ||
|
|
|
|
sample_adc3_min[j] > v) {
|
|
|
|
sample_adc3_min[j] = v;
|
|
|
|
}
|
|
|
|
if (sample_adc3_max[j] == 0 ||
|
|
|
|
sample_adc3_max[j] < v) {
|
|
|
|
sample_adc3_max[j] = v;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
sample_adc3_count += ADC_DMA_BUF_DEPTH;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
setup ADC3 for internal temperature and voltage monitoring
|
|
|
|
*/
|
|
|
|
void AnalogIn::setup_adc3(void)
|
|
|
|
{
|
|
|
|
samples_adc3 = (adcsample_t *)hal.util->malloc_type(sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC3_GRP1_NUM_CHANNELS, AP_HAL::Util::MEM_DMA_SAFE);
|
2021-08-24 02:22:55 -03:00
|
|
|
if (samples_adc3 == nullptr) {
|
|
|
|
// not likely, but can't setup ADC3
|
|
|
|
return;
|
|
|
|
}
|
2021-08-20 21:19:16 -03:00
|
|
|
|
|
|
|
adcStart(&ADCD3, NULL);
|
|
|
|
|
|
|
|
adcSTM32EnableVREF(&ADCD3);
|
|
|
|
adcSTM32EnableTS(&ADCD3);
|
|
|
|
adcSTM32EnableVBAT(&ADCD3);
|
|
|
|
|
|
|
|
memset(&adc3grpcfg, 0, sizeof(adc3grpcfg));
|
|
|
|
adc3grpcfg.circular = true;
|
|
|
|
adc3grpcfg.num_channels = ADC3_GRP1_NUM_CHANNELS;
|
|
|
|
adc3grpcfg.end_cb = adc3callback;
|
|
|
|
#if defined(ADC_CFGR_RES_16BITS)
|
|
|
|
// use 16 bit resolution
|
|
|
|
adc3grpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_16BITS;
|
|
|
|
#elif defined(ADC_CFGR_RES_12BITS)
|
|
|
|
// use 12 bit resolution
|
|
|
|
adc3grpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_12BITS;
|
|
|
|
#else
|
|
|
|
// use 12 bit resolution with ADCv1 or ADCv2
|
|
|
|
adc3grpcfg.sqr1 = ADC_SQR1_NUM_CH(ADC3_GRP1_NUM_CHANNELS);
|
|
|
|
adc3grpcfg.cr2 = ADC_CR2_SWSTART;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
const uint8_t channels[ADC3_GRP1_NUM_CHANNELS] = { ADC3_VBAT4_CHAN, ADC3_VSENSE_CHAN, ADC3_VREFINT_CHAN };
|
|
|
|
|
|
|
|
for (uint8_t i=0; i<ADC3_GRP1_NUM_CHANNELS; i++) {
|
|
|
|
uint8_t chan = channels[i];
|
|
|
|
// setup cycles per sample for the channel
|
|
|
|
adc3grpcfg.pcsel |= (1<<chan);
|
|
|
|
adc3grpcfg.smpr[chan/10] |= ADC_SMPR_SMP_384P5 << (3*(chan%10));
|
|
|
|
if (i < 4) {
|
|
|
|
adc3grpcfg.sqr[0] |= chan << (6*(i+1));
|
|
|
|
} else if (i < 9) {
|
|
|
|
adc3grpcfg.sqr[1] |= chan << (6*(i-4));
|
|
|
|
} else {
|
|
|
|
adc3grpcfg.sqr[2] |= chan << (6*(i-9));
|
|
|
|
}
|
|
|
|
}
|
|
|
|
adcStartConversion(&ADCD3, &adc3grpcfg, samples_adc3, ADC_DMA_BUF_DEPTH);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
calculate average sample since last read for all channels
|
|
|
|
*/
|
|
|
|
void AnalogIn::read_adc3(uint32_t *val, uint16_t *min, uint16_t *max)
|
|
|
|
{
|
|
|
|
chSysLock();
|
|
|
|
for (uint8_t i = 0; i < ADC3_GRP1_NUM_CHANNELS; i++) {
|
|
|
|
val[i] = sample_adc3_sum[i] / sample_adc3_count;
|
|
|
|
min[i] = sample_adc3_min[i];
|
|
|
|
max[i] = sample_adc3_max[i];
|
|
|
|
}
|
|
|
|
memset(sample_adc3_sum, 0, sizeof(sample_adc3_sum));
|
|
|
|
memset(sample_adc3_min, 0, sizeof(sample_adc3_min));
|
|
|
|
memset(sample_adc3_max, 0, sizeof(sample_adc3_max));
|
|
|
|
sample_adc3_count = 0;
|
|
|
|
chSysUnlock();
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif // HAL_WITH_MCU_MONITORING
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
called at 1kHz
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void AnalogIn::_timer_tick(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
// read adc at 100Hz
|
|
|
|
uint32_t now = AP_HAL::micros();
|
|
|
|
uint32_t delta_t = now - _last_run;
|
|
|
|
if (delta_t < 10000) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_last_run = now;
|
|
|
|
|
2018-01-07 23:37:25 -04:00
|
|
|
uint32_t buf_adc[ADC_GRP1_NUM_CHANNELS];
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
/* read all channels available */
|
|
|
|
read_adc(buf_adc);
|
2018-04-08 06:30:32 -03:00
|
|
|
|
|
|
|
// update power status flags
|
|
|
|
update_power_flags();
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
// match the incoming channels to the currently active pins
|
|
|
|
for (uint8_t i=0; i < ADC_GRP1_NUM_CHANNELS; i++) {
|
2018-01-13 00:48:43 -04:00
|
|
|
#ifdef ANALOG_VCC_5V_PIN
|
2018-01-07 23:37:25 -04:00
|
|
|
if (pin_config[i].channel == ANALOG_VCC_5V_PIN) {
|
2018-01-05 02:19:51 -04:00
|
|
|
// record the Vcc value for later use in
|
|
|
|
// voltage_average_ratiometric()
|
2021-04-04 17:47:46 -03:00
|
|
|
_board_voltage = buf_adc[i] * pin_config[i].scaling * ADC_BOARD_SCALING;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-01-13 00:48:43 -04:00
|
|
|
#endif
|
2019-06-23 17:05:28 -03:00
|
|
|
#ifdef FMU_SERVORAIL_ADC_CHAN
|
|
|
|
if (pin_config[i].channel == FMU_SERVORAIL_ADC_CHAN) {
|
2021-04-04 17:47:46 -03:00
|
|
|
_servorail_voltage = buf_adc[i] * pin_config[i].scaling * ADC_BOARD_SCALING;
|
2019-06-23 17:05:28 -03:00
|
|
|
}
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-09-15 02:43:54 -03:00
|
|
|
|
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
// now handle special inputs from IOMCU
|
2021-09-28 13:40:08 -03:00
|
|
|
_servorail_voltage = iomcu.get_vservo_adc_count() * (VOLTAGE_SCALING * HAL_IOMCU_VSERVO_SCALAR);
|
|
|
|
_rssi_voltage = iomcu.get_vrssi_adc_count() * (VOLTAGE_SCALING * HAL_IOMCU_VRSSI_SCALAR);
|
2018-09-15 02:43:54 -03:00
|
|
|
#endif
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
|
|
|
|
Debug("chan %u value=%u\n",
|
2018-01-07 23:37:25 -04:00
|
|
|
(unsigned)pin_config[i].channel,
|
2018-01-05 02:19:51 -04:00
|
|
|
(unsigned)buf_adc[i]);
|
2018-09-11 07:29:48 -03:00
|
|
|
for (uint8_t j=0; j < ANALOG_MAX_CHANNELS; j++) {
|
2018-01-13 00:02:05 -04:00
|
|
|
ChibiOS::AnalogSource *c = _channels[j];
|
2018-09-15 02:43:54 -03:00
|
|
|
if (c != nullptr) {
|
|
|
|
if (pin_config[i].channel == c->_pin) {
|
|
|
|
// add a value
|
2021-04-04 17:47:46 -03:00
|
|
|
c->_add_value(buf_adc[i] * ADC_BOARD_SCALING, _board_voltage);
|
2018-09-15 02:43:54 -03:00
|
|
|
} else if (c->_pin == ANALOG_SERVO_VRSSI_PIN) {
|
|
|
|
c->_add_value(_rssi_voltage / VOLTAGE_SCALING, 0);
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2021-08-20 21:19:16 -03:00
|
|
|
#if HAL_WITH_MCU_MONITORING
|
|
|
|
// 20Hz temperature and ref voltage
|
|
|
|
static uint32_t last_mcu_temp_us;
|
|
|
|
if (now - last_mcu_temp_us > 50000 &&
|
|
|
|
hal.scheduler->is_system_initialized()) {
|
|
|
|
last_mcu_temp_us = now;
|
|
|
|
|
|
|
|
uint32_t buf_adc3[ADC3_GRP1_NUM_CHANNELS];
|
|
|
|
uint16_t min_adc3[ADC3_GRP1_NUM_CHANNELS];
|
|
|
|
uint16_t max_adc3[ADC3_GRP1_NUM_CHANNELS];
|
|
|
|
|
|
|
|
read_adc3(buf_adc3, min_adc3, max_adc3);
|
|
|
|
|
|
|
|
// factory calibration values
|
|
|
|
const float TS_CAL1 = *(const volatile uint16_t *)0x1FF1E820;
|
|
|
|
const float TS_CAL2 = *(const volatile uint16_t *)0x1FF1E840;
|
|
|
|
const float VREFINT_CAL = *(const volatile uint16_t *)0x1FF1E860;
|
|
|
|
|
|
|
|
_mcu_temperature = ((110 - 30) / (TS_CAL2 - TS_CAL1)) * (float(buf_adc3[1]) - TS_CAL1) + 30;
|
|
|
|
_mcu_voltage = 3.3 * VREFINT_CAL / float(buf_adc3[2]+0.001);
|
2022-03-06 22:41:31 -04:00
|
|
|
// note min/max swap due to inversion
|
|
|
|
_mcu_voltage_min = 3.3 * VREFINT_CAL / float(max_adc3[2]+0.001);
|
|
|
|
_mcu_voltage_max = 3.3 * VREFINT_CAL / float(min_adc3[2]+0.001);
|
2018-01-08 03:12:21 -04:00
|
|
|
}
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2019-10-20 10:31:12 -03:00
|
|
|
AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2021-02-05 09:18:04 -04:00
|
|
|
WITH_SEMAPHORE(_semaphore);
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t j=0; j<ANALOG_MAX_CHANNELS; j++) {
|
|
|
|
if (_channels[j] == nullptr) {
|
2020-05-08 03:46:57 -03:00
|
|
|
_channels[j] = new AnalogSource(pin);
|
2018-01-05 02:19:51 -04:00
|
|
|
return _channels[j];
|
|
|
|
}
|
|
|
|
}
|
2022-03-21 06:24:57 -03:00
|
|
|
DEV_PRINTF("Out of analog channels\n");
|
2018-01-05 02:19:51 -04:00
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
2018-04-08 06:30:32 -03:00
|
|
|
/*
|
|
|
|
update power status flags
|
|
|
|
*/
|
|
|
|
void AnalogIn::update_power_flags(void)
|
|
|
|
{
|
|
|
|
uint16_t flags = 0;
|
|
|
|
|
2020-02-13 04:05:54 -04:00
|
|
|
/*
|
|
|
|
primary "brick" power supply valid pin. Some boards have this
|
|
|
|
active high, some active low. Use nVALID for active low, VALID
|
|
|
|
for active high
|
|
|
|
*/
|
|
|
|
#if defined(HAL_GPIO_PIN_VDD_BRICK_VALID)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VDD_BRICK_VALID) == 1) {
|
|
|
|
flags |= MAV_POWER_STATUS_BRICK_VALID;
|
|
|
|
}
|
|
|
|
#elif defined(HAL_GPIO_PIN_VDD_BRICK_nVALID)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VDD_BRICK_nVALID) == 0) {
|
2018-04-08 06:30:32 -03:00
|
|
|
flags |= MAV_POWER_STATUS_BRICK_VALID;
|
|
|
|
}
|
|
|
|
#endif
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2020-02-13 04:05:54 -04:00
|
|
|
/*
|
|
|
|
secondary "brick" power supply valid pin. This is servo rail
|
|
|
|
power valid on some boards. Some boards have this active high,
|
|
|
|
some active low. Use nVALID for active low, VALID for active
|
|
|
|
high. This maps to the MAV_POWER_STATUS_SERVO_VALID in mavlink
|
|
|
|
(as this was first added for older boards that used servo rail
|
|
|
|
for backup power)
|
|
|
|
*/
|
|
|
|
#if defined(HAL_GPIO_PIN_VDD_BRICK2_VALID)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VDD_BRICK_VALID) == 1) {
|
2018-04-08 06:30:32 -03:00
|
|
|
flags |= MAV_POWER_STATUS_SERVO_VALID;
|
|
|
|
}
|
2020-02-13 04:05:54 -04:00
|
|
|
#elif defined(HAL_GPIO_PIN_VDD_BRICK2_nVALID)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VDD_BRICK2_nVALID) == 0) {
|
2019-04-24 08:01:40 -03:00
|
|
|
flags |= MAV_POWER_STATUS_SERVO_VALID;
|
|
|
|
}
|
2018-04-08 06:30:32 -03:00
|
|
|
#endif
|
2019-04-24 08:01:40 -03:00
|
|
|
|
2020-02-13 04:05:54 -04:00
|
|
|
/*
|
|
|
|
USB power. This can be VBUS_VALID, VBUS_nVALID or just
|
|
|
|
VBUS. Some boards have both a valid pin and VBUS. The VBUS pin
|
|
|
|
is an analog pin that could be used to read USB voltage.
|
|
|
|
*/
|
|
|
|
#if defined(HAL_GPIO_PIN_VBUS_VALID)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VBUS_VALID) == 1) {
|
2018-04-08 06:30:32 -03:00
|
|
|
flags |= MAV_POWER_STATUS_USB_CONNECTED;
|
|
|
|
}
|
2020-02-13 04:05:54 -04:00
|
|
|
#elif defined(HAL_GPIO_PIN_VBUS_nVALID)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VBUS_nVALID) == 0) {
|
|
|
|
flags |= MAV_POWER_STATUS_USB_CONNECTED;
|
|
|
|
}
|
|
|
|
#elif defined(HAL_GPIO_PIN_VBUS)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VBUS) == 1) {
|
2019-04-24 08:01:40 -03:00
|
|
|
flags |= MAV_POWER_STATUS_USB_CONNECTED;
|
|
|
|
}
|
2018-04-08 06:30:32 -03:00
|
|
|
#endif
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2020-02-13 04:05:54 -04:00
|
|
|
/*
|
|
|
|
overcurrent on "high power" peripheral rail.
|
|
|
|
*/
|
|
|
|
#if defined(HAL_GPIO_PIN_VDD_5V_HIPOWER_OC)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VDD_5V_HIPOWER_OC) == 1) {
|
|
|
|
flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
|
|
|
|
}
|
|
|
|
#elif defined(HAL_GPIO_PIN_VDD_5V_HIPOWER_nOC)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VDD_5V_HIPOWER_nOC) == 0) {
|
2018-04-08 06:30:32 -03:00
|
|
|
flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
|
2019-10-20 10:31:12 -03:00
|
|
|
}
|
2018-04-08 06:30:32 -03:00
|
|
|
#endif
|
|
|
|
|
2020-02-13 04:05:54 -04:00
|
|
|
/*
|
|
|
|
overcurrent on main peripheral rail.
|
|
|
|
*/
|
|
|
|
#if defined(HAL_GPIO_PIN_VDD_5V_PERIPH_OC)
|
|
|
|
if (palReadLine(HAL_GPIO_PIN_VDD_5V_PERIPH_OC) == 1) {
|
|
|
|
flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT;
|
|
|
|
}
|
2020-10-11 00:44:01 -03:00
|
|
|
#elif defined(HAL_GPIO_PIN_VDD_5V_PERIPH_nOC)
|
2020-02-13 04:05:54 -04:00
|
|
|
if (palReadLine(HAL_GPIO_PIN_VDD_5V_PERIPH_nOC) == 0) {
|
2018-04-08 06:30:32 -03:00
|
|
|
flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT;
|
2019-10-20 10:31:12 -03:00
|
|
|
}
|
2018-04-08 06:30:32 -03:00
|
|
|
#endif
|
2020-02-13 04:05:54 -04:00
|
|
|
|
|
|
|
#if defined(HAL_GPIO_PIN_VDD_SERVO_VALID)
|
|
|
|
#error "building with old hwdef.dat"
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if 0
|
|
|
|
/*
|
|
|
|
this bit of debug code is useful when testing the polarity of
|
|
|
|
VALID pins for power sources. It allows you to see the change on
|
|
|
|
USB with a 3s delay, so you can see USB changes by unplugging
|
|
|
|
and re-inserting USB power
|
|
|
|
*/
|
|
|
|
static uint32_t last_change_ms;
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if (_power_flags != flags) {
|
|
|
|
if (last_change_ms == 0) {
|
|
|
|
last_change_ms = now;
|
|
|
|
} else if (now - last_change_ms > 3000) {
|
|
|
|
last_change_ms = 0;
|
|
|
|
hal.console->printf("POWR: 0x%02x -> 0x%02x\n", _power_flags, flags);
|
|
|
|
_power_flags = flags;
|
|
|
|
}
|
|
|
|
if (hal.util->get_soft_armed()) {
|
|
|
|
// the power status has changed while armed
|
|
|
|
flags |= MAV_POWER_STATUS_CHANGED;
|
|
|
|
}
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2019-10-20 10:31:12 -03:00
|
|
|
if (_power_flags != 0 &&
|
|
|
|
_power_flags != flags &&
|
2018-04-08 06:30:32 -03:00
|
|
|
hal.util->get_soft_armed()) {
|
|
|
|
// the power status has changed while armed
|
|
|
|
flags |= MAV_POWER_STATUS_CHANGED;
|
|
|
|
}
|
2020-07-19 21:34:42 -03:00
|
|
|
_accumulated_power_flags |= flags;
|
2018-04-08 06:30:32 -03:00
|
|
|
_power_flags = flags;
|
|
|
|
}
|
2018-03-06 18:41:03 -04:00
|
|
|
#endif // HAL_USE_ADC
|