Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
CDC USB device driver for STM32 architecture (STM32F1, STM32F4) More...
#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/usb/dwc/otg_fs.h>
#include "mcu_periph/usb_serial.h"
#include "mcu_periph/sys_time_arch.h"
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 enum usbd_request_return_codes | 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 |
CDC USB device driver for STM32 architecture (STM32F1, STM32F4)
Definition in file usb_ser_hw.c.
struct fifo_t |
Definition at line 52 of file usb_ser_hw.c.
Data Fields | ||
---|---|---|
uint8_t * | buf | |
int | head | |
size_t | size | |
int | tail |
#define MAX_PACKET_SIZE 64 |
Definition at line 46 of file usb_ser_hw.c.
#define TX_TIMEOUT_CNT 20 |
Definition at line 50 of file usb_ser_hw.c.
#define VCOM_FIFO_SIZE 256 |
Definition at line 48 of file usb_ser_hw.c.
|
static |
CDC device control request (from libopencm3 examples)
Definition at line 227 of file usb_ser_hw.c.
Referenced by cdcacm_set_config().
|
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().
|
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().
static 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.
Referenced by fifo_free(), fifo_peek(), VCOM_check_available(), and VCOM_event().
static int fifo_free | ( | fifo_t * | fifo | ) |
Definition at line 373 of file usb_ser_hw.c.
References fifo_avail(), and VCOM_FIFO_SIZE.
Referenced by VCOM_check_free_space().
Definition at line 349 of file usb_ser_hw.c.
References fifo_t::buf, fifo_t::head, fifo_t::tail, and VCOM_FIFO_SIZE.
Referenced by VCOM_getchar().
Definition at line 322 of file usb_ser_hw.c.
References fifo_t::buf, fifo_t::head, and fifo_t::tail.
Referenced by VCOM_init().
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().
Definition at line 331 of file usb_ser_hw.c.
References fifo_t::buf, fifo_t::head, fifo_t::tail, and VCOM_FIFO_SIZE.
Referenced by cdcacm_data_rx_cb(), and VCOM_putchar().
|
static |
Definition at line 294 of file usb_ser_hw.c.
References usb_connected.
Referenced by cdcacm_set_config().
|
static |
Definition at line 555 of file usb_ser_hw.c.
References VCOM_check_available().
Referenced by VCOM_init().
|
static |
Definition at line 526 of file usb_ser_hw.c.
References VCOM_check_free_space().
Referenced by VCOM_init().
|
static |
Definition at line 560 of file usb_ser_hw.c.
References VCOM_getchar().
Referenced by VCOM_init().
|
static |
Definition at line 550 of file usb_ser_hw.c.
References VCOM_send_message().
Referenced by VCOM_init().
|
static |
Definition at line 533 of file usb_ser_hw.c.
References VCOM_putchar().
Referenced by main_periodic_task(), and VCOM_init().
|
static |
Definition at line 540 of file usb_ser_hw.c.
References VCOM_putchar().
Referenced by VCOM_init().
int VCOM_check_available | ( | void | ) |
Checks if data available in VCOM buffer.
Definition at line 459 of file usb_ser_hw.c.
References fifo_avail(), and rxfifo.
Referenced by dfu_command_event(), event_usb_serial(), ReadUsbBuffer(), tunnel_event(), and usb_serial_char_available().
bool VCOM_check_free_space | ( | uint16_t | len | ) |
Checks if buffer free in VCOM buffer.
Definition at line 450 of file usb_ser_hw.c.
References FALSE, fifo_free(), TRUE, and txfifo.
Referenced by dfu_command_event(), tunnel_event(), usb_serial_check_free_space(), and VCOM_putchar().
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().
Referenced by event_usb_serial(), main(), and mcu_event().
int VCOM_getchar | ( | void | ) |
Reads one character from VCOM port.
Definition at line 425 of file usb_ser_hw.c.
References fifo_get(), and rxfifo.
Referenced by dfu_command_event(), event_usb_serial(), ReadUsbBuffer(), tunnel_event(), and usb_serial_getch().
void VCOM_init | ( | void | ) |
Definition at line 565 of file usb_ser_hw.c.
References cdcacm_set_config(), config, dev, usb_serial_periph::device, fifo_init(), GPIO11, GPIO12, GPIO_AF10, GPIOA, my_usbd_dev, rxdata, rxfifo, serial_no, tx_timeout, txdata, txfifo, usb_connected, usb_serial, usb_serial_char_available(), usb_serial_check_free_space(), usb_serial_getch(), usb_serial_send(), usb_serial_transmit(), usb_serial_transmit_buffer(), usb_strings, and usbd_control_buffer.
Referenced by init_usb_serial(), main(), and mcu_init().
int VCOM_peekchar | ( | int | ofs | ) |
Reads one character from VCOM port without removing it from the queue.
ofs | position to read |
Definition at line 438 of file usb_ser_hw.c.
References fifo_peek(), and rxfifo.
Referenced by dfu_command_event().
int VCOM_putchar | ( | int | c | ) |
Writes one character to VCOM port fifo.
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.
[in] | c | character to write |
Definition at line 397 of file usb_ser_hw.c.
References fifo_put(), sys_time_usleep(), tx_timeout, TX_TIMEOUT_CNT, txfifo, usb_connected, VCOM_check_free_space(), and VCOM_send_message().
Referenced by cmd_execute(), periodic_usb_serial(), tunnel_event(), usb_serial_parse_packet(), usb_serial_transmit(), and usb_serial_transmit_buffer().
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.
Referenced by cmd_execute(), usb_serial_parse_packet(), usb_serial_send(), VCOM_event(), and VCOM_putchar().
const { ... } cdcacm_functional_descriptors |
|
static |
Definition at line 72 of file usb_ser_hw.c.
|
static |
Definition at line 72 of file usb_ser_hw.c.
|
static |
Definition at line 72 of file usb_ser_hw.c.
Referenced by bmi088_send_config(), dshotStart(), gpio_init(), mpu60x0_send_config(), mpu9250_send_config(), msdStart(), py_check_status(), python_init(), and VCOM_init().
|
static |
Definition at line 72 of file usb_ser_hw.c.
|
static |
Definition at line 72 of file usb_ser_hw.c.
|
static |
Definition at line 72 of file usb_ser_hw.c.
Referenced by actuators_sbus_send(), actuators_spektrum_send(), actuators_uavcan_send_esc(), adc_msg_send(), air_data_parse_WIND_INFO(), airspeed_ets_downlink(), airspeed_uavcan_downlink(), can_fuelcell_send_telemetry(), configure_isp(), datalink_parse_PING(), debug_vect(), dl_parse_msg(), DlCheckAndParse(), DownlinkSendWp(), esc32_msg_send(), esc_msg_send(), faulhaber_send_command(), 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(), intermcu_dl_repack(), mateksys3901l0x_send_optical_flow(), mavlink_check_and_parse(), ms45xx_downlink(), multi_ranger_boot_device(), nav_parse_BLOCK(), opticflow_telem_send(), parse_ins_msg(), pca95xx_configure(), pca95xx_get_input(), pca95xx_init(), pca95xx_set_output(), power_uavcan_send_power_device(), print_hex(), print_hex16(), print_hex32(), print_string(), range_sensor_uavcan_send_lidar(), RdByte(), RdMulti(), 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_quat(), send_ahrs_ref_quat(), send_air_data(), send_airspeed(), send_airspeed_wind_ekf(), send_airspeed_wind_ekf_debug(), send_aligner(), send_alive(), send_amsl(), send_aoa(), send_approach_moving_target(), send_att(), send_att_full_indi(), 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_body_rates_accel(), send_calibration(), send_cam(), send_cc2500_ppm(), send_chirp(), send_circle(), send_cloud_sensor_data(), send_commands(), send_ctc(), send_ctc_control(), send_ctl_a(), send_desired(), send_detect_gate_visual_position(), send_divergence(), send_dl_value(), send_doublet(), send_downlink(), send_dragspeed(), send_eff_mat_g_indi(), send_eff_mat_g_indi_simple(), send_eff_mat_guid_indi_hybrid(), send_eff_mat_guid_oneloop_andi(), send_eff_mat_stab_oneloop_andi(), send_energy(), send_estimator(), send_euler(), send_euler_int(), send_external_pose_down(), send_fbw_status(), 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_sol(), send_guidance_indi_hybrid(), send_guidance_oneloop_andi(), send_gvf(), send_gvf_parametric(), 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_imu_heater(), send_indi_guidance(), send_ins(), send_ins_ekf2(), send_ins_ekf2_ext(), send_ins_flow(), 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_minimal_com(), send_mode(), send_motor_mixing(), send_nav(), send_nav_ref(), send_nav_status(), send_navdata(), send_oneloop_andi(), send_oneloop_debug(), send_optical_flow_hover(), send_parachute(), send_piksi_heartbeat(), send_ppm(), send_quat(), send_rate(), send_rc(), send_relative_localization_data(), send_rotating_wing_state(), 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_target_pos_info(), 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_wave(), send_wind(), send_wind_estimator(), send_wind_info(), send_wind_info_ret(), send_windtunnel_meas(), send_wls_u(), send_wls_u_oneloop(), send_wls_u_stab(), send_wls_v(), send_wls_v_oneloop(), send_wls_v_stab(), send_wp_moved(), settings_parse_msg_GET_SETTING(), settings_parse_msg_SETTING(), spektrum_uart_check(), temp_adc_downlink(), tfmini_i2c_send_lidar(), tfmini_send_lidar(), thd_lidar_vl53l5cx(), 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(), vn200_event(), vn200_read_buffer(), w5100_check_and_parse(), WrByte(), WrMulti(), and xsens_parser_event().
|
static |
Definition at line 72 of file usb_ser_hw.c.
usbd_device* my_usbd_dev |
Definition at line 72 of file usb_ser_hw.c.
Referenced by VCOM_event(), and VCOM_init().
|
static |
Definition at line 59 of file usb_ser_hw.c.
Referenced by VCOM_init().
|
static |
Definition at line 62 of file usb_ser_hw.c.
Referenced by cdcacm_data_rx_cb(), VCOM_check_available(), VCOM_getchar(), VCOM_init(), and VCOM_peekchar().
|
static |
Definition at line 213 of file usb_ser_hw.c.
Referenced by VCOM_init().
int tx_timeout |
Definition at line 70 of file usb_ser_hw.c.
Referenced by VCOM_event(), VCOM_init(), and VCOM_putchar().
|
static |
Definition at line 58 of file usb_ser_hw.c.
Referenced by VCOM_init().
|
static |
Definition at line 61 of file usb_ser_hw.c.
Referenced by VCOM_check_free_space(), VCOM_event(), VCOM_init(), and VCOM_putchar().
|
static |
Definition at line 291 of file usb_ser_hw.c.
Referenced by cdcacm_set_config(), suspend_cb(), VCOM_init(), and VCOM_putchar().
struct usb_serial_periph usb_serial |
Definition at line 487 of file usb_ser_hw.c.
Referenced by VCOM_init().
|
static |
Definition at line 216 of file usb_ser_hw.c.
Referenced by VCOM_init().
uint8_t usbd_control_buffer[128] |
Definition at line 227 of file usb_ser_hw.c.
Referenced by VCOM_init().