APM:Libraries
AnalogIn.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <inttypes.h>
4 
5 #include "AP_HAL_Namespace.h"
6 
8 public:
9  virtual float read_average() = 0;
10  virtual float read_latest() = 0;
11  virtual void set_pin(uint8_t p) = 0;
12 
13  // optionally allow setting of a pin that stops the device from
14  // reading. This is needed for sonar devices where you have more
15  // than one sonar, and you want to stop them interfering with each
16  // other. It assumes that if held low the device is stopped, if
17  // held high the device starts reading.
18  virtual void set_stop_pin(uint8_t p) = 0;
19 
20  // optionally allow a settle period in milliseconds. This is only
21  // used if a stop pin is set. If the settle period is non-zero
22  // then the analog input code will wait to get a reading for that
23  // number of milliseconds. Note that this will slow down the
24  // reading of analog inputs.
25  virtual void set_settle_time(uint16_t settle_time_ms) = 0;
26 
27  // return a voltage from 0.0 to 5.0V, scaled
28  // against a reference voltage
29  virtual float voltage_average() = 0;
30 
31  // return a voltage from 0.0 to 5.0V, scaled
32  // against a reference voltage
33  virtual float voltage_latest() = 0;
34 
35  // return a voltage from 0.0 to 5.0V, assuming a ratiometric
36  // sensor
37  virtual float voltage_average_ratiometric() = 0;
38 };
39 
41 public:
42  virtual void init() = 0;
43  virtual AP_HAL::AnalogSource* channel(int16_t n) = 0;
44 
45  // board 5V rail voltage in volts
46  virtual float board_voltage(void) = 0;
47 
48  // servo rail voltage in volts, or 0 if unknown
49  virtual float servorail_voltage(void) { return 0; }
50 
51  // power supply status flags, see MAV_POWER_STATUS
52  virtual uint16_t power_status_flags(void) { return 0; }
53 };
54 
55 #define ANALOG_INPUT_BOARD_VCC 254
56 #define ANALOG_INPUT_NONE 255
virtual float voltage_average()=0
virtual float read_average()=0
virtual void set_settle_time(uint16_t settle_time_ms)=0
virtual void set_stop_pin(uint8_t p)=0
virtual uint16_t power_status_flags(void)
Definition: AnalogIn.h:52
virtual float servorail_voltage(void)
Definition: AnalogIn.h:49
void init()
Generic board initialization function.
Definition: system.cpp:136
virtual float read_latest()=0
virtual float voltage_latest()=0
virtual void set_pin(uint8_t p)=0
virtual float voltage_average_ratiometric()=0