APM:Libraries
AnalogIn.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_VRBRAIN.h"
4 #include <pthread.h>
5 #include <uORB/uORB.h>
6 
7 #define VRBRAIN_ANALOG_MAX_CHANNELS 16
8 
9 
10 #if defined(CONFIG_ARCH_BOARD_VRBRAIN_V45) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V52) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V52E) || defined(CONFIG_ARCH_BOARD_VRCORE_V10) || defined(CONFIG_ARCH_BOARD_VRBRAIN_V54)
11 #define VRBRAIN_ANALOG_ORB_BATTERY_VOLTAGE_PIN 10
12 #define VRBRAIN_ANALOG_ORB_BATTERY_CURRENT_PIN 11
13 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51)
14 #define VRBRAIN_ANALOG_ORB_BATTERY_VOLTAGE_PIN 10
15 #define VRBRAIN_ANALOG_ORB_BATTERY_CURRENT_PIN -1
16 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
17 #define VRBRAIN_ANALOG_ORB_BATTERY_VOLTAGE_PIN 10
18 #define VRBRAIN_ANALOG_ORB_BATTERY_CURRENT_PIN 1
19 #endif
20 
22 public:
24  VRBRAINAnalogSource(int16_t pin, float initial_value);
25  float read_average();
26  float read_latest();
27  void set_pin(uint8_t p);
28  float voltage_average();
29  float voltage_latest();
31 
32  // implement stop pins
33  void set_stop_pin(uint8_t p);
34  void set_settle_time(uint16_t settle_time_ms) { _settle_time_ms = settle_time_ms; }
35 
36 private:
37  // what pin it is attached to
38  int16_t _pin;
39  int16_t _stop_pin;
40  uint16_t _settle_time_ms;
41 
42  // what value it has
43  float _value;
46  uint8_t _sum_count;
47  float _sum_value;
49  void _add_value(float v, float vcc5V);
50  float _pin_scaler();
51 };
52 
54 public:
56  void init() override;
57  AP_HAL::AnalogSource* channel(int16_t pin) override;
58  void _timer_tick(void);
59  float board_voltage(void) override { return _board_voltage; }
60  float servorail_voltage(void) override { return _servorail_voltage; }
61  uint16_t power_status_flags(void) override { return _power_flags; }
62 
63 private:
64  int _adc_fd = -1;
71 
72  // what pin is currently held low to stop a sonar from reading
75 
76  uint32_t _last_run;
79  uint16_t _power_flags;
80 
81  void next_stop_pin(void);
82 };
uint8_t _current_stop_pin_i
Definition: AnalogIn.h:73
void _add_value(float v, float vcc5V)
Definition: AnalogIn.cpp:164
VRBRAINAnalogSource(int16_t pin, float initial_value)
Definition: AnalogIn.cpp:60
#define VRBRAIN_ANALOG_MAX_CHANNELS
Definition: AnalogIn.h:7
float board_voltage(void) override
Definition: AnalogIn.h:59
uint32_t _stop_pin_change_time
Definition: AnalogIn.h:74
float v
Definition: Printf.cpp:15
float servorail_voltage(void) override
Definition: AnalogIn.h:60
uint16_t power_status_flags(void) override
Definition: AnalogIn.h:61
uint64_t _battery_timestamp
Definition: AnalogIn.h:68
void init()
Generic board initialization function.
Definition: system.cpp:136
uint64_t _servorail_timestamp
Definition: AnalogIn.h:69
void set_settle_time(uint16_t settle_time_ms)
Definition: AnalogIn.h:34
static int8_t pin
Definition: AnalogIn.cpp:15
void set_stop_pin(uint8_t p)
Definition: AnalogIn.cpp:78