APM:Libraries
UART_PPM.cpp
Go to the documentation of this file.
1 /*
2  (c) 2017 night_ghost@ykoctpa.ru
3 
4 
5  * UART_PPM.cpp --- fake UART to get serial data from PPM inputs
6  *
7  */
8 
9 #include <AP_HAL/AP_HAL.h>
10 
11 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
12 
13 #include "UART_PPM.h"
14 
15 
16 #include <stdio.h>
17 #include <unistd.h>
18 #include <stdlib.h>
19 #include <errno.h>
20 #include <fcntl.h>
21 
22 
23 
24 using namespace F4Light;
25 
26 ring_buffer UART_PPM::ppm_rxrb[2] IN_CCM;
28 
29 UART_PPM::UART_PPM(uint8_t n):
30  _initialized(false),
31  _blocking(true),
32  _id(n)
33 {
34  rb_init(&ppm_rxrb[n], USART_PPM_BUF_SIZE, rx_buf[n]);
35 }
36 
37 void UART_PPM::begin(uint32_t baud) {
38  if(_initialized) return;
39 
40  // signal that uart connected
41  _initialized = true;
42 }
43 
44 uint32_t UART_PPM::available() {
45  return rb_full_count(&ppm_rxrb[_id]);
46 }
47 
48 int16_t UART_PPM::read() {
49  if (available() <= 0) return -1;
50  return rb_remove(&ppm_rxrb[_id]);
51 }
52 
53 void UART_PPM::putch(uint8_t c, uint8_t n){
54  /* If the buffer is full ignore new bytes. */
55  rb_safe_insert(&ppm_rxrb[n], c);
56 }
57 
58 #endif // CONFIG_HAL_BOARD
uint32_t available() override
Definition: UART_PPM.cpp:44
void begin(uint32_t b)
Definition: UART_PPM.cpp:37
static uint16_t rb_full_count(ring_buffer *rb)
Return the number of elements stored in the ring buffer.
Definition: ring_buffer.h:84
static uint8_t rb_remove(ring_buffer *rb)
Remove and return the first item from a ring buffer.
Definition: ring_buffer.h:128
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
int16_t read() override
Definition: UART_PPM.cpp:48
static void putch(uint8_t c, uint8_t n)
Definition: UART_PPM.cpp:53
static uint8_t rx_buf[USB_RXFIFO_SIZE]
Definition: usb.c:60
static void rb_init(ring_buffer *rb, uint16_t size, uint8_t *buf)
Definition: ring_buffer.h:73
#define USART_PPM_BUF_SIZE
Definition: UART_PPM.h:13
UART_PPM(uint8_t n)
Definition: UART_PPM.cpp:29
static int rb_safe_insert(ring_buffer *rb, uint8_t element)
Attempt to insert an element into a ring buffer.
Definition: ring_buffer.h:154
ring_buffer UART_PPM::ppm_rxrb [2] IN_CCM
Definition: UART_PPM.cpp:26