3 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 5 #include <drivers/drv_adc.h> 11 #include <nuttx/analog/adc.h> 12 #include <nuttx/config.h> 13 #include <arch/board/board.h> 14 #include <uORB/topics/battery_status.h> 15 #include <uORB/topics/servorail_status.h> 16 #include <uORB/topics/system_power.h> 21 #define ANLOGIN_DEBUGGING 0 24 #define VRBRAIN_VOLTAGE_SCALING (3.3f/4096.0f) 27 # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) 29 # define Debug(fmt, args ...) 42 #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) 45 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51) 47 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52) 53 #error "Unknown board type for AnalogIn scaling" 60 VRBRAINAnalogSource::VRBRAINAnalogSource(int16_t
pin,
float initial_value) :
64 _value(initial_value),
65 _value_ratiometric(initial_value),
66 _latest_value(initial_value),
110 for (uint8_t i=0; i<num_scalings; i++) {
185 _current_stop_pin_i(0),
187 _servorail_voltage(0),
193 _adc_fd =
open(ADC0_DEVICE_PATH, O_RDONLY | O_NONBLOCK);
226 if (c2 && c2->
_stop_pin != -1 && j != idx) {
249 if (delta_t < 10000) {
254 struct adc_msg_s buf_adc[VRBRAIN_ANALOG_MAX_CHANNELS];
263 int ret =
read(
_adc_fd, &buf_adc,
sizeof(buf_adc));
266 for (uint8_t i=0; i<ret/
sizeof(buf_adc[0]); i++) {
267 Debug(
"chan %u value=%u\n",
268 (
unsigned)buf_adc[i].am_channel,
269 (
unsigned)buf_adc[i].am_data);
272 if (c !=
nullptr && buf_adc[i].am_channel == c->
_pin) {
302 #endif // CONFIG_HAL_BOARD
uint8_t _current_stop_pin_i
VRBRAIN::VRBRAINAnalogSource * _channels[VRBRAIN_ANALOG_MAX_CHANNELS]
void _add_value(float v, float vcc5V)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
#define VRBRAIN_ANALOG_MAX_CHANNELS
virtual void write(uint8_t pin, uint8_t value)=0
AP_HAL::AnalogSource * channel(int16_t pin) override
virtual void resume_timer_procs()=0
uint32_t _stop_pin_change_time
virtual void printf(const char *,...) FMT_PRINTF(2
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
virtual void pinMode(uint8_t pin, uint8_t output)=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual void suspend_timer_procs()=0
static const struct @112 pin_scaling[]
#define Debug(fmt, args ...)
float voltage_average_ratiometric()
#define VRBRAIN_VOLTAGE_SCALING
void panic(const char *errormsg,...) FMT_PRINTF(1
void set_stop_pin(uint8_t p)
AP_HAL::Scheduler * scheduler