APM:Libraries
AnalogIn.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3 
4 #include "AP_HAL_SITL.h"
5 #include "AnalogIn.h"
6 #include <stdint.h>
7 
8 using namespace HALSITL;
9 
10 extern const AP_HAL::HAL& hal;
11 
13  _sitlState(sitlState),
14  _pin(pin)
15 {}
16 
18  return read_latest();
19 }
20 
22  return (5.0f/1023.0f) * read_average();
23 }
24 
26  return (5.0f/1023.0f) * read_latest();
27 }
28 
30  switch (_pin) {
32  return 1023;
33 
34  case 0:
36 
37  case 1:
39 
40  case 2:
42 
43  case 12:
45 
46  case 13:
48 
49  case 14:
51 
52  case 15:
54 
55  case ANALOG_INPUT_NONE:
56  default:
57  return 0.0f;
58  }
59 }
60 
61 void ADCSource::set_pin(uint8_t pin) {
62  _pin = pin;
63 }
64 
65 void AnalogIn::init() {
66 }
67 
69  return new ADCSource(_sitlState, pin);
70 }
71 
72 #endif
float read_average()
Definition: AnalogIn.cpp:17
AP_HAL::AnalogSource * channel(int16_t n)
uint16_t voltage2_pin_value
Definition: SITL_State.h:70
ADCSource(SITL_State *sitlState, int16_t pin)
Definition: AnalogIn.cpp:12
#define ANALOG_INPUT_NONE
Definition: AnalogIn.h:56
void set_pin(uint8_t p)
Definition: AnalogIn.cpp:61
uint16_t current2_pin_value
Definition: SITL_State.h:71
uint16_t airspeed_2_pin_value
Definition: SITL_State.h:67
uint16_t voltage_pin_value
Definition: SITL_State.h:68
uint8_t pin
Definition: AnalogIn.cpp:39
float voltage_latest()
Definition: AnalogIn.cpp:25
uint16_t current_pin_value
Definition: SITL_State.h:69
#define f(i)
SITL_State * _sitlState
Definition: AnalogIn.h:27
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AnalogIn.cpp:6
uint16_t sonar_pin_value
Definition: SITL_State.h:65
float read_latest()
Definition: AnalogIn.cpp:29
float voltage_average()
Definition: AnalogIn.cpp:21
static SITL_State sitlState
uint16_t airspeed_pin_value
Definition: SITL_State.h:66
#define ANALOG_INPUT_BOARD_VCC
Definition: AnalogIn.h:55