#include <mavlink_comm.h>
|
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 |
|
|
typedef boost::lock_guard< boost::recursive_mutex > | mutex_lock |
| Convenience typedef for mutex lock. More...
|
|
|
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...
|
|
Definition at line 59 of file mavlink_comm.h.
mavrosflight::MavlinkComm::MavlinkComm |
( |
| ) |
|
Instantiates the class and begins communication on the specified serial port.
- Parameters
-
port | Name of the serial port (e.g. "/dev/ttyUSB0") |
baud_rate | Serial communication baud rate |
Definition at line 44 of file mavlink_comm.cpp.
mavrosflight::MavlinkComm::~MavlinkComm |
( |
| ) |
|
Stops communication and closes the serial port before the object is destroyed.
Definition at line 50 of file mavlink_comm.cpp.
void mavrosflight::MavlinkComm::async_read |
( |
| ) |
|
|
private |
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
-
error | Error code |
bytes_transferred | Number of bytes received |
Definition at line 124 of file mavlink_comm.cpp.
void mavrosflight::MavlinkComm::async_write |
( |
bool |
check_write_state | ) |
|
|
private |
Initialize an asynchronous write operation.
- Parameters
-
check_write_state | If true, only start another write operation if a write sequence is not already running |
Definition at line 162 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
-
error | Error code |
bytes_transferred | Number of bytes sent |
Definition at line 183 of file mavlink_comm.cpp.
void mavrosflight::MavlinkComm::close |
( |
| ) |
|
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 |
( |
| ) |
|
Register a listener for mavlink messages.
- Parameters
-
Definition at line 77 of file mavlink_comm.cpp.
void mavrosflight::MavlinkComm::send_message |
( |
const mavlink_message_t & |
msg | ) |
|
Send a mavlink message.
- Parameters
-
- Todo:
- Do something less catastrophic here
Definition at line 148 of file mavlink_comm.cpp.
Unregister a listener for mavlink messages.
- Parameters
-
Definition at line 96 of file mavlink_comm.cpp.
uint8_t mavrosflight::MavlinkComm::compid_ |
|
private |
boost::asio::io_service mavrosflight::MavlinkComm::io_service_ |
|
protected |
boost::thread mavrosflight::MavlinkComm::io_thread_ |
|
private |
mavlink_message_t mavrosflight::MavlinkComm::msg_in_ |
|
private |
boost::recursive_mutex mavrosflight::MavlinkComm::mutex_ |
|
private |
uint8_t mavrosflight::MavlinkComm::sysid_ |
|
private |
bool mavrosflight::MavlinkComm::write_in_progress_ |
|
private |
flag for whether async_write is already running
Definition at line 192 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 191 of file mavlink_comm.h.
The documentation for this class was generated from the following files: