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"
|
|
|
|
|
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;
|
2012-12-04 18:50:19 -04:00
|
|
|
virtual void set_pin(uint8_t p) = 0;
|
2013-03-03 01:13:04 -04:00
|
|
|
|
2013-04-25 22:00:56 -03:00
|
|
|
// optionally allow setting of a pin that stops the device from
|
|
|
|
// reading. This is needed for sonar devices where you have more
|
|
|
|
// than one sonar, and you want to stop them interfering with each
|
|
|
|
// other. It assumes that if held low the device is stopped, if
|
|
|
|
// held high the device starts reading.
|
|
|
|
virtual void set_stop_pin(uint8_t p) = 0;
|
|
|
|
|
|
|
|
// optionally allow a settle period in milliseconds. This is only
|
|
|
|
// used if a stop pin is set. If the settle period is non-zero
|
|
|
|
// then the analog input code will wait to get a reading for that
|
|
|
|
// number of milliseconds. Note that this will slow down the
|
|
|
|
// reading of analog inputs.
|
|
|
|
virtual void set_settle_time(uint16_t settle_time_ms) = 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; }
|
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
|