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
|
--- tcp.cpp.old 2019-11-16 23:18:03.959450362 -0500
+++ tcp.cpp 2019-11-16 23:14:48.329447262 -0500
@@ -21,6 +21,13 @@
#include <mavconn/thread_utils.h>
#include <mavconn/tcp.h>
+// Ensure the correct io_service() is called based on boost version
+#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
+
namespace mavconn {
using boost::system::error_code;
@@ -120,7 +127,7 @@
server_channel, conn_id, to_string_ss(server_ep).c_str());
// start recv
- socket.get_io_service().post(std::bind(&MAVConnTCPClient::do_recv, shared_from_this()));
+ GET_IO_SERVICE(socket).post(std::bind(&MAVConnTCPClient::do_recv, shared_from_this()));
}
MAVConnTCPClient::~MAVConnTCPClient()
@@ -166,7 +173,7 @@
tx_q.emplace_back(bytes, length);
}
- socket.get_io_service().post(std::bind(&MAVConnTCPClient::do_send, shared_from_this(), true));
+ GET_IO_SERVICE(socket).post(std::bind(&MAVConnTCPClient::do_send, shared_from_this(), true));
}
void MAVConnTCPClient::send_message(const mavlink_message_t *message)
@@ -188,7 +195,7 @@
tx_q.emplace_back(message);
}
- socket.get_io_service().post(std::bind(&MAVConnTCPClient::do_send, shared_from_this(), true));
+ GET_IO_SERVICE(socket).post(std::bind(&MAVConnTCPClient::do_send, shared_from_this(), true));
}
void MAVConnTCPClient::send_message(const mavlink::Message &message, const uint8_t source_compid)
@@ -208,7 +215,7 @@
tx_q.emplace_back(message, get_status_p(), sys_id, source_compid);
}
- socket.get_io_service().post(std::bind(&MAVConnTCPClient::do_send, shared_from_this(), true));
+ GET_IO_SERVICE(socket).post(std::bind(&MAVConnTCPClient::do_send, shared_from_this(), true));
}
void MAVConnTCPClient::do_recv()
|