35 #ifndef ROSSERIAL_SERVER_UDP_STREAM_H
36 #define ROSSERIAL_SERVER_UDP_STREAM_H
39 #include <boost/bind.hpp>
40 #include <boost/asio.hpp>
50 using boost::asio::ip::udp;
51 #if BOOST_VERSION < 107000
52 using boost::asio::handler_type;
59 explicit UdpStream(boost::asio::io_service& io_service) : udp::socket(io_service)
63 void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
65 boost::system::error_code ec;
66 const protocol_type protocol = server_endpoint.protocol();
68 udp::socket::open(protocol, ec);
69 boost::asio::detail::throw_error(ec,
"open");
71 udp::socket::bind(server_endpoint, ec);
72 boost::asio::detail::throw_error(ec,
"bind");
77 template <
typename ConstBufferSequence,
typename WriteHandler>
79 void (boost::system::error_code, std::size_t))
80 async_write_some(
const ConstBufferSequence& buffers,
85 BOOST_ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
86 #if (BOOST_VERSION >= 106600)
88 boost::asio::async_completion<WriteHandler,
89 void (boost::system::error_code, std::size_t)>
init(handler);
91 udp::socket::async_send_to(
94 return init.result.get();
96 return this->get_service().async_send_to(
98 BOOST_ASIO_MOVE_CAST(WriteHandler)(handler));
102 template <
typename MutableBufferSequence,
typename ReadHandler>
104 void (boost::system::error_code, std::size_t))
105 async_read_some(
const MutableBufferSequence& buffers,
110 BOOST_ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
111 #if (BOOST_VERSION >= 106600)
113 boost::asio::async_completion<ReadHandler,
114 void (boost::system::error_code, std::size_t)>
init(handler);
116 udp::socket::async_receive(
117 buffers, 0,
init.completion_handler);
119 return init.result.get();
121 return this->get_service().async_receive_from(
123 BOOST_ASIO_MOVE_CAST(ReadHandler)(handler));
133 #endif // ROSSERIAL_SERVER_UDP_STREAM_H