Public Member Functions | Protected Member Functions | Protected Attributes
msp::client::Client Class Reference

#include <Client.hpp>

List of all members.

Public Member Functions

 Client ()
 Client Constructor.
std::shared_ptr< SubscriptionBasegetSubscription (const msp::ID &id)
 Get pointer to subscription.
FirmwareVariant getVariant () const
 Query the cached device path.
int getVersion () const
 Query the cached device path.
bool hasSubscription (const msp::ID &id) const
 Check if message ID already has a subscription.
bool isConnected () const
 Query the system to see if a connection is active.
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.
bool sendData (const msp::ID id, const ByteVector &data=ByteVector(0))
 Send an ID and payload to the flight controller.
bool sendData (const msp::ID id, const ByteVectorUptr &&data)
 Send an ID and payload to the flight controller.
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.
bool sendMessageNoWait (const msp::Message &message)
 Send a message, but do not wait for any response.
void setLoggingLevel (const LoggingLevel &level)
 Set the verbosity of the output.
void setVariant (const FirmwareVariant &v)
 Change the device path on the next connect.
bool setVersion (const int &ver)
 Change the device path on the next connect.
bool start (const std::string &device, const size_t baudrate=115200)
 Start communications with a flight controller.
bool stop ()
 Stop communications with a flight controller.
template<typename T , typename C , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type>
std::shared_ptr< SubscriptionBasesubscribe (void(C::*callback)(const T &), C *context, const double &tp)
 Register callback function that is called when a message of matching ID is received.
