#include <Client.hpp>
Public Member Functions | |
Client () | |
Client Constructor. More... | |
std::shared_ptr< SubscriptionBase > | getSubscription (const msp::ID &id) |
Get pointer to subscription. More... | |
FirmwareVariant | getVariant () const |
Query the cached device path. More... | |
int | getVersion () const |
Query the cached device path. More... | |
bool | hasSubscription (const msp::ID &id) const |
Check if message ID already has a subscription. More... | |
bool | isConnected () const |
Query the system to see if a connection is active. More... | |
void | processOneMessage (const asio::error_code &ec, const std::size_t &bytes_transferred) |
Main entry point for processing received data. It is called directly by the ASIO library, and as such it much match the function signatures expected by ASIO. More... | |
bool | sendData (const msp::ID id, const ByteVector &data=ByteVector(0)) |
Send an ID and payload to the flight controller. More... | |
bool | sendData (const msp::ID id, const ByteVectorUptr &&data) |
Send an ID and payload to the flight controller. More... | |
bool | sendMessage (msp::Message &message, const double &timeout=0) |
Send a message to the connected flight controller. If the message sends data to the flight controller, it will be packed into a buffer and sent. The method will block (optionally for a finite amount of time) until a matching response is received from the flight controller. If the response includes data, it will be unpacked back into the same Message object. More... | |
bool | sendMessageNoWait (const msp::Message &message) |
Send a message, but do not wait for any response. More... | |
void | setLoggingLevel (const LoggingLevel &level) |
Set the verbosity of the output. More... | |
void | setVariant (const FirmwareVariant &v) |
Change the device path on the next connect. More... | |
bool | setVersion (const int &ver) |
Change the device path on the next connect. More... | |
bool | start (const std::string &device, const size_t baudrate=115200) |
Start communications with a flight controller. More... | |
bool | stop () |
Stop communications with a flight controller. More... | |
template<typename T , typename C , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type> | |
std::shared_ptr< SubscriptionBase > | subscribe (void(C::*callback)(const T &), C *context, const double &tp) |
Register callback function that is called when a message of matching ID is received. More... | |
template<typename T , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type> | |
std::shared_ptr< SubscriptionBase > | subscribe (const std::function< void(const T &)> &recv_callback, const double &tp) |
Register callback function that is called when a message of matching ID is received. Replaces the previous callback of the same ID. More... | |
~Client () | |
~Client Destructor More... | |
Protected Member Functions | |
bool | connectPort (const std::string &device, const size_t baudrate=115200) |
Establish connection to serial device and start read thread. More... | |
uint8_t | crcV1 (const uint8_t id, const ByteVector &data) const |
crcV1 Computes a checksum for MSPv1 messages More... | |
uint8_t | crcV2 (uint8_t crc, const ByteVector &data) const |
crcV2 Computes a checksum for MSPv2 messages More... | |
uint8_t | crcV2 (uint8_t crc, const uint8_t &b) const |
crcV2 Computes a checksum for MSPv2 messages More... | |
bool | disconnectPort () |
Break connection to serial device and stop read thread. More... | |
uint8_t | extractChar () |
Read a single byte from either the buffer or the serial device. More... | |
std::pair< iterator, bool > | messageReady (iterator begin, iterator end) const |
messageReady Method used by ASIO library to determine if a full message is present in receiving buffer. It must match the function signature expected by ASIO. More... | |
ByteVector | packMessageV1 (const msp::ID id, const ByteVector &data=ByteVector(0)) const |
packMessageV1 Packs data ID and data payload into a MSPv1 formatted buffer ready for sending to the serial device More... | |
ByteVector | packMessageV2 (const msp::ID id, const ByteVector &data=ByteVector(0)) const |
packMessageV2 Packs data ID and data payload into a MSPv2 formatted buffer ready for sending to the serial device More... | |
ReceivedMessage | processOneMessageV1 () |
processOneMessageV1 Iterates over characters in the ASIO buffer to identify and unpack a MSPv1 encoded message More... | |
ReceivedMessage | processOneMessageV2 () |
processOneMessageV2 Iterates over characters in the ASIO buffer to identify and unpack a MSPv2 encoded message More... | |
bool | startReadThread () |
Starts the receiver thread that handles incomming messages. More... | |
bool | startSubscriptions () |
Starts the receiver thread that handles incomming messages. More... | |
bool | stopReadThread () |
Stops the receiver thread. More... | |
bool | stopSubscriptions () |
Stops the receiver thread. More... | |
Protected Attributes | |
asio::streambuf | buffer |
std::condition_variable | cv_response |
std::mutex | cv_response_mtx |
FirmwareVariant | fw_variant |
asio::io_service | io |
! io service More... | |
LoggingLevel | log_level_ |
int | msp_ver_ |
std::mutex | mutex_buffer |
std::mutex | mutex_response |
std::mutex | mutex_send |
std::mutex | mutex_subscriptions |
asio::serial_port | port |
! port for serial device More... | |
std::unique_ptr< ReceivedMessage > | request_received |
std::atomic_flag | running_ = ATOMIC_FLAG_INIT |
std::map< msp::ID, std::shared_ptr< SubscriptionBase > > | subscriptions |
std::thread | thread |
Definition at line 35 of file Client.hpp.
msp::client::Client::Client | ( | ) |
Client Constructor.
device | String describing the path to the serial device |
baudrate | Baudrate of the connection (default 115200, unnecessary for direct USB connection) |
Definition at line 10 of file Client.cpp.
msp::client::Client::~Client | ( | ) |
~Client Destructor
Definition at line 16 of file Client.cpp.
|
protected |
Establish connection to serial device and start read thread.
Definition at line 43 of file Client.cpp.
|
protected |
crcV1 Computes a checksum for MSPv1 messages
id | uint8_t MSP ID |
data | Payload which is also part of the checksum |
Definition at line 238 of file Client.cpp.
|
protected |
crcV2 Computes a checksum for MSPv2 messages
crc | Checksum value from which to start calculations |
data | ByteVector of data to be wrapped into the checksum |
Definition at line 266 of file Client.cpp.
|
protected |
crcV2 Computes a checksum for MSPv2 messages
crc | Checksum value from which to start calculations |
data | Single byte to use in the checksum calculation |
Definition at line 273 of file Client.cpp.
|
protected |
Break connection to serial device and stop read thread.
Definition at line 64 of file Client.cpp.
|
protected |
Read a single byte from either the buffer or the serial device.
Definition at line 185 of file Client.cpp.
|
inline |
Get pointer to subscription.
id | Message ID |
Definition at line 191 of file Client.hpp.
FirmwareVariant msp::client::Client::getVariant | ( | ) | const |
Query the cached device path.
Definition at line 32 of file Client.cpp.
int msp::client::Client::getVersion | ( | ) | const |
Query the cached device path.
Definition at line 28 of file Client.cpp.
|
inline |
Check if message ID already has a subscription.
id | Message ID |
Definition at line 182 of file Client.hpp.
bool msp::client::Client::isConnected | ( | ) | const |
Query the system to see if a connection is active.
Definition at line 71 of file Client.cpp.
|
protected |
messageReady Method used by ASIO library to determine if a full message is present in receiving buffer. It must match the function signature expected by ASIO.
Definition at line 355 of file Client.cpp.
|
protected |
packMessageV1 Packs data ID and data payload into a MSPv1 formatted buffer ready for sending to the serial device
id | msp::ID of the message being packed |
data | Optional binary payload to be packed into the outbound buffer |
Definition at line 225 of file Client.cpp.
|
protected |
packMessageV2 Packs data ID and data payload into a MSPv2 formatted buffer ready for sending to the serial device
id | msp::ID of the message being packed |
data | Optional binary payload to be packed into the outbound buffer |
Definition at line 246 of file Client.cpp.
void msp::client::Client::processOneMessage | ( | const asio::error_code & | ec, |
const std::size_t & | bytes_transferred | ||
) |
Main entry point for processing received data. It is called directly by the ASIO library, and as such it much match the function signatures expected by ASIO.
ec | ASIO error code |
bytes_transferred | Number of byte available for processing |
Definition at line 286 of file Client.cpp.
|
protected |
processOneMessageV1 Iterates over characters in the ASIO buffer to identify and unpack a MSPv1 encoded message
Definition at line 396 of file Client.cpp.
|
protected |
processOneMessageV2 Iterates over characters in the ASIO buffer to identify and unpack a MSPv2 encoded message
Definition at line 443 of file Client.cpp.
bool msp::client::Client::sendData | ( | const msp::ID | id, |
const ByteVector & | data = ByteVector(0) |
||
) |
Send an ID and payload to the flight controller.
id | Message ID |
data | Raw data (default zero length, meaning no data to send outbound) |
Definition at line 195 of file Client.cpp.
|
inline |
Send an ID and payload to the flight controller.
id | Message ID |
data | Unique pointer to data. May be empty if there is no data to send |
Definition at line 221 of file Client.hpp.
bool msp::client::Client::sendMessage | ( | msp::Message & | message, |
const double & | timeout = 0 |
||
) |
Send a message to the connected flight controller. If the message sends data to the flight controller, it will be packed into a buffer and sent. The method will block (optionally for a finite amount of time) until a matching response is received from the flight controller. If the response includes data, it will be unpacked back into the same Message object.
message | Reference to a Message-derived object to be sent/recieved. |
timeout | Maximum amount of time to block waiting for a response. A value of 0 (default) means wait forever. |
Definition at line 123 of file Client.cpp.
bool msp::client::Client::sendMessageNoWait | ( | const msp::Message & | message | ) |
Send a message, but do not wait for any response.
message | Reference to a Message-derived object to be sent |
Definition at line 173 of file Client.cpp.
void msp::client::Client::setLoggingLevel | ( | const LoggingLevel & | level | ) |
Set the verbosity of the output.
level | LoggingLevel matching the desired amount of output (default to WARNING) |
Definition at line 18 of file Client.cpp.
void msp::client::Client::setVariant | ( | const FirmwareVariant & | v | ) |
Change the device path on the next connect.
device | Path to device |
Definition at line 30 of file Client.cpp.
bool msp::client::Client::setVersion | ( | const int & | ver | ) |
Change the device path on the next connect.
ver | Version of MSP to use |
Definition at line 20 of file Client.cpp.
bool msp::client::Client::start | ( | const std::string & | device, |
const size_t | baudrate = 115200 |
||
) |
Start communications with a flight controller.
Definition at line 34 of file Client.cpp.
|
protected |
Starts the receiver thread that handles incomming messages.
Definition at line 73 of file Client.cpp.
|
protected |
Starts the receiver thread that handles incomming messages.
Definition at line 107 of file Client.cpp.
bool msp::client::Client::stop | ( | ) |
Stop communications with a flight controller.
Definition at line 39 of file Client.cpp.
|
protected |
|
protected |
|
inline |
Register callback function that is called when a message of matching ID is received.
callback | Pointer to callback function (class method) |
context | Object containing callback method |
tp | Period of timer that will send subscribed requests (in seconds). |
Definition at line 131 of file Client.hpp.
|
inline |
Register callback function that is called when a message of matching ID is received. Replaces the previous callback of the same ID.
recv_callback | Function to be called upon receipt of message |
tp | Period of timer that will send subscribed requests (in seconds). |
Definition at line 148 of file Client.hpp.
|
protected |
Definition at line 341 of file Client.hpp.
|
protected |
Definition at line 348 of file Client.hpp.
|
protected |
Definition at line 349 of file Client.hpp.
|
protected |
Definition at line 366 of file Client.hpp.
|
protected |
! io service
Definition at line 339 of file Client.hpp.
|
protected |
Definition at line 362 of file Client.hpp.
|
protected |
Definition at line 365 of file Client.hpp.
|
protected |
Definition at line 351 of file Client.hpp.
|
protected |
Definition at line 350 of file Client.hpp.
|
protected |
Definition at line 352 of file Client.hpp.
|
protected |
Definition at line 358 of file Client.hpp.
|
protected |
! port for serial device
Definition at line 340 of file Client.hpp.
|
protected |
Definition at line 355 of file Client.hpp.
|
protected |
Definition at line 345 of file Client.hpp.
|
protected |
Definition at line 359 of file Client.hpp.
|
protected |
Definition at line 344 of file Client.hpp.