Go to the documentation of this file.00001
00034 #ifndef ROSSERIAL_SERVER_TCP_SERVER_H
00035 #define ROSSERIAL_SERVER_TCP_SERVER_H
00036
00037 #include <iostream>
00038 #include <boost/bind.hpp>
00039 #include <boost/asio.hpp>
00040
00041 #include <ros/ros.h>
00042
00043 namespace rosserial_server
00044 {
00045
00046 using boost::asio::ip::tcp;
00047
00048 template<typename Session>
00049 class TcpServer
00050 {
00051 public:
00052 TcpServer(boost::asio::io_service& io_service, short port)
00053 : io_service_(io_service),
00054 acceptor_(io_service, tcp::endpoint(tcp::v4(), port))
00055 {
00056 start_accept();
00057 }
00058
00059 private:
00060 void start_accept()
00061 {
00062 Session* new_session = new Session(io_service_);
00063 acceptor_.async_accept(new_session->socket(),
00064 boost::bind(&TcpServer::handle_accept, this, new_session,
00065 boost::asio::placeholders::error));
00066 }
00067
00068 void handle_accept(Session* new_session,
00069 const boost::system::error_code& error)
00070 {
00071 if (!error)
00072 {
00073 new_session->start();
00074 }
00075 else
00076 {
00077 delete new_session;
00078 }
00079
00080 start_accept();
00081 }
00082
00083 boost::asio::io_service& io_service_;
00084 tcp::acceptor acceptor_;
00085 };
00086
00087 }
00088
00089 #endif // ROSSERIAL_SERVER_TCP_SERVER_H