Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
mavrosflight::MavlinkComm Class Referenceabstract

#include <mavlink_comm.h>

Inheritance diagram for mavrosflight::MavlinkComm:
Inheritance graph
[legend]

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...
 
 MavlinkComm ()
 Instantiates the class and begins communication on the specified serial port. More...
 
void open ()
 Opens the port and begins communication. More...
 
void register_mavlink_listener (MavlinkListenerInterface *const listener)
 Register a listener for mavlink messages. More...
 
void send_message (const mavlink_message_t &msg)
 Send a mavlink message. More...
 
void unregister_mavlink_listener (MavlinkListenerInterface *const listener)
 Unregister a listener for mavlink messages. More...
 
 ~MavlinkComm ()
 Stops communication and closes the serial port before the object is destroyed. More...
 

Protected Member Functions

virtual void do_async_read (const boost::asio::mutable_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)=0
 
virtual void do_async_write (const boost::asio::const_buffers_1 &buffer, boost::function< void(const boost::system::error_code &, size_t)> handler)=0
 
virtual void do_close ()=0
 
virtual void do_open ()=0
 
virtual bool is_open ()=0
 

Protected 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

uint8_t compid_
 
boost::thread io_thread_
 thread on which the io service runs More...
 
std::vector< MavlinkListenerInterface * > listeners_
 listeners for mavlink messages More...
 
mavlink_message_t msg_in_
 
boost::recursive_mutex mutex_
 mutex for threadsafe operation More...
 
uint8_t read_buf_raw_ [MAVLINK_SERIAL_READ_BUF_SIZE]
 
mavlink_status_t status_in_
 
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 57 of file mavlink_comm.h.

Member Typedef Documentation

typedef boost::lock_guard<boost::recursive_mutex> mavrosflight::MavlinkComm::mutex_lock
private

Convenience typedef for mutex lock.

Definition at line 141 of file mavlink_comm.h.

Constructor & Destructor Documentation

mavrosflight::MavlinkComm::MavlinkComm ( )

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 mavlink_comm.cpp.

mavrosflight::MavlinkComm::~MavlinkComm ( )

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

Definition at line 45 of file mavlink_comm.cpp.

Member Function Documentation

void mavrosflight::MavlinkComm::async_read ( )
private

Initiate an asynchronous read operation.

Definition at line 104 of file mavlink_comm.cpp.

void mavrosflight::MavlinkComm::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 114 of file mavlink_comm.cpp.

void mavrosflight::MavlinkComm::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 153 of file mavlink_comm.cpp.

void mavrosflight::MavlinkComm::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 169 of file mavlink_comm.cpp.

void mavrosflight::MavlinkComm::close ( )

Stops communication and closes the port.

Definition at line 57 of file mavlink_comm.cpp.

virtual void mavrosflight::MavlinkComm::do_async_read ( const boost::asio::mutable_buffers_1 &  buffer,
boost::function< void(const boost::system::error_code &, size_t)>  handler 
)
protectedpure virtual
virtual void mavrosflight::MavlinkComm::do_async_write ( const boost::asio::const_buffers_1 &  buffer,
boost::function< void(const boost::system::error_code &, size_t)>  handler 
)
protectedpure virtual
virtual void mavrosflight::MavlinkComm::do_close ( )
protectedpure virtual
virtual void mavrosflight::MavlinkComm::do_open ( )
protectedpure virtual
virtual bool mavrosflight::MavlinkComm::is_open ( )
protectedpure virtual
void mavrosflight::MavlinkComm::open ( )

Opens the port and begins communication.

Definition at line 47 of file mavlink_comm.cpp.

void mavrosflight::MavlinkComm::register_mavlink_listener ( MavlinkListenerInterface *const  listener)

Register a listener for mavlink messages.

Parameters
listenerPointer to an object that implements the MavlinkListenerInterface interface

Definition at line 70 of file mavlink_comm.cpp.

void mavrosflight::MavlinkComm::send_message ( const mavlink_message_t &  msg)

Send a mavlink message.

Parameters
msgThe message to send
Todo:
Do something less catastrophic here

Definition at line 139 of file mavlink_comm.cpp.

void mavrosflight::MavlinkComm::unregister_mavlink_listener ( MavlinkListenerInterface *const  listener)

Unregister a listener for mavlink messages.

Parameters
listenerPointer to an object that implements the MavlinkListenerInterface interface

Definition at line 89 of file mavlink_comm.cpp.

Member Data Documentation

uint8_t mavrosflight::MavlinkComm::compid_
private

Definition at line 182 of file mavlink_comm.h.

boost::asio::io_service mavrosflight::MavlinkComm::io_service_
protected

boost io service provider

Definition at line 109 of file mavlink_comm.h.

boost::thread mavrosflight::MavlinkComm::io_thread_
private

thread on which the io service runs

Definition at line 178 of file mavlink_comm.h.

std::vector<MavlinkListenerInterface *> mavrosflight::MavlinkComm::listeners_
private

listeners for mavlink messages

Definition at line 176 of file mavlink_comm.h.

mavlink_message_t mavrosflight::MavlinkComm::msg_in_
private

Definition at line 186 of file mavlink_comm.h.

boost::recursive_mutex mavrosflight::MavlinkComm::mutex_
private

mutex for threadsafe operation

Definition at line 179 of file mavlink_comm.h.

uint8_t mavrosflight::MavlinkComm::read_buf_raw_[MAVLINK_SERIAL_READ_BUF_SIZE]
private

Definition at line 184 of file mavlink_comm.h.

mavlink_status_t mavrosflight::MavlinkComm::status_in_
private

Definition at line 187 of file mavlink_comm.h.

uint8_t mavrosflight::MavlinkComm::sysid_
private

Definition at line 181 of file mavlink_comm.h.

bool mavrosflight::MavlinkComm::write_in_progress_
private

flag for whether async_write is already running

Definition at line 190 of file mavlink_comm.h.

std::list<WriteBuffer *> mavrosflight::MavlinkComm::write_queue_
private

queue of buffers to be written to the serial port

Definition at line 189 of file mavlink_comm.h.


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


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:09:29