APM:Libraries
USBDriver.cpp
Go to the documentation of this file.
1 /*
2  (c) 2017 night_ghost@ykoctpa.ru
3 
4 
5  * USBDriver.cpp --- AP_HAL_F4Light USB-UART driver.
6  *
7  */
8 
9 #include <AP_HAL/AP_HAL.h>
10 
11 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
12 #include "USBDriver.h"
13 
14 #include <stdio.h>
15 #include <unistd.h>
16 #include <stdlib.h>
17 #include <errno.h>
18 #include <fcntl.h>
19 #include <usb.h>
20 #include <gpio_hal.h>
21 #include "Scheduler.h"
22 
23 using namespace F4Light;
24 
25 extern const AP_HAL::HAL& hal;
26 
27 
28 // usb *can* be used in air, eg. to connect companion computer
29 
30 
31 
33  _initialized(false),
34  _blocking(false)
35 {
36 }
37 
38 void USBDriver::begin(uint32_t baud) {
39 
40 /* _usb_present = gpio_read_bit(PIN_MAP[BOARD_USB_SENSE].gpio_device,PIN_MAP[BOARD_USB_SENSE].gpio_bit);
41  using of this bit prevents USB hotplug
42 */
43 
44  _initialized = true; // real USB initialization was much earlier
45 }
46 
47 
48 uint32_t USBDriver::available() {
49  uint32_t v = usb_data_available();
50  return v;
51 }
52 
53 uint32_t USBDriver::txspace() { return usb_tx_space(); }
54 
55 
56 int16_t USBDriver::read() {
57  if(is_usb_opened() ){
58  if (available() == 0)
59  return -1;
60  return usb_getc();
61  }
62  return 0;
63 }
64 
65 size_t USBDriver::write(uint8_t c) {
66  return write(&c,1);
67 }
68 
69 
70 size_t USBDriver::write(const uint8_t *buffer, size_t size)
71 {
72  size_t n = 0;
73  uint32_t t = Scheduler::_micros();
74 
75  if(is_usb_opened()){
76  while(true) {
77  uint8_t k=usb_write((uint8_t *)buffer, size);
78  size-=k;
79  n+=k;
80  buffer+=k;
81  if(size == 0) break; //done
82 
83  uint32_t now = Scheduler::_micros();
84  if(k==0) {
85  if(!_blocking && now - t > 5000 ){ // the waiting time exceeded 5ms - something went wrong ...
87  return n;
88  }
89  if(!is_usb_opened()) break;
90  hal_yield(0);
91  } else {
92  t = now;
93  }
94  }
95  return n;
96  }
97  return size;
98 }
99 
100 #endif // CONFIG_HAL_BOARD
uint16_t usb_tx_space(void)
Definition: usb.c:784
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
static uint8_t usb_getc(void)
Definition: usb.h:127
int16_t read() override
Definition: USBDriver.cpp:56
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
uint32_t txspace() override
Definition: USBDriver.cpp:53
USBDriver(bool usb)
Definition: USBDriver.cpp:32
void begin(uint32_t b)
Definition: USBDriver.cpp:38
float v
Definition: Printf.cpp:15
uint32_t usb_data_available(void)
Definition: usb.c:764
static uint32_t _micros()
Definition: Scheduler.h:232
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint8_t is_usb_opened()
Definition: usb.c:794
void reset_usb_opened()
Definition: usb.c:795
uint32_t available() override
Definition: USBDriver.cpp:48
size_t write(uint8_t c)
Definition: USBDriver.cpp:65
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
int usb_write(const uint8_t *buf, unsigned int nbytes)
Definition: usb.c:756