Classes | Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
Serial Class Reference

#include <serial.h>

Classes

struct  WriteBuffer
 Struct for buffering the contents of a mavlink message. More...
 

Public Member Functions

void close ()
 Stops communication and closes the port. More...
 
void open ()
 Opens the port and begins communication. More...
 
void register_listener (SerialListener *const listener)
 Register a listener for received bytes. More...
 
 Serial (std::__cxx11::string port, int baud_rate)
 Instantiates the class and begins communication on the specified serial port. More...
 
void write (const uint8_t *buffer, uint8_t len)
 write data More...
 
 ~Serial ()
 Stops communication and closes the serial port before the object is destroyed. More...
 

Public Attributes

boost::asio::io_service io_service_
 boost io service provider More...
 

Private Types

typedef boost::lock_guard< boost::recursive_mutex > mutex_lock
 Convenience typedef for mutex lock. More...
 

Private Member Functions

void async_read ()
 Initiate an asynchronous read operation. More...
 
void async_read_end (const boost::system::error_code &error, size_t bytes_transferred)
 Handler for end of asynchronous read operation. More...
 
void async_write (bool check_write_state)
 Initialize an asynchronous write operation. More...
 
void async_write_end (const boost::system::error_code &error, size_t bytes_transferred)
 Handler for end of asynchronous write operation. More...
 

Private Attributes

int baud_rate_
 
uint8_t compid_
 
boost::thread io_thread_
 thread on which the io service runs More...
 
SerialListenerlistener_
 Pointer to byte listener. More...
 
boost::recursive_mutex mutex_
 mutex for threadsafe operation More...
 
std::string port_
 
uint8_t read_buf_raw_ [BUFFER_SIZE]
 
boost::asio::serial_port serial_port_
 boost serial port object More...
 
uint8_t sysid_
 
bool write_in_progress_
 flag for whether async_write is already running More...
 
std::list< WriteBuffer * > write_queue_
 queue of buffers to be written to the serial port More...
 

Detailed Description

Definition at line 59 of file include/serial.h.

Member Typedef Documentation

◆ mutex_lock

typedef boost::lock_guard<boost::recursive_mutex> Serial::mutex_lock
private

Convenience typedef for mutex lock.

Definition at line 140 of file include/serial.h.

Constructor & Destructor Documentation

◆ Serial()

Serial::Serial ( std::__cxx11::string  port,
int  baud_rate 
)

Instantiates the class and begins communication on the specified serial port.

Parameters
portName of the serial port (e.g. "/dev/ttyUSB0")
baud_rateSerial communication baud rate

Definition at line 43 of file serial.cpp.

◆ ~Serial()

Serial::~Serial ( )

Stops communication and closes the serial port before the object is destroyed.

Definition at line 53 of file serial.cpp.

Member Function Documentation

◆ async_read()

void Serial::async_read ( )
private

Initiate an asynchronous read operation.

Definition at line 100 of file serial.cpp.

◆ async_read_end()

void Serial::async_read_end ( const boost::system::error_code &  error,
size_t  bytes_transferred 
)
private

Handler for end of asynchronous read operation.

Parameters
errorError code
bytes_transferredNumber of bytes received

Definition at line 113 of file serial.cpp.

◆ async_write()

void Serial::async_write ( bool  check_write_state)
private

Initialize an asynchronous write operation.

Parameters
check_write_stateIf true, only start another write operation if a write sequence is not already running

Definition at line 147 of file serial.cpp.

◆ async_write_end()

void Serial::async_write_end ( const boost::system::error_code &  error,
size_t  bytes_transferred 
)
private

Handler for end of asynchronous write operation.

Parameters
errorError code
bytes_transferredNumber of bytes sent

Definition at line 168 of file serial.cpp.

◆ close()

void Serial::close ( )

Stops communication and closes the port.

Definition at line 79 of file serial.cpp.

◆ open()

void Serial::open ( )

Opens the port and begins communication.

Definition at line 57 of file serial.cpp.

◆ register_listener()

void Serial::register_listener ( SerialListener *const  listener)

Register a listener for received bytes.

Parameters
listenerPointer to an object that implements the SerialListener interface

Definition at line 92 of file serial.cpp.

◆ write()

void Serial::write ( const uint8_t *  buffer,
uint8_t  len 
)

write data

Parameters
bufferThe message to send
lenThe number of bytes
Todo:
Do something less catastrophic here

Definition at line 128 of file serial.cpp.

Member Data Documentation

◆ baud_rate_

int Serial::baud_rate_
private

Definition at line 135 of file include/serial.h.

◆ compid_

uint8_t Serial::compid_
private

Definition at line 179 of file include/serial.h.

◆ io_service_

boost::asio::io_service Serial::io_service_

boost io service provider

Definition at line 98 of file include/serial.h.

◆ io_thread_

boost::thread Serial::io_thread_
private

thread on which the io service runs

Definition at line 175 of file include/serial.h.

◆ listener_

SerialListener* Serial::listener_
private

Pointer to byte listener.

Definition at line 131 of file include/serial.h.

◆ mutex_

boost::recursive_mutex Serial::mutex_
private

mutex for threadsafe operation

Definition at line 176 of file include/serial.h.

◆ port_

std::string Serial::port_
private

Definition at line 134 of file include/serial.h.

◆ read_buf_raw_

uint8_t Serial::read_buf_raw_[BUFFER_SIZE]
private

Definition at line 181 of file include/serial.h.

◆ serial_port_

boost::asio::serial_port Serial::serial_port_
private

boost serial port object

Definition at line 133 of file include/serial.h.

◆ sysid_

uint8_t Serial::sysid_
private

Definition at line 178 of file include/serial.h.

◆ write_in_progress_

bool Serial::write_in_progress_
private

flag for whether async_write is already running

Definition at line 184 of file include/serial.h.

◆ write_queue_

std::list<WriteBuffer*> Serial::write_queue_
private

queue of buffers to be written to the serial port

Definition at line 183 of file include/serial.h.


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


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:18:03