APM:Libraries
AnalogIn_Navio2.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_Linux.h"
4 
5 #include <fcntl.h>
6 
7 #define NAVIO_ADC_MAX_CHANNELS 6
8 
10 public:
11  friend class AnalogIn_Navio2;
12  AnalogSource_Navio2(uint8_t pin);
13  float read_average() override;
14  float read_latest() override;
15  void set_pin(uint8_t p) override;
16  void set_stop_pin(uint8_t p) override{}
17  void set_settle_time(uint16_t settle_time_ms) override{}
18  float voltage_average() override;
19  float voltage_latest() override;
20  float voltage_average_ratiometric() override;
21 private:
22  void set_channel(uint8_t pin);
23  uint8_t _pin;
24  int _fd = -1;
25  float _value = 0.0f;
26 };
27 
29 public:
31  void init() override;
32  AP_HAL::AnalogSource *channel(int16_t n) override;
33  float board_voltage(void) override;
34  float servorail_voltage(void) override;
35 
36 private:
38  uint8_t _channels_number = NAVIO_ADC_MAX_CHANNELS;
39  AP_HAL::AnalogSource *_board_voltage_pin = nullptr;
40  AP_HAL::AnalogSource *_servorail_pin = nullptr;
41 };
void set_pin(uint8_t p) override
void set_stop_pin(uint8_t p) override
friend class AnalogIn_Navio2
void set_channel(uint8_t pin)
float voltage_average_ratiometric() override
float read_average() override
float voltage_latest() override
float voltage_average() override
void init()
Generic board initialization function.
Definition: system.cpp:136
#define NAVIO_ADC_MAX_CHANNELS
static int8_t pin
Definition: AnalogIn.cpp:15
AnalogSource_Navio2(uint8_t pin)
void set_settle_time(uint16_t settle_time_ms) override
float read_latest() override