server.h
Go to the documentation of this file.
00001 #ifndef __SS_SERVER_H_
00002 #define __SS_SERVER_H
00003 
00004 #include <stdint.h>
00005 #include <sys/time.h>
00006 #include <pthread.h>
00007 
00008 #include <ros/ros.h>
00009 #include <shared_serial/LxSerial.h>
00010 #include <shared_serial/watchdog.h>
00011 
00012 #include <shared_serial/Connect.h>
00013 #include <shared_serial/Send.h>
00014 #include <shared_serial/SendTo.h>
00015 #include <shared_serial/Recv.h>
00016 #include <shared_serial/SendRecv.h>
00017 #include <shared_serial/Close.h>
00018 #include <shared_serial/Flush.h>
00019 
00020 class SerialServerLock
00021 {
00022   protected:
00023     int socket_, last_socket_;
00024     struct timeval timeout_;
00025     pthread_mutex_t mutex_;
00026     pthread_cond_t condition_;
00027     
00028   public:
00029     SerialServerLock();
00030     
00031     int lock(int socket, float timeout);
00032     void unlock();
00033     void checkTimeout();
00034 };
00035 
00036 class SerialServer
00037 {
00038   protected:
00039     ros::NodeHandle nh_;
00040     ros::ServiceServer connect_service_;
00041     ros::ServiceServer sendto_service_;
00042     ros::ServiceServer recv_service_;
00043     ros::ServiceServer sendrecv_service_;
00044     ros::Subscriber    send_topic_;
00045     ros::Subscriber    close_topic_;
00046     ros::Subscriber    flush_topic_;
00047     
00048     LxSerial serial_port_;
00049     SerialServerLock lock_;
00050     WatchdogThread watchdog_;
00051 
00052   public:
00053     SerialServer() : nh_("~")
00054     {
00055       advertiseServices();
00056       readParameters();
00057     }
00058     ~SerialServer()
00059     {
00060       nh_.shutdown();
00061     }
00062     
00063     void checkTimeout()
00064     {
00065       lock_.checkTimeout();
00066     }
00067     
00068     void kickWatchdog()
00069     {
00070       watchdog_.kick();
00071     }
00072     
00073     void advertiseServices();
00074     void readParameters();
00075     
00076     void callbackSend(const shared_serial::Send::ConstPtr& msg);
00077     void callbackClose(const shared_serial::Close::ConstPtr& msg);
00078     void callbackFlush(const shared_serial::Flush::ConstPtr& msg);
00079     bool callbackConnect(shared_serial::Connect::Request& req, shared_serial::Connect::Response& res);
00080     bool callbackSendTo(shared_serial::SendTo::Request& req, shared_serial::SendTo::Response& res);
00081     bool callbackRecv(shared_serial::Recv::Request& req, shared_serial::Recv::Response& res);
00082     bool callbackSendRecv(shared_serial::SendRecv::Request& req, shared_serial::SendRecv::Response& res);
00083 };
00084 
00085 #endif /* __SS_SERVER_H */


shared_serial
Author(s): Wouter Caarls
autogenerated on Thu Jun 6 2019 19:47:36