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 using boost::asio::handler_type;
52 
53 
54 class UdpStream : public udp::socket
55 {
56 public:
57  explicit UdpStream(boost::asio::io_service& io_service) : udp::socket(io_service)
58  {
59  }
60 
61  void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
62  {
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");
69 
70  client_endpoint_ = client_endpoint;
71  }
72 
73  template <typename ConstBufferSequence, typename WriteHandler>
74  BOOST_ASIO_INITFN_RESULT_TYPE(WriteHandler,
75  void (boost::system::error_code, std::size_t))
76  async_write_some(const ConstBufferSequence& buffers,
77  BOOST_ASIO_MOVE_ARG(WriteHandler) handler)
78  {
79  // If you get an error on the following line it means that your handler does
80  // not meet the documented type requirements for a WriteHandler.
81  BOOST_ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
82 #if (BOOST_VERSION >= 106600)
83  // See: http://www.boost.org/doc/libs/1_66_0/doc/html/boost_asio/net_ts.html
84  boost::asio::async_completion<WriteHandler,
85  void (boost::system::error_code, std::size_t)> init(handler);
86 
87  this->get_service().async_send_to(
88  this->get_implementation(), buffers, client_endpoint_, 0,
89  init.completion_handler);
90 
91  return init.result.get();
92 #else
93  return this->get_service().async_send_to(
94  this->get_implementation(), buffers, client_endpoint_, 0,
95  BOOST_ASIO_MOVE_CAST(WriteHandler)(handler));
96 #endif
97  }
98 
99  template <typename MutableBufferSequence, typename ReadHandler>
100  BOOST_ASIO_INITFN_RESULT_TYPE(ReadHandler,
101  void (boost::system::error_code, std::size_t))
102  async_read_some(const MutableBufferSequence& buffers,
103  BOOST_ASIO_MOVE_ARG(ReadHandler) handler)
104  {
105  // If you get an error on the following line it means that your handler does
106  // not meet the documented type requirements for a ReadHandler.
107  BOOST_ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
108 #if (BOOST_VERSION >= 106600)
109  // See: http://www.boost.org/doc/libs/1_66_0/doc/html/boost_asio/net_ts.html
110  boost::asio::async_completion<ReadHandler,
111  void (boost::system::error_code, std::size_t)> init(handler);
112 
113  this->get_service().async_receive(this->get_implementation(),
114  buffers, 0, init.completion_handler);
115 
116  return init.result.get();
117 #else
118  return this->get_service().async_receive_from(
119  this->get_implementation(), buffers, client_endpoint_, 0,
120  BOOST_ASIO_MOVE_CAST(ReadHandler)(handler));
121 #endif
122  }
123 
124 private:
125  udp::endpoint client_endpoint_;
126 };
127 
128 } // namespace
129 
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)
Definition: udp_stream.h:57
void open(udp::endpoint server_endpoint, udp::endpoint client_endpoint)
Definition: udp_stream.h:61
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:77
udp::endpoint client_endpoint_
Definition: udp_stream.h:125
BOOST_ASIO_MOVE_ARG(ReadHandler) handler)
Definition: udp_stream.h:103


rosserial_server
Author(s): Mike Purvis
autogenerated on Fri Jun 7 2019 22:02:58