udp_stream.h
Go to the documentation of this file.
00001 
00035 #ifndef ROSSERIAL_SERVER_UDP_STREAM_H
00036 #define ROSSERIAL_SERVER_UDP_STREAM_H
00037 
00038 #include <iostream>
00039 #include <boost/bind.hpp>
00040 #include <boost/asio.hpp>
00041 
00042 #include <ros/ros.h>
00043 
00044 #include "rosserial_server/session.h"
00045 
00046 
00047 namespace rosserial_server
00048 {
00049 
00050 using boost::asio::ip::udp;
00051 using boost::asio::handler_type;
00052 
00053 
00054 class UdpStream : public udp::socket
00055 {
00056 public:
00057   explicit UdpStream(boost::asio::io_service& io_service) : udp::socket(io_service)
00058   {
00059   }
00060 
00061   void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
00062   {
00063     boost::system::error_code ec;
00064     const protocol_type protocol = server_endpoint.protocol();
00065     this->get_service().open(this->get_implementation(), protocol, ec);
00066     boost::asio::detail::throw_error(ec, "open");
00067     this->get_service().bind(this->get_implementation(), server_endpoint, ec);
00068     boost::asio::detail::throw_error(ec, "bind");
00069 
00070     client_endpoint_ = client_endpoint;
00071   }
00072 
00073   template <typename ConstBufferSequence, typename WriteHandler>
00074   BOOST_ASIO_INITFN_RESULT_TYPE(WriteHandler,
00075       void (boost::system::error_code, std::size_t))
00076   async_write_some(const ConstBufferSequence& buffers,
00077       BOOST_ASIO_MOVE_ARG(WriteHandler) handler)
00078   {
00079     // If you get an error on the following line it means that your handler does
00080     // not meet the documented type requirements for a WriteHandler.
00081     BOOST_ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
00082 
00083     return this->get_service().async_send_to(
00084         this->get_implementation(), buffers, client_endpoint_, 0,
00085         BOOST_ASIO_MOVE_CAST(WriteHandler)(handler));
00086   }
00087 
00088   template <typename MutableBufferSequence, typename ReadHandler>
00089   BOOST_ASIO_INITFN_RESULT_TYPE(ReadHandler,
00090       void (boost::system::error_code, std::size_t))
00091   async_read_some(const MutableBufferSequence& buffers,
00092       BOOST_ASIO_MOVE_ARG(ReadHandler) handler)
00093   {
00094     // If you get an error on the following line it means that your handler does
00095     // not meet the documented type requirements for a ReadHandler.
00096     BOOST_ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
00097 
00098     return this->get_service().async_receive_from(
00099         this->get_implementation(), buffers, client_endpoint_, 0,
00100         BOOST_ASIO_MOVE_CAST(ReadHandler)(handler));
00101   }
00102 
00103 private:
00104   udp::endpoint client_endpoint_;
00105 };
00106 
00107 }  // namespace
00108 
00109 #endif  // ROSSERIAL_SERVER_UDP_STREAM_H


rosserial_server
Author(s): Mike Purvis
autogenerated on Sat Oct 7 2017 03:08:51