Go to the documentation of this file.00001
00034 #include <iostream>
00035 #include <boost/bind.hpp>
00036 #include <boost/asio.hpp>
00037
00038 #include <ros/ros.h>
00039
00040 #include "Session.h"
00041 #include "AsyncOkPoll.h"
00042
00043
00044 using boost::asio::ip::tcp;
00045
00046
00047 template<typename Session>
00048 class TcpServer
00049 {
00050 public:
00051 TcpServer(boost::asio::io_service& io_service, short port)
00052 : io_service_(io_service),
00053 acceptor_(io_service, tcp::endpoint(tcp::v4(), port))
00054 {
00055 start_accept();
00056 }
00057
00058 private:
00059 void start_accept()
00060 {
00061 Session* new_session = new Session(io_service_);
00062 acceptor_.async_accept(new_session->socket(),
00063 boost::bind(&TcpServer::handle_accept, this, new_session,
00064 boost::asio::placeholders::error));
00065 }
00066
00067 void handle_accept(Session* new_session,
00068 const boost::system::error_code& error)
00069 {
00070 if (!error)
00071 {
00072 new_session->start();
00073 }
00074 else
00075 {
00076 delete new_session;
00077 }
00078
00079 start_accept();
00080 }
00081
00082 boost::asio::io_service& io_service_;
00083 tcp::acceptor acceptor_;
00084 };
00085
00086
00087 int main(int argc, char* argv[])
00088 {
00089 boost::asio::io_service io_service;
00090
00091
00092 ros::init(argc, argv, "rosserial_server_socket_node");
00093 ros::NodeHandle nh("~");
00094
00095
00096 ros::AsyncSpinner ros_spinner(1);
00097 ros_spinner.start();
00098
00099
00100 AsyncOkPoll ok_poll(io_service, boost::posix_time::milliseconds(500), ros::ok);
00101
00102
00103 int port;
00104 nh.param<int>("port", port, 11411);
00105 TcpServer< Session<tcp::socket> > s(io_service, port);
00106 std::cout << "Listening on port " << port << "\n";
00107 io_service.run();
00108
00109 return 0;
00110 }