ardupilot/libraries/AP_HAL_PX4/RCOutput.h

31 lines
821 B
C++

#ifndef __AP_HAL_PX4_RCOUTPUT_H__
#define __AP_HAL_PX4_RCOUTPUT_H__
#include <AP_HAL_PX4.h>
#define PX4_NUM_OUTPUT_CHANNELS 16
class PX4::PX4RCOutput : public AP_HAL::RCOutput
{
public:
void init(void* machtnichts);
void set_freq(uint32_t chmask, uint16_t freq_hz);
uint16_t get_freq(uint8_t ch);
void enable_ch(uint8_t ch);
void enable_mask(uint32_t chmask);
void disable_ch(uint8_t ch);
void disable_mask(uint32_t chmask);
void write(uint8_t ch, uint16_t period_us);
void write(uint8_t ch, uint16_t* period_us, uint8_t len);
uint16_t read(uint8_t ch);
void read(uint16_t* period_us, uint8_t len);
private:
int _pwm_fd;
uint16_t _freq_hz;
uint16_t _period[PX4_NUM_OUTPUT_CHANNELS];
};
#endif // __AP_HAL_PX4_RCOUTPUT_H__