tcp_server.h
Go to the documentation of this file.
1 
34 #ifndef ROSSERIAL_SERVER_TCP_SERVER_H
35 #define ROSSERIAL_SERVER_TCP_SERVER_H
36 
37 #include <iostream>
38 #include <boost/bind.hpp>
39 #include <boost/asio.hpp>
40 
41 #include <ros/ros.h>
42 
44 
45 
46 namespace rosserial_server
47 {
48 
49 using boost::asio::ip::tcp;
50 
51 template< typename Session = rosserial_server::Session<tcp::socket> >
52 class TcpServer
53 {
54 public:
55  TcpServer(boost::asio::io_service& io_service, short port)
56  : io_service_(io_service),
57  acceptor_(io_service, tcp::endpoint(tcp::v4(), port))
58  {
59  start_accept();
60  }
61 
62 private:
63  void start_accept()
64  {
65  Session* new_session = new Session(io_service_);
66  acceptor_.async_accept(new_session->socket(),
67  boost::bind(&TcpServer::handle_accept, this, new_session,
68  boost::asio::placeholders::error));
69  }
70 
71  void handle_accept(Session* new_session,
72  const boost::system::error_code& error)
73  {
74  if (!error)
75  {
76  new_session->start();
77  }
78  else
79  {
80  delete new_session;
81  }
82 
83  start_accept();
84  }
85 
86  boost::asio::io_service& io_service_;
87  tcp::acceptor acceptor_;
88 };
89 
90 } // namespace
91 
92 #endif // ROSSERIAL_SERVER_TCP_SERVER_H
TcpServer(boost::asio::io_service &io_service, short port)
Definition: tcp_server.h:55
Class representing a session between this node and a templated rosserial client.
boost::asio::io_service & io_service_
Definition: tcp_server.h:86
void handle_accept(Session *new_session, const boost::system::error_code &error)
Definition: tcp_server.h:71


rosserial_server
Author(s): Mike Purvis
autogenerated on Mon Jun 10 2019 14:53:36