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
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_HAL_ChibiOS.h"
|
|
|
|
|
|
|
|
#define ANALOG_MAX_CHANNELS 16
|
|
|
|
|
2018-01-07 23:37:25 -04:00
|
|
|
// number of samples on each channel to gather on each DMA callback
|
|
|
|
#define ADC_DMA_BUF_DEPTH 8
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-10-28 20:24:01 -03:00
|
|
|
#if HAL_USE_ADC == TRUE && !defined(HAL_DISABLE_ADC_DRIVER)
|
2018-03-06 18:41:03 -04:00
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
class ChibiOS::AnalogSource : public AP_HAL::AnalogSource {
|
2018-01-05 02:19:51 -04:00
|
|
|
public:
|
2018-01-13 00:02:05 -04:00
|
|
|
friend class ChibiOS::AnalogIn;
|
2020-05-08 03:46:57 -03:00
|
|
|
AnalogSource(int16_t pin);
|
2018-11-07 06:58:46 -04:00
|
|
|
float read_average() override;
|
|
|
|
float read_latest() override;
|
2021-09-22 16:47:38 -03:00
|
|
|
bool set_pin(uint8_t p) override WARN_IF_UNUSED;
|
2018-11-07 06:58:46 -04:00
|
|
|
float voltage_average() override;
|
|
|
|
float voltage_latest() override;
|
|
|
|
float voltage_average_ratiometric() override;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
private:
|
|
|
|
// what value it has
|
|
|
|
int16_t _pin;
|
|
|
|
float _value;
|
|
|
|
float _value_ratiometric;
|
|
|
|
float _latest_value;
|
|
|
|
uint8_t _sum_count;
|
|
|
|
float _sum_value;
|
|
|
|
float _sum_ratiometric;
|
|
|
|
void _add_value(float v, float vcc5V);
|
|
|
|
float _pin_scaler();
|
2018-10-11 20:35:32 -03:00
|
|
|
HAL_Semaphore _semaphore;
|
2018-01-05 02:19:51 -04:00
|
|
|
};
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
class ChibiOS::AnalogIn : public AP_HAL::AnalogIn {
|
2018-01-05 02:19:51 -04:00
|
|
|
public:
|
2018-01-13 00:02:05 -04:00
|
|
|
friend class AnalogSource;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
void init() override;
|
|
|
|
AP_HAL::AnalogSource* channel(int16_t pin) override;
|
|
|
|
void _timer_tick(void);
|
|
|
|
float board_voltage(void) override { return _board_voltage; }
|
|
|
|
float servorail_voltage(void) override { return _servorail_voltage; }
|
|
|
|
uint16_t power_status_flags(void) override { return _power_flags; }
|
2020-07-19 21:34:42 -03:00
|
|
|
uint16_t accumulated_power_status_flags(void) const override { return _accumulated_power_flags; }
|
2021-08-20 21:19:16 -03:00
|
|
|
|
|
|
|
#if HAL_WITH_MCU_MONITORING
|
|
|
|
float mcu_temperature(void) override { return _mcu_temperature; }
|
|
|
|
float mcu_voltage(void) override { return _mcu_voltage; }
|
|
|
|
float mcu_voltage_max(void) override { return _mcu_voltage_max; }
|
|
|
|
float mcu_voltage_min(void) override { return _mcu_voltage_min; }
|
|
|
|
#endif
|
2018-04-08 06:30:32 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
private:
|
|
|
|
void read_adc(uint32_t *val);
|
2018-04-08 06:30:32 -03:00
|
|
|
void update_power_flags(void);
|
2021-08-20 21:19:16 -03:00
|
|
|
static void adccallback(ADCDriver *adcp);
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
ChibiOS::AnalogSource* _channels[ANALOG_MAX_CHANNELS];
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
uint32_t _last_run;
|
|
|
|
float _board_voltage;
|
|
|
|
float _servorail_voltage;
|
2018-09-15 02:43:54 -03:00
|
|
|
float _rssi_voltage;
|
2018-01-05 02:19:51 -04:00
|
|
|
uint16_t _power_flags;
|
2020-07-19 21:34:42 -03:00
|
|
|
uint16_t _accumulated_power_flags; // bitmask of all _power_flags ever set
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
ADCConversionGroup adcgrpcfg;
|
2018-01-07 23:37:25 -04:00
|
|
|
|
|
|
|
struct pin_info {
|
|
|
|
uint8_t channel;
|
|
|
|
float scaling;
|
2019-10-20 10:31:12 -03:00
|
|
|
};
|
2018-01-07 23:37:25 -04:00
|
|
|
static const pin_info pin_config[];
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-05-31 19:35:09 -03:00
|
|
|
static adcsample_t *samples;
|
2018-01-07 23:37:25 -04:00
|
|
|
static uint32_t sample_sum[];
|
|
|
|
static uint32_t sample_count;
|
2021-08-20 21:19:16 -03:00
|
|
|
|
2021-02-05 09:18:04 -04:00
|
|
|
HAL_Semaphore _semaphore;
|
2021-08-20 21:19:16 -03:00
|
|
|
|
|
|
|
#if HAL_WITH_MCU_MONITORING
|
|
|
|
// use ADC3 for MCU temperature and voltage monitoring
|
|
|
|
void setup_adc3();
|
|
|
|
void read_adc3(uint32_t *val, uint16_t *min, uint16_t *max);
|
|
|
|
ADCConversionGroup adc3grpcfg;
|
|
|
|
static void adc3callback(ADCDriver *adcp);
|
|
|
|
static adcsample_t *samples_adc3;
|
|
|
|
static uint32_t sample_adc3_sum[];
|
|
|
|
static uint16_t sample_adc3_max[];
|
|
|
|
static uint16_t sample_adc3_min[];
|
|
|
|
static uint32_t sample_adc3_count;
|
|
|
|
float _mcu_temperature;
|
|
|
|
float _mcu_voltage;
|
|
|
|
float _mcu_voltage_min;
|
|
|
|
float _mcu_voltage_max;
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
};
|
2018-03-06 18:41:03 -04:00
|
|
|
|
|
|
|
#endif // HAL_USE_ADC
|