APM:Libraries
AnalogIn.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
5 
6 #define SITL_INPUT_MAX_CHANNELS 12
7 
9 public:
10  friend class HALSITL::AnalogIn;
11  /* pin designates the ADC input number */
12  ADCSource(SITL_State *sitlState, int16_t pin);
13 
14  /* implement AnalogSource virtual api: */
15  float read_average();
16  float read_latest();
17  void set_pin(uint8_t p);
18  float voltage_average();
19  float voltage_latest();
21  return voltage_average();
22  }
23  void set_stop_pin(uint8_t pin) {}
24  void set_settle_time(uint16_t settle_time_ms) {}
25 
26 private:
28  int16_t _pin;
29 };
30 
31 /* AnalogIn : a concrete class providing the implementations of the
32  * timer event and the AP_HAL::AnalogIn interface */
34 public:
35  explicit AnalogIn(SITL_State *sitlState): _sitlState(sitlState) {}
36  void init();
37  AP_HAL::AnalogSource* channel(int16_t n);
38  float board_voltage(void) {
39  return 5.0f;
40  }
41 private:
42  static ADCSource* _channels[SITL_INPUT_MAX_CHANNELS];
44 };
float read_average()
Definition: AnalogIn.cpp:17
AnalogIn(SITL_State *sitlState)
Definition: AnalogIn.h:35
ADCSource(SITL_State *sitlState, int16_t pin)
Definition: AnalogIn.cpp:12
void set_pin(uint8_t p)
Definition: AnalogIn.cpp:61
void set_stop_pin(uint8_t pin)
Definition: AnalogIn.h:23
float voltage_latest()
Definition: AnalogIn.cpp:25
SITL_State * _sitlState
Definition: AnalogIn.h:27
float board_voltage(void)
Definition: AnalogIn.h:38
float read_latest()
Definition: AnalogIn.cpp:29
SITL_State * _sitlState
Definition: AnalogIn.h:43
void set_settle_time(uint16_t settle_time_ms)
Definition: AnalogIn.h:24
float voltage_average()
Definition: AnalogIn.cpp:21
#define SITL_INPUT_MAX_CHANNELS
Definition: AnalogIn.h:6
void init()
Generic board initialization function.
Definition: system.cpp:136
static SITL_State sitlState
static int8_t pin
Definition: AnalogIn.cpp:15
float voltage_average_ratiometric()
Definition: AnalogIn.h:20