APM:Libraries
USBDriver.h
Go to the documentation of this file.
1 
2 #pragma once
3 
5 
6 #include <gpio_hal.h>
7 //#include <usb.h> can't include here because defines there conflicts with AP_Math
8 #include <usart.h>
9 
10 #define DEFAULT_TX_TIMEOUT 10000
11 
12 extern "C" {
13  extern int usb_open(void);
14  extern int usb_close(void);
15  uint32_t usb_data_available(void);
16  void usb_reset_rx();
17 }
18 
19 namespace F4Light {
20 
21 class USBDriver : public AP_HAL::UARTDriver {
22 public:
23  USBDriver(bool usb);
24 
25  void begin(uint32_t b);
26  void begin(uint32_t b, uint16_t rxS, uint16_t txS) { begin(b); }
27 
28  inline void end() { usb_close(); }
29  inline bool is_initialized(){ return _initialized; }
30  inline void set_blocking_writes(bool blocking) { _blocking=blocking; }
31  inline bool tx_pending() { return false; } // not used
32 
33  void flush() { return; };
34 
35  uint32_t available() override;
36  uint32_t txspace() override;
37  int16_t read() override;
38 
39  size_t write(uint8_t c);
40  size_t write(const uint8_t *buffer, size_t size);
41 
42 private:
44  bool _blocking;
45 };
46 
47 } // namespace
48 
49 
uint32_t usb_data_available(void)
Definition: usb.c:764
int usb_open(void)
Definition: usb.c:674
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void usb_reset_rx()
Definition: usb.c:772
void set_blocking_writes(bool blocking)
Definition: USBDriver.h:30
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
bool is_initialized()
Definition: USBDriver.h:29
void begin(uint32_t b, uint16_t rxS, uint16_t txS)
Definition: USBDriver.h:26
int usb_close(void)
Definition: usb.c:688
uint32_t available() override
Definition: USBDriver.cpp:48
size_t write(uint8_t c)
Definition: USBDriver.cpp:65