Go to the documentation of this file.00001 #ifndef CLIENT_HPP
00002 #define CLIENT_HPP
00003
00004 #include <string>
00005 #include <asio.hpp>
00006 #include <thread>
00007 #include <condition_variable>
00008 #include <map>
00009
00010 #include "types.hpp"
00011
00012 namespace msp {
00013
00014 class PeriodicTimer {
00015 public:
00016 typedef unsigned int uint;
00017
00023 PeriodicTimer(const std::function<void()> funct, const double period_seconds);
00024
00028 void start();
00029
00033 void stop();
00034
00039 double getPeriod() {
00040 return period_us.count()/1.e6;
00041 }
00042
00048 void setPeriod(const double period_seconds);
00049
00050 private:
00051 std::shared_ptr<std::thread> thread_ptr;
00052 std::function<void()> funct;
00053 std::chrono::duration<uint, std::micro> period_us;
00054 bool running;
00055 };
00056
00057 }
00058
00059 namespace msp {
00060 namespace client {
00061
00062 class SubscriptionBase {
00063 public:
00064 SubscriptionBase(PeriodicTimer *timer=NULL) : timer(timer) { }
00065
00066 virtual ~SubscriptionBase() {
00067 if(timer!=NULL) { delete timer; }
00068 }
00069
00070 virtual void call(const msp::Request &req) = 0;
00071
00072 bool hasTimer() {
00073
00074 return !(timer->getPeriod()>0);
00075 }
00076
00081 void setTimerPeriod(const double period_seconds) {
00082 timer->setPeriod(period_seconds);
00083 }
00084
00089 void setTimerFrequency(const double rate_hz) {
00090 timer->setPeriod(1.0/rate_hz);
00091 }
00092
00093 protected:
00094 PeriodicTimer *timer;
00095 };
00096
00097 template<typename T, typename C>
00098 class Subscription : public SubscriptionBase {
00099 public:
00100 typedef void(C::*Callback)(const T&);
00101
00102 Subscription(const Callback caller, C *const context_class)
00103 : funct(caller), context(context_class) {
00104 }
00105
00106 Subscription(const Callback caller, C *const context_class, PeriodicTimer *timer)
00107 : SubscriptionBase(timer), funct(caller), context(context_class)
00108 {
00109 this->timer->start();
00110 }
00111
00112 void call(const msp::Request &req) {
00113 (*context.*funct)( dynamic_cast<const T&>(req) );
00114 }
00115
00116 private:
00117 Callback funct;
00118 C *const context;
00119 };
00120
00121 enum MessageStatus {
00122 OK,
00123 FAIL_ID,
00124 FAIL_CRC
00125 };
00126
00127 struct ReceivedMessage {
00128 uint8_t id;
00129 std::vector<uint8_t> data;
00130 MessageStatus status;
00131 };
00132
00133 class Client {
00134 public:
00135 Client();
00136
00137 ~Client();
00138
00139 void setPrintWarnings(const bool warnings) {
00140 print_warnings = warnings;
00141 }
00142
00149 void connect(const std::string &device, const uint baudrate=115200);
00150
00154 void waitForOneMessage();
00155
00156 void waitForOneMessageBlock();
00157
00161 void start();
00162
00166 void stop();
00167
00172 uint8_t read();
00173
00181 bool sendData(const uint8_t id, const ByteVector &data = ByteVector(0));
00182
00189 bool sendRequest(const uint8_t id) {
00190 return sendData(id, ByteVector());
00191 }
00192
00193 bool sendRequest(const msp::ID id) {
00194 return sendData(uint8_t(id), ByteVector());
00195 }
00196
00203 bool sendResponse(const msp::Response &response) {
00204 return sendData(uint8_t(response.id()), response.encode());
00205 }
00206
00215 int request(msp::Request &request, const double timeout = 0);
00216
00226 int request_raw(const uint8_t id, ByteVector &data, const double timeout = 0);
00227
00235 bool respond(const msp::Response &response, const bool wait_ack=true);
00236
00245 bool respond_raw(const uint8_t id, const ByteVector &data, const bool wait_ack=true);
00246
00254 template<typename T, typename C>
00255 SubscriptionBase* subscribe(void (C::*callback)(const T&), C *context, const double tp = 0.0) {
00256
00257 if(!std::is_base_of<msp::Request, T>::value)
00258 throw std::runtime_error("Callback parameter needs to be of Request type!");
00259
00260 if(!(tp>=0.0))
00261 throw std::runtime_error("Period must be positive!");
00262
00263 const msp::ID id = T().id();
00264
00265 std::lock_guard<std::mutex> lock(mutex_callbacks);
00266
00267
00268 if(subscribed_requests.count(id)) { delete subscribed_requests[id]; }
00269 subscribed_requests[id] = new T();
00270
00271
00272 subscriptions[id] = new Subscription<T,C>(callback, context,
00273 new PeriodicTimer(
00274 std::bind(static_cast<bool(Client::*)(msp::ID)>(&Client::sendRequest), this, id),
00275 tp
00276 )
00277 );
00278
00279 return subscriptions[id];
00280 }
00281
00288 bool hasSubscription(const msp::ID& id) {
00289 return (subscriptions.count(id)==1);
00290 }
00291
00297 SubscriptionBase* getSubscription(const msp::ID& id) {
00298 return subscriptions.at(id);
00299 }
00300
00301 void processOneMessage();
00302
00303 private:
00310 uint8_t crc(const uint8_t id, const ByteVector &data);
00311
00312 private:
00313
00314 asio::io_service io;
00315 asio::serial_port port;
00316 asio::streambuf buffer;
00317
00318 std::thread thread;
00319 bool running;
00320 std::condition_variable cv_request;
00321 std::condition_variable cv_ack;
00322 std::mutex mutex_cv_request;
00323 std::mutex mutex_cv_ack;
00324 std::mutex mutex_request;
00325 std::mutex mutex_callbacks;
00326 std::mutex mutex_send;
00327 std::mutex mutex_buffer;
00328
00329 std::unique_ptr<ReceivedMessage> request_received;
00330
00331 std::map<msp::ID, SubscriptionBase*> subscriptions;
00332 std::map<msp::ID, msp::Request*> subscribed_requests;
00333
00334 bool print_warnings;
00335 };
00336
00337 }
00338 }
00339
00340 #endif // CLIENT_HPP