summarylogtreecommitdiffstats
path: root/io-service.patch
blob: 2ba97de129e8f062a6c133d128780a45f4892c81 (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
--- async_read_buffer.h.orig	2019-11-28 22:48:02.933056047 -0500
+++ async_read_buffer.h	2019-11-28 22:52:40.829715275 -0500
@@ -38,6 +38,12 @@
 #include <boost/asio.hpp>
 #include <boost/function.hpp>
 
+#if BOOST_VERSION >= 107000
+#define GET_IO_SERVICE(s) ((boost::asio::io_context&)(s).get_executor().context())
+#else
+#define GET_IO_SERVICE(s) ((s).get_io_service())
+#endif
+
 #include <ros/ros.h>
 
 namespace rosserial_server
@@ -166,7 +172,7 @@
 
     // 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));
+    GET_IO_SERVICE(stream_).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;