2016-02-17 21:25:25 -04:00
|
|
|
#pragma once
|
2012-08-27 15:44:50 -03:00
|
|
|
|
|
|
|
#include "AP_HAL_Namespace.h"
|
|
|
|
|
2012-08-27 20:45:10 -03:00
|
|
|
#define RC_INPUT_MIN_PULSEWIDTH 900
|
|
|
|
#define RC_INPUT_MAX_PULSEWIDTH 2100
|
|
|
|
|
2012-08-27 15:44:50 -03:00
|
|
|
class AP_HAL::RCInput {
|
|
|
|
public:
|
2012-08-27 20:45:10 -03:00
|
|
|
/**
|
|
|
|
* Call init from the platform hal instance init, so that both the type of
|
|
|
|
* the RCInput implementation and init argument (e.g. ISRRegistry) are
|
2016-09-16 22:43:32 -03:00
|
|
|
* known to the programmer. (It's too difficult to describe this dependency
|
2012-08-27 20:45:10 -03:00
|
|
|
* in the C++ type system.)
|
|
|
|
*/
|
2015-12-02 11:37:22 -04:00
|
|
|
virtual void init() = 0;
|
2016-10-26 17:41:47 -03:00
|
|
|
virtual void teardown() {};
|
2012-08-27 20:45:10 -03:00
|
|
|
|
|
|
|
/**
|
2017-01-07 21:26:54 -04:00
|
|
|
* Return true if there has been new input since the last call to new_input()
|
2012-08-27 20:45:10 -03:00
|
|
|
*/
|
2017-01-07 21:26:54 -04:00
|
|
|
virtual bool new_input(void) = 0;
|
2014-03-25 00:39:41 -03:00
|
|
|
|
|
|
|
/**
|
|
|
|
* Return the number of valid channels in the last read
|
|
|
|
*/
|
|
|
|
virtual uint8_t num_channels() = 0;
|
2012-08-27 20:45:10 -03:00
|
|
|
|
|
|
|
/* Read a single channel at a time */
|
|
|
|
virtual uint16_t read(uint8_t ch) = 0;
|
|
|
|
|
|
|
|
/* Read an array of channels, return the valid count */
|
|
|
|
virtual uint8_t read(uint16_t* periods, uint8_t len) = 0;
|
2012-12-06 16:45:44 -04:00
|
|
|
|
2017-06-20 00:12:18 -03:00
|
|
|
/* get receiver based RSSI if available. -1 for unknown, 0 for no link, 255 for maximum link */
|
|
|
|
virtual int16_t get_rssi(void) { return -1; }
|
|
|
|
|
2012-12-06 16:45:44 -04:00
|
|
|
/**
|
|
|
|
* Overrides: these are really grody and don't belong here but we need
|
|
|
|
* them at the moment to make the port work.
|
|
|
|
* case v of:
|
|
|
|
* v == -1 -> no change to this channel
|
|
|
|
* v == 0 -> do not override this channel
|
|
|
|
* v > 0 -> set v as override.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/* set_override: set just a specific channel */
|
|
|
|
virtual bool set_override(uint8_t channel, int16_t override) = 0;
|
2016-05-12 13:58:35 -03:00
|
|
|
/* clear_overrides: equivalent to setting all overrides to 0 */
|
2012-12-06 16:45:44 -04:00
|
|
|
virtual void clear_overrides() = 0;
|
|
|
|
|
2015-06-10 03:44:57 -03:00
|
|
|
/* execute receiver bind */
|
2016-07-01 02:35:07 -03:00
|
|
|
virtual bool rc_bind(int dsmMode) { return false; }
|
2012-08-27 15:44:50 -03:00
|
|
|
};
|