2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2014-11-13 23:10:35 -04:00
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-11-13 23:10:35 -04:00
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
namespace Linux {
|
|
|
|
|
2016-07-29 20:26:07 -03:00
|
|
|
#define MAX_ZYNQ_PWMS 8 /* number of pwm channels */
|
2016-07-29 16:14:02 -03:00
|
|
|
|
|
|
|
class RCOutput_ZYNQ : public AP_HAL::RCOutput {
|
|
|
|
public:
|
2019-02-21 19:08:12 -04:00
|
|
|
void init() override;
|
|
|
|
void set_freq(uint32_t chmask, uint16_t freq_hz) override;
|
|
|
|
uint16_t get_freq(uint8_t ch) override;
|
|
|
|
void enable_ch(uint8_t ch) override;
|
|
|
|
void disable_ch(uint8_t ch) override;
|
|
|
|
void write(uint8_t ch, uint16_t period_us) override;
|
|
|
|
uint16_t read(uint8_t ch) override;
|
|
|
|
void read(uint16_t* period_us, uint8_t len) override;
|
2016-10-11 21:19:16 -03:00
|
|
|
void cork(void) override;
|
|
|
|
void push(void) override;
|
2014-11-13 23:10:35 -04:00
|
|
|
|
|
|
|
private:
|
2017-08-17 19:41:58 -03:00
|
|
|
#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;
|
2017-08-17 19:41:58 -03:00
|
|
|
#endif
|
2014-11-13 23:10:35 -04:00
|
|
|
|
|
|
|
// Period|Hi 32 bits each
|
|
|
|
struct s_period_hi {
|
|
|
|
uint32_t period;
|
|
|
|
uint32_t hi;
|
|
|
|
};
|
|
|
|
struct pwm_cmd {
|
2015-04-06 15:25:15 -03:00
|
|
|
struct s_period_hi periodhi[MAX_ZYNQ_PWMS];
|
2014-11-13 23:10:35 -04:00
|
|
|
};
|
|
|
|
volatile struct pwm_cmd *sharedMem_cmd;
|
2016-10-11 21:19:16 -03:00
|
|
|
|
|
|
|
uint16_t pending[MAX_ZYNQ_PWMS];
|
|
|
|
bool corked;
|
|
|
|
uint32_t pending_mask;
|
2014-11-13 23:10:35 -04:00
|
|
|
};
|
2016-07-29 16:14:02 -03:00
|
|
|
|
|
|
|
}
|