2016-02-17 21:25:25 -04:00
|
|
|
#pragma once
|
2012-08-20 15:37:46 -03:00
|
|
|
|
2015-10-21 14:51:49 -03:00
|
|
|
#include <inttypes.h>
|
|
|
|
|
2012-08-20 15:37:46 -03:00
|
|
|
#include "AP_HAL_Namespace.h"
|
2021-08-22 22:40:20 -03:00
|
|
|
#include "AP_HAL_Boards.h"
|
2012-08-20 15:37:46 -03:00
|
|
|
|
2012-09-10 23:05:02 -03:00
|
|
|
class AP_HAL::AnalogSource {
|
|
|
|
public:
|
2012-12-06 19:57:30 -04:00
|
|
|
virtual float read_average() = 0;
|
|
|
|
virtual float read_latest() = 0;
|
2021-09-22 16:46:55 -03:00
|
|
|
virtual bool set_pin(uint8_t p) WARN_IF_UNUSED = 0;
|
2013-03-03 01:13:04 -04:00
|
|
|
|
|
|
|
// return a voltage from 0.0 to 5.0V, scaled
|
|
|
|
// against a reference voltage
|
|
|
|
virtual float voltage_average() = 0;
|
2013-05-13 02:12:43 -03:00
|
|
|
|
2013-09-12 00:23:04 -03:00
|
|
|
// return a voltage from 0.0 to 5.0V, scaled
|
|
|
|
// against a reference voltage
|
|
|
|
virtual float voltage_latest() = 0;
|
|
|
|
|
2013-05-13 02:12:43 -03:00
|
|
|
// return a voltage from 0.0 to 5.0V, assuming a ratiometric
|
|
|
|
// sensor
|
|
|
|
virtual float voltage_average_ratiometric() = 0;
|
2012-09-10 23:05:02 -03:00
|
|
|
};
|
|
|
|
|
2012-08-20 15:37:46 -03:00
|
|
|
class AP_HAL::AnalogIn {
|
|
|
|
public:
|
2015-12-02 11:37:22 -04:00
|
|
|
virtual void init() = 0;
|
2012-12-06 14:57:50 -04:00
|
|
|
virtual AP_HAL::AnalogSource* channel(int16_t n) = 0;
|
2014-02-13 02:07:32 -04:00
|
|
|
|
|
|
|
// board 5V rail voltage in volts
|
|
|
|
virtual float board_voltage(void) = 0;
|
2014-02-13 07:08:08 -04:00
|
|
|
|
|
|
|
// servo rail voltage in volts, or 0 if unknown
|
|
|
|
virtual float servorail_voltage(void) { return 0; }
|
|
|
|
|
|
|
|
// power supply status flags, see MAV_POWER_STATUS
|
|
|
|
virtual uint16_t power_status_flags(void) { return 0; }
|
2020-07-19 21:34:43 -03:00
|
|
|
|
|
|
|
// bitmask of all _power_flags bits ever set, so transient
|
|
|
|
// failures can still be diagnosed
|
|
|
|
virtual uint16_t accumulated_power_status_flags(void) const { return 0; }
|
2021-08-22 22:40:20 -03:00
|
|
|
|
2024-02-01 23:26:43 -04:00
|
|
|
// this enum class is 1:1 with MAVLink's MAV_POWER_STATUS enumeration!
|
|
|
|
enum class PowerStatusFlag : uint16_t {
|
|
|
|
BRICK_VALID = 1, // main brick power supply valid
|
|
|
|
SERVO_VALID = 2, // main servo power supply valid for FMU
|
|
|
|
USB_CONNECTED = 4, // USB power is connected
|
|
|
|
PERIPH_OVERCURRENT = 8, // peripheral supply is in over-current state
|
|
|
|
PERIPH_HIPOWER_OVERCURRENT = 16, // hi-power peripheral supply is in over-current state
|
|
|
|
CHANGED = 32, // Power status has changed since boot
|
|
|
|
};
|
|
|
|
|
2021-08-22 22:40:20 -03:00
|
|
|
#if HAL_WITH_MCU_MONITORING
|
|
|
|
virtual float mcu_temperature(void) { return 0; }
|
|
|
|
virtual float mcu_voltage(void) { return 0; }
|
|
|
|
virtual float mcu_voltage_max(void) { return 0; }
|
|
|
|
virtual float mcu_voltage_min(void) { return 0; }
|
|
|
|
#endif
|
2012-08-20 15:37:46 -03:00
|
|
|
};
|
|
|
|
|
2012-11-28 20:03:13 -04:00
|
|
|
#define ANALOG_INPUT_BOARD_VCC 254
|
|
|
|
#define ANALOG_INPUT_NONE 255
|