ardupilot/libraries/AP_HAL_Linux/RCInput_ZYNQ.h

34 lines
713 B
C
Raw Normal View History

#pragma once
2014-11-13 23:10:35 -04:00
/*
This class implements RCInput on the ZYNQ / ZyboPilot platform with custom
logic doing the edge detection of the PPM sum input
*/
#include "RCInput.h"
2014-11-13 23:10:35 -04:00
namespace Linux {
class RCInput_ZYNQ : public RCInput {
2014-11-13 23:10:35 -04:00
public:
void init() override;
void _timer_tick(void) override;
2014-11-13 23:10:35 -04:00
private:
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ
static const int TICK_PER_US=50;
static const int TICK_PER_S=50000000;
#else
2014-11-13 23:10:35 -04:00
static const int TICK_PER_US=100;
static const int TICK_PER_S=100000000;
#endif
2014-11-13 23:10:35 -04:00
// Memory mapped keyhole register to pulse input FIFO
volatile uint32_t *pulse_input;
// time spent in the low state
uint32_t _s0_time;
};
}