2012-08-27 15:44:50 -03:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_AVR_RC_INPUT_H__
|
|
|
|
#define __AP_HAL_AVR_RC_INPUT_H__
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include "AP_HAL_AVR_Namespace.h"
|
|
|
|
|
2012-08-27 20:45:27 -03:00
|
|
|
#define AVR_RC_INPUT_NUM_CHANNELS 8
|
2013-04-29 02:35:59 -03:00
|
|
|
#define AVR_RC_INPUT_MIN_CHANNELS 5 // for ppm sum we allow less than 8 channels to make up a valid packet
|
2012-08-27 20:45:27 -03:00
|
|
|
|
2012-08-27 15:44:50 -03:00
|
|
|
class AP_HAL_AVR::APM1RCInput : public AP_HAL::RCInput {
|
|
|
|
public:
|
2012-12-03 21:47:18 -04:00
|
|
|
/**
|
|
|
|
* init:
|
|
|
|
* HAL_AVR::init should pass in a AP_HAL_AVR::ISRRegistry* as a void*
|
|
|
|
*/
|
2012-08-27 20:45:27 -03:00
|
|
|
void init(void* isrregistry);
|
2012-12-03 21:47:18 -04:00
|
|
|
|
|
|
|
/**
|
2013-04-29 03:05:53 -03:00
|
|
|
* valid_channels():
|
2012-12-03 21:47:18 -04:00
|
|
|
* Return the number of currently valid channels.
|
|
|
|
* Typically 0 (no valid radio channels) or 8 (implementation-defined)
|
|
|
|
* Could be less than or greater than 8 depending on your incoming radio
|
|
|
|
* or PPM stream
|
|
|
|
*/
|
2013-04-29 03:05:53 -03:00
|
|
|
uint8_t valid_channels();
|
2012-12-03 21:47:18 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
* read(uint8_t):
|
|
|
|
* Read a single channel at a time
|
|
|
|
*/
|
2012-08-27 20:45:27 -03:00
|
|
|
uint16_t read(uint8_t ch);
|
2012-12-03 21:47:18 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
* read(uint16_t*,uint8_t):
|
|
|
|
* Read an array of channels, return the valid count
|
|
|
|
*/
|
2012-08-27 20:45:27 -03:00
|
|
|
uint8_t read(uint16_t* periods, uint8_t len);
|
2012-12-03 21:47:18 -04:00
|
|
|
|
2012-12-06 16:45:56 -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_overrides: array starts at ch 0, for len channels */
|
|
|
|
bool set_overrides(int16_t *overrides, uint8_t len);
|
|
|
|
/* set_override: set just a specific channel */
|
|
|
|
bool set_override(uint8_t channel, int16_t override);
|
|
|
|
/* clear_overrides: equivelant to setting all overrides to 0 */
|
|
|
|
void clear_overrides();
|
|
|
|
|
2012-08-27 15:44:50 -03:00
|
|
|
private:
|
2012-08-27 20:45:27 -03:00
|
|
|
/* private callback for input capture ISR */
|
|
|
|
static void _timer4_capt_cb(void);
|
|
|
|
/* private variables to communicate with input capture isr */
|
|
|
|
static volatile uint16_t _pulse_capt[AVR_RC_INPUT_NUM_CHANNELS];
|
2013-04-29 03:05:53 -03:00
|
|
|
static volatile uint8_t _valid_channels;
|
2012-12-06 16:45:56 -04:00
|
|
|
|
|
|
|
/* override state */
|
|
|
|
uint16_t _override[AVR_RC_INPUT_NUM_CHANNELS];
|
2012-08-27 15:44:50 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
class AP_HAL_AVR::APM2RCInput : public AP_HAL::RCInput {
|
2012-08-27 20:45:27 -03:00
|
|
|
/* Pass in a AP_HAL_AVR::ISRRegistry* as void*. */
|
|
|
|
void init(void* isrregistry);
|
2013-04-29 03:05:53 -03:00
|
|
|
uint8_t valid_channels();
|
2012-08-27 20:45:27 -03:00
|
|
|
uint16_t read(uint8_t ch);
|
|
|
|
uint8_t read(uint16_t* periods, uint8_t len);
|
2012-12-06 16:45:56 -04:00
|
|
|
bool set_overrides(int16_t *overrides, uint8_t len);
|
|
|
|
bool set_override(uint8_t channel, int16_t override);
|
|
|
|
void clear_overrides();
|
2012-08-27 15:44:50 -03:00
|
|
|
private:
|
2012-08-27 20:45:27 -03:00
|
|
|
/* private callback for input capture ISR */
|
|
|
|
static void _timer5_capt_cb(void);
|
|
|
|
/* private variables to communicate with input capture isr */
|
|
|
|
static volatile uint16_t _pulse_capt[AVR_RC_INPUT_NUM_CHANNELS];
|
2013-04-29 03:05:53 -03:00
|
|
|
static volatile uint8_t _valid_channels;
|
2012-12-06 16:45:56 -04:00
|
|
|
|
|
|
|
/* override state */
|
|
|
|
uint16_t _override[AVR_RC_INPUT_NUM_CHANNELS];
|
2012-08-27 15:44:50 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_AVR_RC_INPUT_H__
|
|
|
|
|