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 #include "rosserial_server/session.h"
00044
00045
00046 namespace rosserial_server
00047 {
00048
00049 using boost::asio::ip::tcp;
00050
00051 template< typename Session = rosserial_server::Session<tcp::socket> >
00052 class TcpServer
00053 {
00054 public:
00055 TcpServer(boost::asio::io_service& io_service, short port)
00056 : io_service_(io_service),
00057 acceptor_(io_service, tcp::endpoint(tcp::v4(), port))
00058 {
00059 start_accept();
00060 }
00061
00062 private:
00063 void start_accept()
00064 {
00065 Session* new_session = new Session(io_service_);
00066 acceptor_.async_accept(new_session->socket(),
00067 boost::bind(&TcpServer::handle_accept, this, new_session,
00068 boost::asio::placeholders::error));
00069 }
00070
00071 void handle_accept(Session* new_session,
00072 const boost::system::error_code& error)
00073 {
00074 if (!error)
00075 {
00076 new_session->start();
00077 }
00078 else
00079 {
00080 delete new_session;
00081 }
00082
00083 start_accept();
00084 }
00085
00086 boost::asio::io_service& io_service_;
00087 tcp::acceptor acceptor_;
00088 };
00089
00090 }
00091
00092 #endif // ROSSERIAL_SERVER_TCP_SERVER_H