ardupilot/libraries/AP_HAL_Linux/AnalogIn_Raspilot.h

47 lines
1.0 KiB
C
Raw Normal View History

#pragma once
2015-08-18 00:29:58 -03:00
#include <AP_ADC/AP_ADC.h>
#include <AP_HAL/SPIDevice.h>
2015-08-18 00:29:58 -03:00
#include "AP_HAL_Linux.h"
2015-08-18 00:29:58 -03:00
#define RASPILOT_ADC_MAX_CHANNELS 8
class AnalogSource_Raspilot: public AP_HAL::AnalogSource {
2015-08-18 00:29:58 -03:00
public:
friend class AnalogIn_Raspilot;
AnalogSource_Raspilot(int16_t pin);
2015-08-18 00:29:58 -03:00
float read_average();
float read_latest();
void set_pin(uint8_t p);
void set_stop_pin(uint8_t p) { }
void set_settle_time(uint16_t settle_time_ms) { }
2015-08-18 00:29:58 -03:00
float voltage_average();
float voltage_latest();
float voltage_average_ratiometric();
private:
int16_t _pin;
float _value;
};
class AnalogIn_Raspilot: public AP_HAL::AnalogIn {
2015-08-18 00:29:58 -03:00
public:
AnalogIn_Raspilot();
void init();
2015-08-18 00:29:58 -03:00
AP_HAL::AnalogSource* channel(int16_t n);
/* Board voltage is not available */
float board_voltage(void);
2015-08-18 00:29:58 -03:00
protected:
void _update();
AP_HAL::AnalogSource *_vcc_pin_analog_source;
AnalogSource_Raspilot *_channels[RASPILOT_ADC_MAX_CHANNELS];
2015-08-18 00:29:58 -03:00
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev;
2015-08-18 00:29:58 -03:00
uint8_t _channels_number;
2015-08-18 00:29:58 -03:00
};