Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
usb_ser_hw.c File Reference
#include <stdlib.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/cdc.h>
#include <libopencm3/cm3/scb.h>
#include <libopencm3/stm32/desig.h>
#include <libopencm3/stm32/otg_fs.h>
#include "mcu_periph/usb_serial.h"
#include "mcu_periph/sys_time_arch.h"
+ Include dependency graph for usb_ser_hw.c:

Go to the source code of this file.

Data Structures

struct  fifo_t
 

Macros

#define MAX_PACKET_SIZE   64
 
#define VCOM_FIFO_SIZE   256
 
#define TX_TIMEOUT_CNT   20
 

Functions

void fifo_init (fifo_t *fifo, uint8_t *buf)
 
bool fifo_put (fifo_t *fifo, uint8_t c)
 
bool fifo_get (fifo_t *fifo, uint8_t *pc)
 
bool fifo_peek (fifo_t *fifo, uint8_t *pc, uint8_t ofs)
 
int fifo_avail (fifo_t *fifo)
 
int fifo_free (fifo_t *fifo)
 
static int cdcacm_control_request (usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, void(**complete)(usbd_device *usbd_dev, struct usb_setup_data *req))
 CDC device control request (from libopencm3 examples) More...
 
static void cdcacm_data_rx_cb (usbd_device *usbd_dev, uint8_t ep)
 RX callback for CDC device (from libopencm3 examples) More...
 
static void suspend_cb (void)
 
static void cdcacm_set_config (usbd_device *usbd_dev, uint16_t wValue)
 Set configuration and control callbacks for CDC device (from libopencm3 examples) More...
 
int VCOM_putchar (int c)
 Writes one character to VCOM port fifo. More...
 
int VCOM_getchar (void)
 Reads one character from VCOM port. More...
 
int VCOM_peekchar (int ofs)
 Reads one character from VCOM port without removing it from the queue. More...
 
bool VCOM_check_free_space (uint16_t len)
 Checks if buffer free in VCOM buffer. More...
 
int VCOM_check_available (void)
 Checks if data available in VCOM buffer. More...
 
void VCOM_event (void)
 Poll usb (required by libopencm3). More...
 
void VCOM_send_message (void)
 Send data from fifo right now. More...
 
static int usb_serial_check_free_space (struct usb_serial_periph *p, long *fd, uint16_t len)
 
static void usb_serial_transmit (struct usb_serial_periph *p, long fd, uint8_t byte)
 
static void usb_serial_transmit_buffer (struct usb_serial_periph *p, long fd, uint8_t *data, uint16_t len)
 
static void usb_serial_send (struct usb_serial_periph *p, long fd)
 
static int usb_serial_char_available (struct usb_serial_periph *p)
 
static uint8_t usb_serial_getch (struct usb_serial_periph *p)
 
void VCOM_init (void)
 

Variables

static uint8_t txdata [VCOM_FIFO_SIZE]
 
static uint8_t rxdata [VCOM_FIFO_SIZE]
 
static fifo_t txfifo
 
static fifo_t rxfifo
 
int tx_timeout
 
usbd_device * my_usbd_dev
 
static const struct usb_device_descriptor dev
 
static const struct usb_endpoint_descriptor comm_endp []
 
static const struct usb_endpoint_descriptor data_endp []
 
