Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
VCP Class Reference

#include <vcp.h>

Inheritance diagram for VCP:
Inheritance graph
[legend]

Public Member Functions

void begin_write ()
 
bool connected ()
 
void end_write ()
 
bool flush () override
 
bool in_bulk_mode ()
 
void init ()
 
void put_byte (uint8_t ch) override
 
uint8_t read_byte () override
 
void register_rx_callback (void(*rx_callback_ptr)(uint8_t data)) override
 
uint32_t rx_bytes_waiting () override
 
bool set_baud_rate (uint32_t baud)
 
bool tx_buffer_empty () override
 
uint32_t tx_bytes_free () override
 
void unregister_rx_callback () override
 
virtual void write (const uint8_t *ch, uint8_t len) override
 
- Public Member Functions inherited from Serial
 Serial ()
 

Public Attributes

std::function< void(uint8_t)> cb_
 
bool connected_ = false
 
bool reset_ = false
 

Private Member Functions

void perform_maintenance ()
 
void send_disconnect_signal ()
 

Private Attributes

bool bulk_mode
 
uint8_t bulk_mode_buffer [64]
 
uint8_t bulk_mode_buffer_index
 
GPIO rx_pin_
 
GPIO tx_pin_
 
GPIO vbus_sens_
 

Additional Inherited Members

- Public Types inherited from Serial
enum  { POLLING = 0x00, INTERRUPT = 0x01, DMA_TX = 0x02, DMA_RX = 0x04 }
 
enum  { UART = 0, VCP = 1 }
 
- Protected Attributes inherited from Serial
uint8_t mode_
 
std::function< void(uint8_t)> receive_CB_ = nullptr
 
GPIO rx_pin_
 
GPIO tx_pin_
 

Detailed Description

Definition at line 19 of file vcp.h.

Member Function Documentation

void VCP::begin_write ( )

Definition at line 118 of file vcp.cpp.

bool VCP::connected ( )

Definition at line 108 of file vcp.cpp.

void VCP::end_write ( )

Definition at line 119 of file vcp.cpp.

bool VCP::flush ( )
overridevirtual

Implements Serial.

Definition at line 113 of file vcp.cpp.

bool VCP::in_bulk_mode ( )

Definition at line 132 of file vcp.cpp.

void VCP::init ( )

Definition at line 24 of file vcp.cpp.

void VCP::perform_maintenance ( )
private

Definition at line 59 of file vcp.cpp.

void VCP::put_byte ( uint8_t  ch)
overridevirtual

Implements Serial.

Definition at line 102 of file vcp.cpp.

uint8_t VCP::read_byte ( )
overridevirtual

Implements Serial.

Definition at line 84 of file vcp.cpp.

void VCP::register_rx_callback ( void(*)(uint8_t data)  rx_callback_ptr)
overridevirtual

Implements Serial.

Definition at line 121 of file vcp.cpp.

uint32_t VCP::rx_bytes_waiting ( )
overridevirtual

Implements Serial.

Definition at line 74 of file vcp.cpp.

void VCP::send_disconnect_signal ( )
private

Definition at line 137 of file vcp.cpp.

bool VCP::set_baud_rate ( uint32_t  baud)
bool VCP::tx_buffer_empty ( )
overridevirtual

Implements Serial.

Definition at line 97 of file vcp.cpp.

uint32_t VCP::tx_bytes_free ( )
overridevirtual

Implements Serial.

Definition at line 79 of file vcp.cpp.

void VCP::unregister_rx_callback ( )
overridevirtual

Implements Serial.

Definition at line 126 of file vcp.cpp.

void VCP::write ( const uint8_t *  ch,
uint8_t  len 
)
overridevirtual

Implements Serial.

Definition at line 39 of file vcp.cpp.

Member Data Documentation

bool VCP::bulk_mode
private

Definition at line 49 of file vcp.h.

uint8_t VCP::bulk_mode_buffer[64]
private

Definition at line 47 of file vcp.h.

uint8_t VCP::bulk_mode_buffer_index
private

Definition at line 48 of file vcp.h.

std::function<void(uint8_t)> VCP::cb_

Definition at line 38 of file vcp.h.

bool VCP::connected_ = false

Definition at line 39 of file vcp.h.

bool VCP::reset_ = false

Definition at line 40 of file vcp.h.

GPIO VCP::rx_pin_
private

Definition at line 51 of file vcp.h.

GPIO VCP::tx_pin_
private

Definition at line 52 of file vcp.h.

GPIO VCP::vbus_sens_
private

Definition at line 53 of file vcp.h.


The documentation for this class was generated from the following files:


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:58