Client.hpp
Go to the documentation of this file.
00001 #ifndef CLIENT_HPP
00002 #define CLIENT_HPP
00003 
00004 #include <asio.hpp>
00005 #include <condition_variable>
00006 #include <functional>
00007 #include <map>
00008 #include <mutex>
00009 #include <string>
00010 #include <thread>
00011 #include "ByteVector.hpp"
00012 #include "FirmwareVariants.hpp"
00013 #include "Message.hpp"
00014 #include "Subscription.hpp"
00015 
00016 namespace msp {
00017 namespace client {
00018 
00019 typedef asio::buffers_iterator<asio::streambuf::const_buffers_type> iterator;
00020 
00021 enum LoggingLevel { SILENT, WARNING, INFO, DEBUG };
00022 
00023 enum MessageStatus {
00024     OK,       // no errors
00025     FAIL_ID,  // message ID is unknown
00026     FAIL_CRC  // wrong CRC
00027 };
00028 
00029 struct ReceivedMessage {
00030     msp::ID id;
00031     ByteVector payload;
00032     MessageStatus status;
00033 };
00034 
00035 class Client {
00036 public:
00043     Client();
00044 
00048     ~Client();
00049 
00055     void setLoggingLevel(const LoggingLevel& level);
00056 
00062     bool setVersion(const int& ver);
00063 
00068     int getVersion() const;
00069 
00074     void setVariant(const FirmwareVariant& v);
00075 
00080     FirmwareVariant getVariant() const;
00081 
00086     bool start(const std::string& device, const size_t baudrate = 115200);
00087 
00092     bool stop();
00093 
00098     bool isConnected() const;
00099 
00111     bool sendMessage(msp::Message& message, const double& timeout = 0);
00112 
00117     bool sendMessageNoWait(const msp::Message& message);
00118 
00128     template <typename T, typename C,
00129               class = typename std::enable_if<
00130                   std::is_base_of<msp::Message, T>::value>::type>
00131     std::shared_ptr<SubscriptionBase> subscribe(void (C::*callback)(const T&),
00132                                                 C* context, const double& tp) {
00133         return subscribe<T>(std::bind(callback, context, std::placeholders::_1),
00134                             tp);
00135     }
00136 
00145     template <typename T, class = typename std::enable_if<
00146                               std::is_base_of<msp::Message, T>::value>::type>
00147     std::shared_ptr<SubscriptionBase> subscribe(
00148         const std::function<void(const T&)>& recv_callback, const double& tp) {
00149         // validate the period
00150         if(!(tp >= 0.0)) throw std::runtime_error("Period must be positive!");
00151 
00152         // get the id of the message in question
00153         const msp::ID id = T(fw_variant).id();
00154         if(log_level_ >= INFO)
00155             std::cout << "SUBSCRIBING TO " << id << std::endl;
00156 
00157         // generate the callback for sending messages
00158         std::function<bool(const Message&)> send_callback =
00159             std::bind(&Client::sendMessageNoWait, this, std::placeholders::_1);
00160 
00161         // create a shared pointer to a new Subscription and set all properties
00162         auto subscription = std::make_shared<Subscription<T>>(
00163             recv_callback, send_callback, std::make_unique<T>(fw_variant), tp);
00164 
00165         // gonna modify the subscription map, so lock the mutex
00166         std::lock_guard<std::mutex> lock(mutex_subscriptions);
00167 
00168         // move the new subscription into the subscription map
00169         subscriptions.emplace(id, std::move(subscription));
00170         return subscriptions[id];
00171     }
00172 
00178     bool hasSubscription(const msp::ID& id) const {
00179         return (subscriptions.count(id) == 1);
00180     }
00181 
00187     std::shared_ptr<SubscriptionBase> getSubscription(const msp::ID& id) {
00188         return subscriptions.at(id);
00189     }
00190 
00198     void processOneMessage(const asio::error_code& ec,
00199                            const std::size_t& bytes_transferred);
00200 
00208     bool sendData(const msp::ID id, const ByteVector& data = ByteVector(0));
00209 
00217     bool sendData(const msp::ID id, const ByteVectorUptr&& data) {
00218         if(!data) return sendData(id);
00219         return sendData(id, *data);
00220     }
00221 
00222 protected:
00227     bool connectPort(const std::string& device, const size_t baudrate = 115200);
00228 
00233     bool disconnectPort();
00234 
00239     bool startReadThread();
00240 
00245     bool stopReadThread();
00246 
00251     bool startSubscriptions();
00252 
00257     bool stopSubscriptions();
00258 
00263     uint8_t extractChar();
00264 
00272     std::pair<iterator, bool> messageReady(iterator begin, iterator end) const;
00273 
00280     ReceivedMessage processOneMessageV1();
00281 
00288     ReceivedMessage processOneMessageV2();
00289 
00297     ByteVector packMessageV1(const msp::ID id,
00298                              const ByteVector& data = ByteVector(0)) const;
00299 
00306     uint8_t crcV1(const uint8_t id, const ByteVector& data) const;
00307 
00315     ByteVector packMessageV2(const msp::ID id,
00316                              const ByteVector& data = ByteVector(0)) const;
00317 
00324     uint8_t crcV2(uint8_t crc, const ByteVector& data) const;
00325 
00332     uint8_t crcV2(uint8_t crc, const uint8_t& b) const;
00333 
00334 protected:
00335     asio::io_service io;     
00336     asio::serial_port port;  
00337     asio::streambuf buffer;
00338 
00339     // read thread management
00340     std::thread thread;
00341     std::atomic_flag running_ = ATOMIC_FLAG_INIT;
00342 
00343     // thread safety and synchronization
00344     std::condition_variable cv_response;
00345     std::mutex cv_response_mtx;
00346     std::mutex mutex_response;
00347     std::mutex mutex_buffer;
00348     std::mutex mutex_send;
00349 
00350     // holder for received data
00351     std::unique_ptr<ReceivedMessage> request_received;
00352 
00353     // subscription management
00354     std::mutex mutex_subscriptions;
00355     std::map<msp::ID, std::shared_ptr<SubscriptionBase>> subscriptions;
00356 
00357     // debugging
00358     LoggingLevel log_level_;
00359 
00360     // reference values
00361     int msp_ver_;
00362     FirmwareVariant fw_variant;
00363 };
00364 
00365 }  // namespace client
00366 }  // namespace msp
00367 
00368 #endif  // CLIENT_HPP


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