template<typename T , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type>
std::shared_ptr< SubscriptionBasesubscribe (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.
 ~Client ()
 ~Client Destructor

Protected Member Functions

bool connectPort (const std::string &device, const size_t baudrate=115200)
 Establish connection to serial device and start read thread.
uint8_t crcV1 (const uint8_t id, const ByteVector &data) const
 crcV1 Computes a checksum for MSPv1 messages
uint8_t crcV2 (uint8_t crc, const ByteVector &data) const
 crcV2 Computes a checksum for MSPv2 messages
uint8_t crcV2 (uint8_t crc, const uint8_t &b) const
 crcV2 Computes a checksum for MSPv2 messages
bool disconnectPort ()
 Break connection to serial device and stop read thread.
uint8_t extractChar ()
 Read a single byte from either the buffer or the serial device.
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.
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
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
ReceivedMessage processOneMessageV1 ()
 processOneMessageV1 Iterates over characters in the ASIO buffer to identify and unpack a MSPv1 encoded message
ReceivedMessage processOneMessageV2 ()
 processOneMessageV2 Iterates over characters in the ASIO buffer to identify and unpack a MSPv2 encoded message
bool startReadThread ()
 Starts the receiver thread that handles incomming messages.
bool startSubscriptions ()
 Starts the receiver thread that handles incomming messages.
bool stopReadThread ()
 Stops the receiver thread.
bool stopSubscriptions ()
 Stops the receiver thread.

Protected Attributes

asio::streambuf buffer
std::condition_variable cv_response
std::mutex cv_response_mtx
FirmwareVariant fw_variant
asio::io_service io
 ! io service
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
std::unique_ptr< ReceivedMessagerequest_received
std::atomic_flag running_ = ATOMIC_FLAG_INIT
std::map< msp::ID,
std::shared_ptr
< SubscriptionBase > > 
subscriptions
std::thread thread

Detailed Description

Definition at line 35 of file Client.hpp.


Constructor & Destructor Documentation

Client Constructor.

Parameters:
deviceString describing the path to the serial device
baudrateBaudrate of the connection (default 115200, unnecessary for direct USB connection)

Definition at line 10 of file Client.cpp.

~Client Destructor

Definition at line 16 of file Client.cpp.


Member Function Documentation

bool msp::client::Client::connectPort ( const std::string &  device,
const size_t  baudrate = 115200 
) [protected]

Establish connection to serial device and start read thread.

Returns:
True on success

Definition at line 43 of file Client.cpp.

uint8_t msp::client::Client::crcV1 ( const uint8_t  id,
const ByteVector data 
) const [protected]

crcV1 Computes a checksum for MSPv1 messages

Parameters:
iduint8_t MSP ID
dataPayload which is also part of the checksum
Returns:
uint8_t checksum

Definition at line 241 of file Client.cpp.

uint8_t msp::client::Client::crcV2 ( uint8_t  crc,
const ByteVector data 
) const [protected]

crcV2 Computes a checksum for MSPv2 messages

Parameters:
crcChecksum value from which to start calculations
dataByteVector of data to be wrapped into the checksum
Returns:
uint8_t checksum

Definition at line 269 of file Client.cpp.

uint8_t msp::client::Client::crcV2 ( uint8_t  crc,
const uint8_t &  b 
) const [protected]

crcV2 Computes a checksum for MSPv2 messages

Parameters:
crcChecksum value from which to start calculations
dataSingle byte to use in the checksum calculation
Returns:
uint8_t checksum

Definition at line 276 of file Client.cpp.

Break connection to serial device and stop read thread.

Returns:
True on success

Definition at line 64 of file Client.cpp.

uint8_t msp::client::Client::extractChar ( ) [protected]

Read a single byte from either the buffer or the serial device.

Returns:
byte from buffer or device

Definition at line 188 of file Client.cpp.

std::shared_ptr<SubscriptionBase> msp::client::Client::getSubscription ( const msp::ID id) [inline]

Get pointer to subscription.

Parameters:
idMessage ID
Returns:
Shared pointer to subscription (empty if there was no match)

Definition at line 187 of file Client.hpp.

Query the cached device path.

Returns:
Cached path to device

Definition at line 32 of file Client.cpp.

Query the cached device path.

Returns:
Cached path to device

Definition at line 28 of file Client.cpp.

bool msp::client::Client::hasSubscription ( const msp::ID id) const [inline]

Check if message ID already has a subscription.

Parameters:
idMessage ID
Returns:
True if there is already a matching subscription

Definition at line 178 of file Client.hpp.

Query the system to see if a connection is active.

Returns:
true on success

Definition at line 71 of file Client.cpp.

std::pair< iterator, bool > msp::client::Client::messageReady ( iterator  begin,
iterator  end 
) const [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.

Returns:
std::pair<iterator, bool> indicating where the start the next message check operation and whether the current check was successful

Definition at line 358 of file Client.cpp.

ByteVector msp::client::Client::packMessageV1 ( const msp::ID  id,
const ByteVector data = ByteVector(0) 
) const [protected]

packMessageV1 Packs data ID and data payload into a MSPv1 formatted buffer ready for sending to the serial device

Parameters:
idmsp::ID of the message being packed
dataOptional binary payload to be packed into the outbound buffer
Returns:
ByteVector of full MSPv1 message ready for sending

Definition at line 228 of file Client.cpp.

ByteVector msp::client::Client::packMessageV2 ( const msp::ID  id,
const ByteVector data = ByteVector(0) 
) const [protected]

packMessageV2 Packs data ID and data payload into a MSPv2 formatted buffer ready for sending to the serial device

Parameters:
idmsp::ID of the message being packed
dataOptional binary payload to be packed into the outbound buffer
Returns:
ByteVector of full MSPv2 message ready for sending

Definition at line 249 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.

Parameters:
ecASIO error code
bytes_transferredNumber of byte available for processing

Definition at line 289 of file Client.cpp.

processOneMessageV1 Iterates over characters in the ASIO buffer to identify and unpack a MSPv1 encoded message

Returns:
ReceivedMessage data structure containing the results of unpacking

Definition at line 399 of file Client.cpp.

processOneMessageV2 Iterates over characters in the ASIO buffer to identify and unpack a MSPv2 encoded message

Returns:
ReceivedMessage data structure containing the results of unpacking

Definition at line 446 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.

Parameters:
idMessage ID
dataRaw data (default zero length, meaning no data to send outbound)
Returns:
true on success

Definition at line 198 of file Client.cpp.

bool msp::client::Client::sendData ( const msp::ID  id,
const ByteVectorUptr &&  data 
) [inline]

Send an ID and payload to the flight controller.

Parameters:
idMessage ID
dataUnique pointer to data. May be empty if there is no data to send
Returns:
true on success

Definition at line 217 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.

Parameters:
messageReference to a Message-derived object to be sent/recieved.
timeoutMaximum 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.

Send a message, but do not wait for any response.

Parameters:
messageReference to a Message-derived object to be sent

Definition at line 176 of file Client.cpp.

Set the verbosity of the output.

Parameters:
levelLoggingLevel matching the desired amount of output (default to WARNING)

Definition at line 18 of file Client.cpp.

Change the device path on the next connect.

Parameters:
devicePath 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.

Parameters:
verVersion of MSP to use
Returns:
True if successful

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.

Returns:
True on success

Definition at line 34 of file Client.cpp.

Starts the receiver thread that handles incomming messages.

Returns:
True on success

Definition at line 73 of file Client.cpp.

Starts the receiver thread that handles incomming messages.

Returns:
True on success

Definition at line 107 of file Client.cpp.

Stop communications with a flight controller.

Returns:
True on success

Definition at line 39 of file Client.cpp.

Stops the receiver thread.

Returns:
True on success

Definition at line 95 of file Client.cpp.

Stops the receiver thread.

Returns:
True on success

Definition at line 115 of file Client.cpp.

template<typename T , typename C , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type>
std::shared_ptr<SubscriptionBase> msp::client::Client::subscribe ( void(C::*)(const T &)  callback,
C *  context,
const double &  tp 
) [inline]

Register callback function that is called when a message of matching ID is received.

Parameters:
callbackPointer to callback function (class method)
contextObject containing callback method
tpPeriod of timer that will send subscribed requests (in seconds).
Returns:
pointer to subscription that is added to internal list

Definition at line 131 of file Client.hpp.

template<typename T , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type>
std::shared_ptr<SubscriptionBase> msp::client::Client::subscribe ( const std::function< void(const T &)> &  recv_callback,
const double &  tp 
) [inline]

Register callback function that is called when a message of matching ID is received.

Parameters:
recv_callbackFunction to be called upon receipt of message
tpPeriod of timer that will send subscribed requests (in seconds).
Returns:
pointer to subscription that is added to internal list

Definition at line 147 of file Client.hpp.


Member Data Documentation

asio::streambuf msp::client::Client::buffer [protected]

Definition at line 337 of file Client.hpp.

std::condition_variable msp::client::Client::cv_response [protected]

Definition at line 344 of file Client.hpp.

std::mutex msp::client::Client::cv_response_mtx [protected]

Definition at line 345 of file Client.hpp.

Definition at line 362 of file Client.hpp.

asio::io_service msp::client::Client::io [protected]

! io service

Definition at line 335 of file Client.hpp.

Definition at line 358 of file Client.hpp.

Definition at line 361 of file Client.hpp.

std::mutex msp::client::Client::mutex_buffer [protected]

Definition at line 347 of file Client.hpp.

std::mutex msp::client::Client::mutex_response [protected]

Definition at line 346 of file Client.hpp.

std::mutex msp::client::Client::mutex_send [protected]

Definition at line 348 of file Client.hpp.

Definition at line 354 of file Client.hpp.

asio::serial_port msp::client::Client::port [protected]

! port for serial device

Definition at line 336 of file Client.hpp.

Definition at line 351 of file Client.hpp.

std::atomic_flag msp::client::Client::running_ = ATOMIC_FLAG_INIT [protected]

Definition at line 341 of file Client.hpp.

std::map<msp::ID, std::shared_ptr<SubscriptionBase> > msp::client::Client::subscriptions [protected]

Definition at line 355 of file Client.hpp.

std::thread msp::client::Client::thread [protected]

Definition at line 340 of file Client.hpp.


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


msp
Author(s): Christian Rauch
autogenerated on Thu Jun 20 2019 19:40:38