APM:Libraries
AnalogIn.cpp
Go to the documentation of this file.
1 #include "AnalogIn.h"
2 
3 using namespace Empty;
4 
6  _v(v)
7 {}
8 
10  return _v;
11 }
12 
14  return 5.0f * _v / 1024.0f;
15 }
16 
18  return 5.0f * _v / 1024.0f;
19 }
20 
22  return _v;
23 }
24 
25 void AnalogSource::set_pin(uint8_t p)
26 {}
27 
29 {}
30 
31 void AnalogSource::set_settle_time(uint16_t settle_time_ms)
32 {}
33 
35 {}
36 
38 {}
39 
41  return new AnalogSource(1.11);
42 }
43 
45 {
46  return 5.0f;
47 }
void set_stop_pin(uint8_t p)
Definition: AnalogIn.cpp:28
AnalogSource(float v)
Definition: AnalogIn.cpp:5
float board_voltage(void)
Definition: AnalogIn.cpp:44
float read_average()
Definition: AnalogIn.cpp:9
void set_pin(uint8_t p)
Definition: AnalogIn.cpp:25
AP_HAL::AnalogSource * channel(int16_t n)
Definition: AnalogIn.cpp:40
float voltage_latest()
Definition: AnalogIn.cpp:17
float v
Definition: Printf.cpp:15
float voltage_average()
Definition: AnalogIn.cpp:13
void set_settle_time(uint16_t settle_time_ms)
Definition: AnalogIn.cpp:31