struct {
struct usb_cdc_header_descriptor header
 
struct usb_cdc_call_management_descriptor call_mgmt
 
struct usb_cdc_acm_descriptor acm
 
struct usb_cdc_union_descriptor cdc_union
 
cdcacm_functional_descriptors
 
static const struct usb_interface_descriptor comm_iface []
 
static const struct usb_interface_descriptor data_iface []
 
static const struct usb_interface ifaces []
 
static const struct usb_config_descriptor config
 
static char serial_no [25]
 
static const char * usb_strings []
 
uint8_t usbd_control_buffer [128]
 
static bool usb_connected
 
struct usb_serial_periph usb_serial
 

Detailed Description

CDC USB device driver for STM32 architecture (STM32F1, STM32F4)

Definition in file usb_ser_hw.c.


Data Structure Documentation

◆ fifo_t

struct fifo_t

Definition at line 90 of file usb_ser_hw.c.

Data Fields
uint8_t * buf
int head
size_t size
int tail

Macro Definition Documentation

◆ MAX_PACKET_SIZE

#define MAX_PACKET_SIZE   64

Definition at line 46 of file usb_ser_hw.c.

◆ TX_TIMEOUT_CNT

#define TX_TIMEOUT_CNT   20

Definition at line 50 of file usb_ser_hw.c.

◆ VCOM_FIFO_SIZE

#define VCOM_FIFO_SIZE   256

Definition at line 48 of file usb_ser_hw.c.

Function Documentation

◆ cdcacm_control_request()

static int cdcacm_control_request ( usbd_device *  usbd_dev,
struct usb_setup_data *  req,
uint8_t **  buf,
uint16_t len,
void(**)(usbd_device *usbd_dev, struct usb_setup_data *req)  complete 
)
static

CDC device control request (from libopencm3 examples)

Definition at line 233 of file usb_ser_hw.c.

Referenced by cdcacm_set_config().

+ Here is the caller graph for this function:

◆ cdcacm_data_rx_cb()

static void cdcacm_data_rx_cb ( usbd_device *  usbd_dev,
uint8_t  ep 
)
static

RX callback for CDC device (from libopencm3 examples)

Definition at line 276 of file usb_ser_hw.c.

References fifo_put(), MAX_PACKET_SIZE, and rxfifo.

Referenced by cdcacm_set_config().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ cdcacm_set_config()

static void cdcacm_set_config ( usbd_device *  usbd_dev,
uint16_t  wValue 
)
static

Set configuration and control callbacks for CDC device (from libopencm3 examples)

Definition at line 303 of file usb_ser_hw.c.

References cdcacm_control_request(), cdcacm_data_rx_cb(), MAX_PACKET_SIZE, suspend_cb(), and usb_connected.

Referenced by VCOM_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ fifo_avail()

int fifo_avail ( fifo_t fifo)

Definition at line 367 of file usb_ser_hw.c.

References fifo_t::head, fifo_t::tail, and VCOM_FIFO_SIZE.

◆ fifo_free()

int fifo_free ( fifo_t fifo)

Definition at line 373 of file usb_ser_hw.c.

References fifo_avail(), and VCOM_FIFO_SIZE.

+ Here is the call graph for this function:

◆ fifo_get()

static bool fifo_get ( fifo_t fifo,
uint8_t pc 
)

Definition at line 349 of file usb_ser_hw.c.

References fifo_t::buf, fifo_t::head, fifo_t::tail, and VCOM_FIFO_SIZE.

◆ fifo_init()

void fifo_init ( fifo_t fifo,
uint8_t buf 
)

Definition at line 322 of file usb_ser_hw.c.

References fifo_t::buf, fifo_t::head, and fifo_t::tail.

◆ fifo_peek()

bool fifo_peek ( fifo_t fifo,
uint8_t pc,
uint8_t  ofs 
)

Definition at line 378 of file usb_ser_hw.c.

References fifo_t::buf, fifo_avail(), fifo_t::tail, and VCOM_FIFO_SIZE.

Referenced by VCOM_peekchar().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ fifo_put()

static bool fifo_put ( fifo_t fifo,
uint8_t  c 
)

Definition at line 331 of file usb_ser_hw.c.

References fifo_t::buf, c(), fifo_t::head, fifo_t::tail, and VCOM_FIFO_SIZE.

+ Here is the call graph for this function:

◆ suspend_cb()

static void suspend_cb ( void  )
static

Definition at line 294 of file usb_ser_hw.c.

References usb_connected.

Referenced by cdcacm_set_config().

+ Here is the caller graph for this function:

◆ usb_serial_char_available()

static int usb_serial_char_available ( struct usb_serial_periph p)
static

Definition at line 555 of file usb_ser_hw.c.

References VCOM_check_available().

Referenced by VCOM_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ usb_serial_check_free_space()

static int usb_serial_check_free_space ( struct usb_serial_periph p,
long *  fd,
uint16_t  len 
)
static

Definition at line 526 of file usb_ser_hw.c.

References VCOM_check_free_space().

Referenced by VCOM_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ usb_serial_getch()

static uint8_t usb_serial_getch ( struct usb_serial_periph p)
static

Definition at line 560 of file usb_ser_hw.c.

References VCOM_getchar().

Referenced by VCOM_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ usb_serial_send()

static void usb_serial_send ( struct usb_serial_periph p,
long  fd 
)
static

Definition at line 550 of file usb_ser_hw.c.

References VCOM_send_message().

Referenced by VCOM_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ usb_serial_transmit()

static void usb_serial_transmit ( struct usb_serial_periph p,
long  fd,
uint8_t  byte 
)
static

Definition at line 533 of file usb_ser_hw.c.

References VCOM_putchar().

Referenced by VCOM_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ usb_serial_transmit_buffer()

static void usb_serial_transmit_buffer ( struct usb_serial_periph p,
long  fd,
uint8_t data,
uint16_t  len 
)
static

Definition at line 540 of file usb_ser_hw.c.

References VCOM_putchar().

Referenced by VCOM_init().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ VCOM_check_available()

int VCOM_check_available ( void  )

Checks if data available in VCOM buffer.

Returns
nonzero if char is available in the queue, zero otherwise

Definition at line 459 of file usb_ser_hw.c.

References fifo_avail(), and rxfifo.

+ Here is the call graph for this function:

◆ VCOM_check_free_space()

bool VCOM_check_free_space ( uint16_t  len)

Checks if buffer free in VCOM buffer.

Returns
TRUE if len bytes are free

Definition at line 450 of file usb_ser_hw.c.

References FALSE, fifo_free(), TRUE, and txfifo.

+ Here is the call graph for this function:

◆ VCOM_event()

void VCOM_event ( void  )

Poll usb (required by libopencm3).

VCOM_event() should be called from main/module event function

Definition at line 468 of file usb_ser_hw.c.

References fifo_avail(), my_usbd_dev, tx_timeout, txfifo, and VCOM_send_message().

+ Here is the call graph for this function:

◆ VCOM_getchar()

int VCOM_getchar ( void  )

Reads one character from VCOM port.

Returns
character read, or -1 if character could not be read

Definition at line 425 of file usb_ser_hw.c.

References BULK_OUT_EP, BulkOut(), BulkOut_is_blocked, c(), disableIRQ(), enableIRQ(), EOF, fifo_free(), fifo_get(), MAX_PACKET_SIZE, and rxfifo.

+ Here is the call graph for this function:

◆ VCOM_init()

◆ VCOM_peekchar()

int VCOM_peekchar ( int  ofs)

Reads one character from VCOM port without removing it from the queue.

Parameters
ofsposition to read
Returns
character read, or -1 if character could not be read

Definition at line 438 of file usb_ser_hw.c.

References c(), fifo_peek(), and rxfifo.

Referenced by dfu_command_event().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ VCOM_putchar()

int VCOM_putchar ( int  c)

Writes one character to VCOM port fifo.

Writes one character to VCOM port.

Since we don't really have an instant feeedback from USB driver if the character was written, we always return c if we are connected.

Parameters
[in]ccharacter to write
Returns
character to be written, -1 if not usb is not connected

Definition at line 397 of file usb_ser_hw.c.

References c(), EOF, fifo_put(), sys_time_usleep(), tx_timeout, TX_TIMEOUT_CNT, txfifo, usb_connected, VCOM_check_free_space(), and VCOM_send_message().

+ Here is the call graph for this function:

◆ VCOM_send_message()

void VCOM_send_message ( void  )

Send data from fifo right now.

Only if usb is connected.

Definition at line 487 of file usb_ser_hw.c.

References fifo_get(), MAX_PACKET_SIZE, my_usbd_dev, txfifo, and usb_connected.

+ Here is the call graph for this function:

Variable Documentation

◆ cdcacm_functional_descriptors

const { ... } cdcacm_functional_descriptors
Initial value:
= {
.header = {
.bFunctionLength = sizeof(struct usb_cdc_header_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_HEADER,
.bcdCDC = 0x0110,
},
.call_mgmt = {
.bFunctionLength =
sizeof(struct usb_cdc_call_management_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT,
.bmCapabilities = 0,
.bDataInterface = 1,
},
.acm = {
.bFunctionLength = sizeof(struct usb_cdc_acm_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_ACM,
.bmCapabilities = 0,
},
.cdc_union = {
.bFunctionLength = sizeof(struct usb_cdc_union_descriptor),
.bDescriptorType = CS_INTERFACE,
.bDescriptorSubtype = USB_CDC_TYPE_UNION,
.bControlInterface = 0,
.bSubordinateInterface0 = 1,
}
}

◆ comm_endp

const struct usb_endpoint_descriptor comm_endp[]
static
Initial value:
= {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x83,
.bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
.wMaxPacketSize = 16,
.bInterval = 255,
}
}

Definition at line 96 of file usb_ser_hw.c.

◆ comm_iface

const struct usb_interface_descriptor comm_iface[]
static
Initial value:
= {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 0,
.bAlternateSetting = 0,
.bNumEndpoints = 1,
.bInterfaceClass = USB_CLASS_CDC,
.bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
.bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
.iInterface = 0,
.endpoint = comm_endp,
.extralen = sizeof(cdcacm_functional_descriptors)
}
}

Definition at line 158 of file usb_ser_hw.c.

◆ config

const struct usb_config_descriptor config
static
Initial value:
= {
.bLength = USB_DT_CONFIGURATION_SIZE,
.bDescriptorType = USB_DT_CONFIGURATION,
.wTotalLength = 0,
.bNumInterfaces = 2,
.bConfigurationValue = 1,
.iConfiguration = 0,
.bmAttributes = 0x80,
.bMaxPower = 0x32,
.interface = ifaces,
}

Definition at line 200 of file usb_ser_hw.c.

Referenced by bmi088_send_config(), dshotStart(), gpio_init(), mpu60x0_send_config(), mpu9250_send_config(), msdStart(), and VCOM_init().

◆ data_endp

const struct usb_endpoint_descriptor data_endp[]
static
Initial value:
= {{
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x01,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = MAX_PACKET_SIZE,
.bInterval = 1,
}, {
.bLength = USB_DT_ENDPOINT_SIZE,
.bDescriptorType = USB_DT_ENDPOINT,
.bEndpointAddress = 0x82,
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
.wMaxPacketSize = MAX_PACKET_SIZE,
.bInterval = 1,
}
}

Definition at line 106 of file usb_ser_hw.c.

◆ data_iface

const struct usb_interface_descriptor data_iface[]
static
Initial value:
= {{
.bLength = USB_DT_INTERFACE_SIZE,
.bDescriptorType = USB_DT_INTERFACE,
.bInterfaceNumber = 1,
.bAlternateSetting = 0,
.bNumEndpoints = 2,
.bInterfaceClass = USB_CLASS_DATA,
.bInterfaceSubClass = 0,
.bInterfaceProtocol = 0,
.iInterface = 0,
.endpoint = data_endp,
}
}

Definition at line 176 of file usb_ser_hw.c.

◆ dev

const struct usb_device_descriptor dev
static
Initial value:
= {
.bLength = USB_DT_DEVICE_SIZE,
.bDescriptorType = USB_DT_DEVICE,
.bcdUSB = 0x0200,
.bDeviceClass = USB_CLASS_CDC,
.bDeviceSubClass = 0,
.bDeviceProtocol = 0,
.bMaxPacketSize0 = MAX_PACKET_SIZE,
.idVendor = 0x1d50,
.idProduct = 0x603d,
.bcdDevice = 0x0200,
.iManufacturer = 1,
.iProduct = 2,
.iSerialNumber = 3,
.bNumConfigurations = 1,
}

Definition at line 74 of file usb_ser_hw.c.

Referenced by actuators_sbus_send(), actuators_spektrum_send(), adc_msg_send(), configure_isp(), dl_parse_msg(), DlCheckAndParse(), DownlinkSendWp(), esc32_msg_send(), firmware_parse_msg(), gps_mtk_event(), gps_nmea_event(), gps_sirf_event(), gps_skytraq_event(), gps_ublox_write(), gps_ubx_event(), hott_common_decode_event(), hott_common_init(), ins_event_check_and_handle(), mag_pitot_raw_downlink(), mateksys3901l0x_send_optical_flow(), mavlink_check_and_parse(), ms45xx_downlink(), multi_ranger_boot_device(), opticflow_telem_send(), parse_ins_msg(), pca95xx_configure(), pca95xx_get_input(), pca95xx_init(), pca95xx_set_output(), print_hex(), print_hex16(), print_hex32(), print_string(), rpm_sensor_send_motor(), sbus_common_decode_event(), sbus_common_init(), sdp3x_downlink(), send_accel(), send_accel_raw(), send_accel_scaled(), send_actuators(), send_ahrs_bias(), send_ahrs_ref_quat(), send_air_data(), send_airspeed(), send_aligner(), send_alive(), send_amsl(), send_aoa(), send_att(), send_att_indi(), send_att_ref(), send_attitude(), send_autopilot_version(), send_baro_bmp_data(), send_baro_raw(), send_batmon(), send_bebop_actuators(), send_bias(), send_bluegiga(), send_calibration(), send_cam(), send_cc2500_ppm(), send_chirp(), send_circle(), send_circle_parametric(), send_commands(), send_ctc(), send_ctc_control(), send_ctl_a(), send_dcf(), send_desired(), send_detect_gate_visual_position(), send_divergence(), send_dl_value(), send_downlink(), send_dragspeed(), send_energy(), send_estimator(), send_euler(), send_euler_int(), send_fbw_status(), send_filter(), send_filter_status(), send_fp(), send_fp_min(), send_geo_mag(), send_gh(), send_gps(), send_gps_int(), send_gps_lla(), send_gps_rtk(), send_gps_rxmrtcm(), send_gps_sol(), send_gvf(), send_gvf_parametric(), send_gx3(), send_gyro(), send_gyro_raw(), send_gyro_scaled(), send_hff(), send_hff_debug(), send_hott(), send_hover_loop(), send_href(), send_hybrid_guidance(), send_i2c_err(), send_indi_g(), send_infrared(), send_ins(), send_ins_ekf2(), send_ins_ekf2_ext(), send_ins_ref(), send_ins_z(), send_inv_filter(), send_jevois_mavlink_visual_position(), send_jevois_mavlink_visual_target(), send_mag(), send_mag_heading(), send_mag_raw(), send_mag_scaled(), send_mode(), send_motor_mixing(), send_nav(), send_nav_ref(), send_nav_status(), send_navdata(), send_optical_flow_hover(), send_piksi_heartbeat(), send_ppm(), send_quat(), send_rate(), send_rc(), send_relative_localization_data(), send_rotorcraft_cmd(), send_rotorcraft_rc(), send_sbus(), send_sdlog_status(), send_secure_link_info(), send_segment(), send_status(), send_superbit(), send_survey(), send_svinfo(), send_svinfo_available(), send_svinfo_id(), send_thumbnails(), send_tune_hover(), send_tune_roll(), send_tune_vert(), send_uart_err(), send_vert_loop(), send_vff(), send_vffe(), send_vn_info(), send_wind(), send_wind_estimator(), send_wind_info(), send_wind_info_ret(), send_windtunnel_meas(), send_wp_moved(), spektrum_uart_check(), telemetry_intermcu_repack(), temp_adc_downlink(), tfmini_i2c_send_lidar(), tfmini_send_lidar(), throttle_curve_send_telem(), ubx_header(), ubx_send_1byte(), ubx_send_bytes(), ubx_send_cfg_rst(), ubx_trailer(), v4l2_capture_thread(), v4l2_close(), v4l2_image_free(), v4l2_image_get(), v4l2_image_get_nonblock(), v4l2_init(), v4l2_start_capture(), v4l2_stop_capture(), VCOM_init(), VL53L1_NonBlocking_ReadMulti(), VL53L1_NonBlocking_WriteMulti(), VL53L1_RdByte(), VL53L1_RdDWord(), VL53L1_RdWord(), VL53L1_ReadMulti(), VL53L1_WrByte(), VL53L1_WrDWord(), VL53L1_WriteMulti(), VL53L1_WrWord(), VL53L1X_BootDevice(), VL53L1X_BootState(), VL53L1X_CheckForDataReady(), VL53L1X_ClearInterrupt(), VL53L1X_GetAmbientPerSpad(), VL53L1X_GetAmbientRate(), VL53L1X_GetDistance(), VL53L1X_GetDistanceMode(), VL53L1X_GetDistanceThresholdHigh(), VL53L1X_GetDistanceThresholdLow(), VL53L1X_GetDistanceThresholdWindow(), VL53L1X_GetInterMeasurementInMs(), VL53L1X_GetInterruptPolarity(), VL53L1X_GetOffset(), VL53L1X_GetRangeStatus(), VL53L1X_GetResult(), VL53L1X_GetROI_XY(), VL53L1X_GetROICenter(), VL53L1X_GetSensorId(), VL53L1X_GetSigmaThreshold(), VL53L1X_GetSignalPerSpad(), VL53L1X_GetSignalRate(), VL53L1X_GetSignalThreshold(), VL53L1X_GetSpadNb(), VL53L1X_GetTimingBudgetInMs(), VL53L1X_GetXtalk(), VL53L1X_NonBlocking_CheckForDataReady(), VL53L1X_NonBlocking_ClearInterrupt(), VL53L1X_NonBlocking_GetDistance(), VL53L1X_NonBlocking_GetRangeStatus(), VL53L1X_NonBlocking_IsIdle(), VL53L1X_NonBlocking_ReadDataEvent(), VL53L1X_NonBlocking_RequestData(), VL53L1X_SensorInit(), VL53L1X_SetDistanceMode(), VL53L1X_SetDistanceThreshold(), VL53L1X_SetI2CAddress(), VL53L1X_SetInterMeasurementInMs(), VL53L1X_SetInterruptPolarity(), VL53L1X_SetOffset(), VL53L1X_SetROI(), VL53L1X_SetROICenter(), VL53L1X_SetSigmaThreshold(), VL53L1X_SetSignalThreshold(), VL53L1X_SetTimingBudgetInMs(), VL53L1X_SetXtalk(), VL53L1X_StartRanging(), VL53L1X_StartTemperatureUpdate(), VL53L1X_StopRanging(), w5100_check_and_parse(), and xsens_parser_event().

◆ ifaces

const struct usb_interface ifaces[]
static
Initial value:
= {{
.num_altsetting = 1,
.altsetting = comm_iface,
}, {
.num_altsetting = 1,
.altsetting = data_iface,
}
}

Definition at line 191 of file usb_ser_hw.c.

◆ my_usbd_dev

usbd_device* my_usbd_dev

Definition at line 72 of file usb_ser_hw.c.

Referenced by VCOM_event(), VCOM_init(), and VCOM_send_message().

◆ rxdata

uint8_t rxdata[VCOM_FIFO_SIZE]
static

Definition at line 59 of file usb_ser_hw.c.

Referenced by VCOM_init().

◆ rxfifo

fifo_t rxfifo
static

◆ serial_no

char serial_no[25]
static

Definition at line 213 of file usb_ser_hw.c.

Referenced by VCOM_init().

◆ tx_timeout

int tx_timeout

Definition at line 70 of file usb_ser_hw.c.

Referenced by VCOM_event(), VCOM_init(), and VCOM_putchar().

◆ txdata

uint8_t txdata[VCOM_FIFO_SIZE]
static

Definition at line 58 of file usb_ser_hw.c.

Referenced by VCOM_init().

◆ txfifo

fifo_t txfifo
static

◆ usb_connected

bool usb_connected
static

◆ usb_serial

struct usb_serial_periph usb_serial

Definition at line 523 of file usb_ser_hw.c.

◆ usb_strings

const char* usb_strings[]
static
Initial value:
= {
"Paparazzi UAV",
"CDC Serial STM32",
}

Definition at line 216 of file usb_ser_hw.c.

Referenced by VCOM_init().

◆ usbd_control_buffer

uint8_t usbd_control_buffer[128]

Definition at line 227 of file usb_ser_hw.c.

Referenced by VCOM_init().

data_endp
static const struct usb_endpoint_descriptor data_endp[]
Definition: usb_ser_hw.c:106
comm_iface
static const struct usb_interface_descriptor comm_iface[]
Definition: usb_ser_hw.c:158
serial_no
static char serial_no[25]
Definition: usb_ser_hw.c:213
CS_INTERFACE
#define CS_INTERFACE
Definition: usb_ser_hw.c:78
cdcacm_functional_descriptors
static const struct @17 cdcacm_functional_descriptors
ifaces
static const struct usb_interface ifaces[]
Definition: usb_ser_hw.c:191
MAX_PACKET_SIZE
#define MAX_PACKET_SIZE
Definition: usb_ser_hw.c:46
data_iface
static const struct usb_interface_descriptor data_iface[]
Definition: usb_ser_hw.c:176
comm_endp
static const struct usb_endpoint_descriptor comm_endp[]
Definition: usb_ser_hw.c:96