summaryrefslogtreecommitdiff
blob: cbf106fc9acdb0ff67c45175bf8e63508600b822 (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
Index: rosserial_server/include/rosserial_server/async_read_buffer.h
===================================================================
--- rosserial_server.orig/include/rosserial_server/async_read_buffer.h
+++ rosserial_server/include/rosserial_server/async_read_buffer.h
@@ -166,7 +166,7 @@ private:
 
     // Post the callback rather than executing it here so, so that we have a chance to do the cleanup
     // below prior to it actually getting run, in the event that the callback queues up another read.
-    stream_.get_io_service().post(boost::bind(read_success_callback_, stream));
+    static_cast<boost::asio::io_service&>(stream_.get_executor().context()).post(boost::bind(read_success_callback_, stream));
 
     // Resetting these values clears our state so that we know there isn't a callback pending.
     read_requested_bytes_ = 0;
Index: rosserial_server/include/rosserial_server/udp_stream.h
===================================================================
--- rosserial_server.orig/include/rosserial_server/udp_stream.h
+++ rosserial_server/include/rosserial_server/udp_stream.h
@@ -48,7 +48,6 @@ namespace rosserial_server
 {
 
 using boost::asio::ip::udp;
-using boost::asio::handler_type;
 
 
 class UdpStream : public udp::socket
@@ -62,9 +61,9 @@ public:
   {
     boost::system::error_code ec;
     const protocol_type protocol = server_endpoint.protocol();
-    this->get_service().open(this->get_implementation(), protocol, ec);
+    udp::socket::open(protocol, ec);
     boost::asio::detail::throw_error(ec, "open");
-    this->get_service().bind(this->get_implementation(), server_endpoint, ec);
+    bind(server_endpoint, ec);
     boost::asio::detail::throw_error(ec, "bind");
 
     client_endpoint_ = client_endpoint;
@@ -76,6 +75,8 @@ public:
   async_write_some(const ConstBufferSequence& buffers,
       BOOST_ASIO_MOVE_ARG(WriteHandler) handler)
   {
+    return async_send(buffers, handler);
+#if 0
     // If you get an error on the following line it means that your handler does
     // not meet the documented type requirements for a WriteHandler.
     BOOST_ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
@@ -94,6 +95,7 @@ public:
         this->get_implementation(), buffers, client_endpoint_, 0,
         BOOST_ASIO_MOVE_CAST(WriteHandler)(handler));
 #endif
+#endif
   }
 
   template <typename MutableBufferSequence, typename ReadHandler>
@@ -102,6 +104,8 @@ public:
   async_read_some(const MutableBufferSequence& buffers,
       BOOST_ASIO_MOVE_ARG(ReadHandler) handler)
   {
+    return async_receive(buffers, handler);
+#if 0
     // If you get an error on the following line it means that your handler does
     // not meet the documented type requirements for a ReadHandler.
     BOOST_ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
@@ -119,6 +123,7 @@ public:
         this->get_implementation(), buffers, client_endpoint_, 0,
         BOOST_ASIO_MOVE_CAST(ReadHandler)(handler));
 #endif
+#endif
   }
 
 private: