udp_stream.h
Go to the documentation of this file.
1 
35 #ifndef ROSSERIAL_SERVER_UDP_STREAM_H
36 #define ROSSERIAL_SERVER_UDP_STREAM_H
37 
38 #include <iostream>
39 #include <boost/bind.hpp>
40 #include <boost/asio.hpp>
41 
42 #include <ros/ros.h>
43 
45 
46 
47 namespace rosserial_server
48 {
49 
50 using boost::asio::ip::udp;
51 #if BOOST_VERSION < 107000
52 using boost::asio::handler_type;
53 #endif
54 
55 
56 class UdpStream : public udp::socket
57 {
58 public:
59  explicit UdpStream(boost::asio::io_service& io_service) : udp::socket(io_service)
60  {
61  }
62 
63  void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
64  {
65  boost::system::error_code ec;
66  const protocol_type protocol = server_endpoint.protocol();
67 
68  udp::socket::open(protocol, ec);
69  boost::asio::detail::throw_error(ec, "open");
70 
71  udp::socket::bind(server_endpoint, ec);
72  boost::asio::detail::throw_error(ec, "bind");
73 
74  client_endpoint_ = client_endpoint;
75  }
76 
77  template <typename ConstBufferSequence, typename WriteHandler>
78  BOOST_ASIO_INITFN_RESULT_TYPE(WriteHandler,
79  void (boost::system::error_code, std::size_t))
80  async_write_some(const ConstBufferSequence& buffers,
81  BOOST_ASIO_MOVE_ARG(WriteHandler) handler)
82  {
83  // If you get an error on the following line it means that your handler does
84  // not meet the documented type requirements for a WriteHandler.
85  BOOST_ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
86 #if (BOOST_VERSION >= 106600)
87  // See: http://www.boost.org/doc/libs/1_66_0/doc/html/boost_asio/net_ts.html
88  boost::asio::async_completion<WriteHandler,
89  void (boost::system::error_code, std::size_t)> init(handler);
90 
91  udp::socket::async_send_to(
92  buffers, client_endpoint_, 0, init.completion_handler);
93 
94  return init.result.get();
95 #else
96  return this->get_service().async_send_to(
97  this->get_implementation(), buffers, client_endpoint_, 0,
98  BOOST_ASIO_MOVE_CAST(WriteHandler)(handler));
99 #endif
100  }
101 
102  template <typename MutableBufferSequence, typename ReadHandler>
103  BOOST_ASIO_INITFN_RESULT_TYPE(ReadHandler,
104  void (boost::system::error_code, std::size_t))
105  async_read_some(const MutableBufferSequence& buffers,
106  BOOST_ASIO_MOVE_ARG(ReadHandler) handler)
107  {
108  // If you get an error on the following line it means that your handler does
109  // not meet the documented type requirements for a ReadHandler.
110  BOOST_ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
111 #if (BOOST_VERSION >= 106600)
112  // See: http://www.boost.org/doc/libs/1_66_0/doc/html/boost_asio/net_ts.html
113  boost::asio::async_completion<ReadHandler,
114  void (boost::system::error_code, std::size_t)> init(handler);
115 
116  udp::socket::async_receive(
117  buffers, 0, init.completion_handler);
118 
119  return init.result.get();
120 #else
121  return this->get_service().async_receive_from(
122  this->get_implementation(), buffers, client_endpoint_, 0,
123  BOOST_ASIO_MOVE_CAST(ReadHandler)(handler));
124 #endif
125  }
126 
127 private:
128  udp::endpoint client_endpoint_;
129 };
130 
131 } // namespace
132 
133 #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)
Definition: udp_stream.h:59
void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
Definition: udp_stream.h:63
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)
Definition: udp_stream.h:81
udp::endpoint client_endpoint_
Definition: udp_stream.h:128
BOOST_ASIO_MOVE_ARG(ReadHandler) handler)
Definition: udp_stream.h:106


rosserial_server
Author(s): Mike Purvis
autogenerated on Mon Feb 28 2022 23:35:31