2013-01-03 06:30:35 -04:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_PX4_RCINPUT_H__
|
|
|
|
#define __AP_HAL_PX4_RCINPUT_H__
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_PX4.h"
|
2013-01-26 21:51:34 -04:00
|
|
|
#include <drivers/drv_rc_input.h>
|
|
|
|
#include <systemlib/perf_counter.h>
|
2013-12-31 07:24:55 -04:00
|
|
|
#include <pthread.h>
|
2013-01-03 06:30:35 -04:00
|
|
|
|
2015-11-25 19:10:32 -04:00
|
|
|
|
|
|
|
#ifndef RC_INPUT_MAX_CHANNELS
|
|
|
|
#define RC_INPUT_MAX_CHANNELS 18
|
|
|
|
#endif
|
|
|
|
|
2013-01-03 06:30:35 -04:00
|
|
|
class PX4::PX4RCInput : public AP_HAL::RCInput {
|
|
|
|
public:
|
2015-12-02 11:14:20 -04:00
|
|
|
void init();
|
2014-03-25 00:39:41 -03:00
|
|
|
bool new_input();
|
|
|
|
uint8_t num_channels();
|
2013-01-03 06:30:35 -04:00
|
|
|
uint16_t read(uint8_t ch);
|
|
|
|
uint8_t read(uint16_t* periods, uint8_t len);
|
|
|
|
|
|
|
|
bool set_overrides(int16_t *overrides, uint8_t len);
|
|
|
|
bool set_override(uint8_t channel, int16_t override);
|
|
|
|
void clear_overrides();
|
|
|
|
|
2013-01-26 21:51:34 -04:00
|
|
|
void _timer_tick(void);
|
|
|
|
|
2015-06-10 03:45:26 -03:00
|
|
|
bool rc_bind(int dsmMode);
|
|
|
|
|
2013-01-03 06:30:35 -04:00
|
|
|
private:
|
|
|
|
/* override state */
|
2013-01-26 21:51:34 -04:00
|
|
|
uint16_t _override[RC_INPUT_MAX_CHANNELS];
|
|
|
|
struct rc_input_values _rcin;
|
|
|
|
int _rc_sub;
|
2013-01-03 17:31:23 -04:00
|
|
|
uint64_t _last_read;
|
2013-01-22 16:57:59 -04:00
|
|
|
bool _override_valid;
|
2013-01-26 21:51:34 -04:00
|
|
|
perf_counter_t _perf_rcin;
|
2013-12-31 07:24:55 -04:00
|
|
|
pthread_mutex_t rcin_mutex;
|
2013-01-03 06:30:35 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_PX4_RCINPUT_H__
|