APM:Libraries
AnalogIn.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_PX4.h"
4 #include <pthread.h>
5 #include <uORB/uORB.h>
6 
7 #define PX4_ANALOG_MAX_CHANNELS 16
8 
9 
10 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
11 // these are virtual pins that read from the ORB
12 #define PX4_ANALOG_ORB_BATTERY_VOLTAGE_PIN 100
13 #define PX4_ANALOG_ORB_BATTERY_CURRENT_PIN 101
14 #elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO)
15 #define PX4_ANALOG_VCC_5V_PIN 4
16 #define PX4_ANALOG_ORB_SERVO_VOLTAGE_PIN 102
17 #define PX4_ANALOG_ORB_SERVO_VRSSI_PIN 103
18 #endif
19 
21 public:
22  friend class PX4::PX4AnalogIn;
23  PX4AnalogSource(int16_t pin, float initial_value);
24  float read_average();
25  float read_latest();
26  void set_pin(uint8_t p);
27  float voltage_average();
28  float voltage_latest();
30 
31  // implement stop pins
32  void set_stop_pin(uint8_t p);
33  void set_settle_time(uint16_t settle_time_ms) { _settle_time_ms = settle_time_ms; }
34 
35 private:
36  // what pin it is attached to
37  int16_t _pin;
38  int16_t _stop_pin;
39  uint16_t _settle_time_ms;
40 
41  // what value it has
42  float _value;
45  uint8_t _sum_count;
46  float _sum_value;
48  void _add_value(float v, float vcc5V);
49  float _pin_scaler();
50 };
51 
53 public:
54  PX4AnalogIn();
55  void init() override;
56  AP_HAL::AnalogSource* channel(int16_t pin) override;
57  void _timer_tick(void);
58  float board_voltage(void) override { return _board_voltage; }
59  float servorail_voltage(void) override { return _servorail_voltage; }
60  uint16_t power_status_flags(void) override { return _power_flags; }
61 
62 private:
63  int _adc_fd = -1;
70 
71  // what pin is currently held low to stop a sonar from reading
74 
75  uint32_t _last_run;
78  uint16_t _power_flags;
79 
80  void next_stop_pin(void);
81 };
uint32_t _stop_pin_change_time
Definition: AnalogIn.h:73
int _battery_handle
Definition: AnalogIn.h:64
uint8_t _current_stop_pin_i
Definition: AnalogIn.h:72
int _servorail_handle
Definition: AnalogIn.h:65
float servorail_voltage(void) override
Definition: AnalogIn.h:59
float _value_ratiometric
Definition: AnalogIn.h:43
uint64_t _servorail_timestamp
Definition: AnalogIn.h:68
PX4AnalogSource(int16_t pin, float initial_value)
Definition: AnalogIn.cpp:71
void _add_value(float v, float vcc5V)
Definition: AnalogIn.cpp:175
float board_voltage(void) override
Definition: AnalogIn.h:58
uint64_t _battery_timestamp
Definition: AnalogIn.h:67
uint8_t _sum_count
Definition: AnalogIn.h:45
uint16_t _settle_time_ms
Definition: AnalogIn.h:39
float v
Definition: Printf.cpp:15
float _sum_ratiometric
Definition: AnalogIn.h:47
uint16_t _power_flags
Definition: AnalogIn.h:78
uint32_t _last_run
Definition: AnalogIn.h:75
void set_pin(uint8_t p)
Definition: AnalogIn.cpp:156
void init()
Generic board initialization function.
Definition: system.cpp:136
float _board_voltage
Definition: AnalogIn.h:76
#define PX4_ANALOG_MAX_CHANNELS
Definition: AnalogIn.h:7
void set_stop_pin(uint8_t p)
Definition: AnalogIn.cpp:89
uint16_t power_status_flags(void) override
Definition: AnalogIn.h:60
float _servorail_voltage
Definition: AnalogIn.h:77
static int8_t pin
Definition: AnalogIn.cpp:15
void set_settle_time(uint16_t settle_time_ms)
Definition: AnalogIn.h:33
int _system_power_handle
Definition: AnalogIn.h:66
float voltage_average_ratiometric()
Definition: AnalogIn.cpp:142