mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
dff6a5bff9
this is needed for linux boards with no native RCOutput that use SBUS out on a serial port to ensure they can display the servo values in the GCS
19 lines
594 B
C++
19 lines
594 B
C++
#pragma once
|
|
|
|
#include "AP_HAL_Empty.h"
|
|
|
|
class Empty::RCOutput : public AP_HAL::RCOutput {
|
|
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;
|
|
void cork(void) override {}
|
|
void push(void) override {}
|
|
private:
|
|
uint16_t value[16];
|
|
};
|