11 #pragma GCC optimize ("O2") 15 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && defined(BOARD_SOFTSERIAL_RX) && defined(BOARD_SOFTSERIAL_TX) 32 void SerialDriver::begin(uint32_t baud) {
53 transmitBufferRead = transmitBufferWrite = 0;
58 receiveBufferRead = receiveBufferWrite = 0;
73 void SerialDriver::rxSetCapture(){
78 void SerialDriver::rxSetCompare(){
90 void SerialDriver::flush() {
91 receiveBufferRead = receiveBufferWrite = 0;
95 bool SerialDriver::tx_pending() {
96 if(!_initialized)
return 0;
98 return (transmitBufferWrite + SS_MAX_TX_BUFF - transmitBufferRead) % SS_MAX_TX_BUFF;
102 uint32_t SerialDriver::available() {
104 return (receiveBufferWrite + SS_MAX_RX_BUFF - receiveBufferRead) % SS_MAX_RX_BUFF;
107 uint32_t SerialDriver::txspace() {
108 return SS_MAX_TX_BUFF - tx_pending();
116 if(receiveBufferRead == receiveBufferWrite)
return -1;
118 uint8_t inData = receiveBuffer[receiveBufferRead];
120 receiveBufferRead = (receiveBufferRead + 1) % SS_MAX_RX_BUFF;
126 if (!_initialized)
return 0;
131 if( ((transmitBufferWrite + 1) % SS_MAX_TX_BUFF) == transmitBufferRead ){
133 if(! _blocking) n_try--;
138 transmitBuffer[transmitBufferWrite] = c;
140 transmitBufferWrite = (transmitBufferWrite == SS_MAX_TX_BUFF) ? 0 : transmitBufferWrite + 1;
151 txEnableInterrupts();
161 n +=
write(*buffer++);
167 #define bitRead(value, bit) (((value) >> (bit)) & 0x01) 170 void SerialDriver::txNextBit(
void ) {
178 if (txBitCount <= 7) {
179 if (bitRead(transmitBuffer[transmitBufferRead], txBitCount) == (_inverse?0:1)) {
188 #if DEBUG_DELAY && defined(DEBUG_PIN1) 195 }
else if (txBitCount == 8) {
200 transmitBufferRead = (transmitBufferRead == SS_MAX_TX_BUFF ) ? 0 : transmitBufferRead + 1;
202 if (transmitBufferRead != transmitBufferWrite) {
206 txDisableInterrupts();
211 }
else if (txBitCount >= 10) {
221 void SerialDriver::rxNextBit(
void ) {
226 if (rxBitCount == 9) {
244 uint8_t d =
gpio_read_bit( rx_pp.gpio_device, rx_pp.gpio_bit);
246 if (rxBitCount == 9) {
253 }
else if (rxBitCount < 8) {
269 }
else if (rxBitCount == 8) {
274 receiveBuffer[receiveBufferWrite] = receiveByte;
277 uint8_t next = (receiveBufferWrite + 1) % SS_MAX_RX_BUFF;
281 if (next != receiveBufferRead) {
282 receiveBufferWrite = next;
286 bufferOverflow =
true;
289 #if DEBUG_DELAY && defined(DEBUG_PIN1) 290 overFlowTail = receiveBufferWrite;
291 overFlowHead = receiveBufferRead;
static Handler get_handler(AP_HAL::MemberProc proc)
void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode)
static void timer_cc_set_pol(const timer_dev *dev, timer_Channel channel, timer_cc_polarity pol)
Set a timer channel's capture/compare output polarity.
static uint8_t buffer[SRXL_FRAMELEN_MAX]
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
static void _write(uint8_t pin, uint8_t value)
static INLINE uint16_t timer_get_capture(const timer_dev *dev, timer_Channel channel)
static INLINE void timer_pause(const timer_dev *dev)
Stop a timer's counter from changing.
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void timer_attach_interrupt(const timer_dev *dev, timer_interrupt_id interrupt, Handler handler, uint8_t priority)
Attach a timer interrupt.
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
static INLINE void timer_resume(const timer_dev *dev)
Start a timer's counter.
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
#define SOFT_UART_INT_PRIORITY
static void yield(uint16_t ttw=0)
static void timer_set_compare(const timer_dev *dev, timer_Channel channel, uint16_t value)
Set the compare value for the given timer channel.
static void timer_ic_set_mode(const timer_dev *dev, timer_Channel _channel, uint8_t mode, uint16_t filter)
Configure a channel's input capture mode.
static INLINE uint8_t gpio_read_bit(const gpio_dev *const dev, uint8_t pin)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
static INLINE void timer_set_reload(const timer_dev *dev, uint32_t arr)
Set a timer's reload value.
#define CYCLES_PER_MICROSECOND
static void timer_set_prescaler(const timer_dev *dev, uint16_t psc)
Set a timer's prescale value.
static void timer_generate_update(const timer_dev *dev)
Generate an update event for the given timer.
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)