21 #if HAL_USE_ADC == TRUE 27 extern AP_IOMCU iomcu;
30 #ifndef CHIBIOS_ADC_MAVLINK_DEBUG 32 #define CHIBIOS_ADC_MAVLINK_DEBUG 0 37 #define ANLOGIN_DEBUGGING 0 40 #define VOLTAGE_SCALING (3.3f/4096.0f) 43 # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) 45 # define Debug(fmt, args ...) 58 #define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE_SIMPLE(AnalogIn::pin_config) 67 _value(initial_value),
68 _value_ratiometric(initial_value),
69 _latest_value(initial_value),
102 if (AnalogIn::pin_config[i].channel ==
_pin) {
103 scaling = AnalogIn::pin_config[i].
scaling;
175 _servorail_voltage(0),
204 adcStart(&ADCD1,
NULL);
218 adcgrpcfg.smpr1 |= ADC_SAMPLE_480 << (3*(chan-10));
254 if (delta_t < 10000) {
269 #ifdef ANALOG_VCC_5V_PIN 278 Debug(
"chan %u value=%u\n",
280 (
unsigned)buf_adc[i]);
295 #if CHIBIOS_ADC_MAVLINK_DEBUG 296 static uint8_t
count;
303 mavlink_msg_ap_adc_send(MAVLINK_COMM_0, adc[0], adc[1], adc[2], adc[3], adc[4], adc[5]);
327 #ifdef HAL_GPIO_PIN_VDD_BRICK_VALID 328 if (!palReadLine(HAL_GPIO_PIN_VDD_BRICK_VALID)) {
329 flags |= MAV_POWER_STATUS_BRICK_VALID;
333 #ifdef HAL_GPIO_PIN_VDD_SERVO_VALID 334 if (!palReadLine(HAL_GPIO_PIN_VDD_SERVO_VALID)) {
335 flags |= MAV_POWER_STATUS_SERVO_VALID;
339 #ifdef HAL_GPIO_PIN_VBUS 340 if (palReadLine(HAL_GPIO_PIN_VBUS)) {
341 flags |= MAV_POWER_STATUS_USB_CONNECTED;
345 #ifdef HAL_GPIO_PIN_VDD_5V_HIPOWER_OC 346 if (!palReadLine(HAL_GPIO_PIN_VDD_5V_HIPOWER_OC)) {
347 flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
351 #ifdef HAL_GPIO_PIN_VDD_5V_PERIPH_OC 352 if (!palReadLine(HAL_GPIO_PIN_VDD_5V_PERIPH_OC)) {
353 flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT;
360 flags |= MAV_POWER_STATUS_CHANGED;
364 #endif // HAL_USE_ADC
bool get_soft_armed() const
void update_power_flags(void)
static adcsample_t samples[]
AP_HAL::UARTDriver * console
static uint8_t buffer[SRXL_FRAMELEN_MAX]
AP_HAL::AnalogSource * channel(int16_t pin) override
#define Debug(fmt, args ...)
virtual void printf(const char *,...) FMT_PRINTF(2
AnalogSource(int16_t pin, float initial_value)
static uint32_t sample_sum[]
ChibiOS::AnalogSource * _channels[ANALOG_MAX_CHANNELS]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void _add_value(float v, float vcc5V)
friend class AnalogSource
#define ADC_GRP1_NUM_CHANNELS
float voltage_average_ratiometric()
AP_HAL::AnalogSource * chan
static uint32_t sample_count
static void adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
static const pin_info pin_config[]
#define ANALOG_MAX_CHANNELS
ADCConversionGroup adcgrpcfg
#define ADC_DMA_BUF_DEPTH
void read_adc(uint32_t *val)