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 using boost::asio::handler_type;
57 explicit UdpStream(boost::asio::io_service& io_service) : udp::socket(io_service)
61 void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
63 boost::system::error_code ec;
64 const protocol_type protocol = server_endpoint.protocol();
65 this->get_service().open(this->get_implementation(), protocol, ec);
66 boost::asio::detail::throw_error(ec,
"open");
67 this->get_service().bind(this->get_implementation(), server_endpoint, ec);
68 boost::asio::detail::throw_error(ec,
"bind");
73 template <
typename ConstBufferSequence,
typename WriteHandler>
75 void (boost::system::error_code, std::size_t))
76 async_write_some(
const ConstBufferSequence& buffers,
81 BOOST_ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
82 #if (BOOST_VERSION >= 106600) 84 boost::asio::async_completion<WriteHandler,
85 void (boost::system::error_code, std::size_t)>
init(handler);
87 this->get_service().async_send_to(
89 init.completion_handler);
91 return init.result.get();
93 return this->get_service().async_send_to(
95 BOOST_ASIO_MOVE_CAST(WriteHandler)(handler));
99 template <
typename MutableBufferSequence,
typename ReadHandler>
101 void (boost::system::error_code, std::size_t))
102 async_read_some(
const MutableBufferSequence& buffers,
107 BOOST_ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
108 #if (BOOST_VERSION >= 106600) 110 boost::asio::async_completion<ReadHandler,
111 void (boost::system::error_code, std::size_t)>
init(handler);
113 this->get_service().async_receive(this->get_implementation(),
114 buffers, 0, init.completion_handler);
116 return init.result.get();
118 return this->get_service().async_receive_from(
120 BOOST_ASIO_MOVE_CAST(ReadHandler)(handler));
130 #endif // ROSSERIAL_SERVER_UDP_STREAM_H
void init(const M_string &remappings)
Class representing a session between this node and a templated rosserial client.
UdpStream(boost::asio::io_service &io_service)
void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
BOOST_ASIO_INITFN_RESULT_TYPE(WriteHandler, void(boost::system::error_code, std::size_t)) async_write_some(const ConstBufferSequence &buffers
BOOST_ASIO_MOVE_ARG(WriteHandler) handler)
udp::endpoint client_endpoint_
BOOST_ASIO_MOVE_ARG(ReadHandler) handler)