3 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 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 PX4_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 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 44 { 10, (5.7f*3.3f)/4096 },
49 #elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO) 61 #elif defined(CONFIG_ARCH_BOARD_AEROFC_V1) 64 #error "Unknown board type for AnalogIn scaling" 71 PX4AnalogSource::PX4AnalogSource(int16_t
pin,
float initial_value) :
75 _value(initial_value),
76 _value_ratiometric(initial_value),
77 _latest_value(initial_value),
82 #ifdef PX4_ANALOG_VCC_5V_PIN 84 _pin = PX4_ANALOG_VCC_5V_PIN;
121 for (uint8_t i=0; i<num_scalings; i++) {
196 _current_stop_pin_i(0),
198 _servorail_voltage(0),
204 _adc_fd =
open(ADC0_DEVICE_PATH, O_RDONLY | O_NONBLOCK);
237 if (c2 && c2->
_stop_pin != -1 && j != idx) {
260 if (delta_t < 10000) {
265 struct adc_msg_s buf_adc[PX4_ANALOG_MAX_CHANNELS];
274 int ret =
read(
_adc_fd, &buf_adc,
sizeof(buf_adc));
277 for (uint8_t i=0; i<ret/
sizeof(buf_adc[0]); i++) {
278 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO) 279 if (buf_adc[i].am_channel == 4) {
286 for (uint8_t i=0; i<ret/
sizeof(buf_adc[0]); i++) {
287 Debug(
"chan %u value=%u\n",
288 (
unsigned)buf_adc[i].am_channel,
289 (
unsigned)buf_adc[i].am_data);
292 if (c !=
nullptr && buf_adc[i].am_channel == c->
_pin) {
308 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 311 struct battery_status_s battery;
312 bool updated =
false;
319 if (c ==
nullptr)
continue;
320 if (c->
_pin == PX4_ANALOG_ORB_BATTERY_VOLTAGE_PIN) {
323 if (c->
_pin == PX4_ANALOG_ORB_BATTERY_CURRENT_PIN) {
334 #if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO) 337 struct servorail_status_s servorail;
338 bool updated =
false;
346 if (c ==
nullptr)
continue;
347 if (c->
_pin == PX4_ANALOG_ORB_SERVO_VOLTAGE_PIN) {
350 if (c->
_pin == PX4_ANALOG_ORB_SERVO_VRSSI_PIN) {
358 struct system_power_s system_power;
359 bool updated =
false;
363 if (system_power.usb_connected) flags |= MAV_POWER_STATUS_USB_CONNECTED;
364 if (system_power.brick_valid) flags |= MAV_POWER_STATUS_BRICK_VALID;
365 if (system_power.servo_valid) flags |= MAV_POWER_STATUS_SERVO_VALID;
366 if (system_power.periph_5V_OC) flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT;
367 if (system_power.hipower_5V_OC) flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
372 flags |= MAV_POWER_STATUS_CHANGED;
393 #endif // CONFIG_HAL_BOARD
bool get_soft_armed() const
uint32_t _stop_pin_change_time
AP_HAL::AnalogSource * channel(int16_t pin) override
uint8_t _current_stop_pin_i
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
#define Debug(fmt, args ...)
uint64_t _servorail_timestamp
virtual void write(uint8_t pin, uint8_t value)=0
void _add_value(float v, float vcc5V)
virtual void resume_timer_procs()=0
uint64_t _battery_timestamp
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.
static const struct @103 pin_scaling[]
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 -*-
PX4::PX4AnalogSource * _channels[PX4_ANALOG_MAX_CHANNELS]
virtual void suspend_timer_procs()=0
#define ANALOG_INPUT_BOARD_VCC
#define PX4_ANALOG_MAX_CHANNELS
void set_stop_pin(uint8_t p)
void panic(const char *errormsg,...) FMT_PRINTF(1
AP_HAL::Scheduler * scheduler
float voltage_average_ratiometric()
#define PX4_VOLTAGE_SCALING