Go to the documentation of this file.00001
00041 #pragma once
00042
00043 #include <cstdlib>
00044 #include <iostream>
00045 #include <boost/bind.hpp>
00046 #include <boost/asio.hpp>
00047 #include <boost/signals2/signal.hpp>
00048 #include <boost/thread/mutex.hpp>
00049
00050 #include <ros/console.h>
00051
00053 class Any_Session
00054 {
00055 public:
00057 typedef boost::signals2::signal<void (const char *data, const size_t size, Any_Session *writer)> SIG_ON_DATA;
00058
00060 Any_Session(SIG_ON_DATA &cb)
00061 : on_data_(cb)
00062 {
00063 }
00064
00065 virtual ~Any_Session() {}
00066
00068 virtual void write(const std::string &buffer)=0;
00069
00070 protected:
00071
00072 SIG_ON_DATA &on_data_;
00073 };
00074
00075
00077 class TCP_Session : public Any_Session
00078 {
00079 public:
00080
00081 TCP_Session(boost::asio::io_service& io_service, SIG_ON_DATA &cb)
00082 : Any_Session(cb), socket_(io_service)
00083 {
00084 }
00085
00086 virtual ~TCP_Session() {
00087 }
00088
00090 boost::asio::ip::tcp::socket& socket()
00091 {
00092 return socket_;
00093 }
00094
00095 virtual bool connect(const std::string &path, const std::string &service)
00096 {
00097 boost::asio::ip::tcp::resolver resolver(socket_.get_io_service());
00098 boost::asio::ip::tcp::resolver::query query(path, service);
00099 boost::asio::ip::tcp::resolver::iterator endpoint_iterator = resolver.resolve(query);
00100 boost::asio::ip::tcp::resolver::iterator end;
00101
00102 while (endpoint_iterator != end) {
00103 if(connect(*endpoint_iterator))
00104 return true;
00105 }
00106
00107 return false;
00108 }
00109
00110 virtual bool connect(const boost::asio::ip::tcp::resolver::endpoint_type &ep)
00111 {
00112 close();
00113
00114 boost::system::error_code error = boost::asio::error::host_not_found;
00115 socket_.connect(ep, error);
00116 if (error) {
00117 ROS_ERROR("connecting failed");
00118 return false;
00119 }
00120
00121 socket_.async_read_some(boost::asio::buffer(data_, max_length),
00122 boost::bind(&TCP_Session::handle_read, this,
00123 boost::asio::placeholders::error,
00124 boost::asio::placeholders::bytes_transferred));
00125 return true;
00126 }
00127
00128 virtual void close() {
00129 if(socket_.is_open()) socket_.close();
00130 boost::mutex::scoped_lock lock(mtx_);
00131 }
00132
00133 protected:
00134
00136 virtual void write(const std::string &buffer) {
00137 boost::asio::async_write(socket_,
00138 boost::asio::buffer( buffer ),
00139 boost::bind(&TCP_Session::handle_write, this,
00140 boost::asio::placeholders::error));
00141 }
00142 virtual void write(const std::vector<char> &buffer) {
00143 boost::asio::async_write(socket_,
00144 boost::asio::buffer( buffer ),
00145 boost::bind(&TCP_Session::handle_write, this,
00146 boost::asio::placeholders::error));
00147 }
00148
00150 virtual void write(const boost::asio::mutable_buffers_1 &buffer) {
00151 boost::asio::async_write(socket_,
00152 buffer,
00153 boost::bind(&TCP_Session::handle_write, this,
00154 boost::asio::placeholders::error));
00155 }
00156
00157 private:
00158
00160 void handle_read(const boost::system::error_code& error,
00161 size_t bytes_transferred)
00162 {
00163
00164
00165 if (!error)
00166 {
00167 on_data_(data_, bytes_transferred, this);
00168 }
00169 else
00170 {
00171 ROS_ERROR("error while reading from socket");
00172 delete this;
00173 }
00174
00175 if(socket_.is_open())
00176 socket_.async_read_some(boost::asio::buffer(data_, max_length),
00177 boost::bind(&TCP_Session::handle_read, this,
00178 boost::asio::placeholders::error,
00179 boost::asio::placeholders::bytes_transferred));
00180 }
00181
00183 void handle_write(const boost::system::error_code& error)
00184 {
00185
00186
00187 if (error)
00188 {
00189 ROS_ERROR("error while writing to socket");
00190 delete this;
00191 }
00192 }
00193
00194 protected:
00195 boost::asio::ip::tcp::socket socket_;
00196 enum { max_length = 4096 };
00197 char data_[max_length];
00198 boost::mutex mtx_;
00199 };