From 9f2375ad93e7b695709420fd550d7bed874b96eb Mon Sep 17 00:00:00 2001 From: Mike Purvis Date: Mon, 2 Mar 2020 16:37:13 -0500 Subject: [PATCH] Port rosserial_server to Boost 1.71. --- .../include/rosserial_server/async_read_buffer.h | 4 ++++ .../include/rosserial_server/udp_stream.h | 15 +++++++++------ 2 files changed, 13 insertions(+), 6 deletions(-) diff --git a/rosserial_server/include/rosserial_server/async_read_buffer.h b/rosserial_server/include/rosserial_server/async_read_buffer.h index 1e30d978c..e53f23e86 100644 --- a/rosserial_server/include/rosserial_server/async_read_buffer.h +++ b/rosserial_server/include/rosserial_server/async_read_buffer.h @@ -166,7 +166,11 @@ class AsyncReadBuffer // 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. +#if BOOST_VERSION >= 107000 + boost::asio::post(stream_.get_executor(), boost::bind(read_success_callback_, stream)); +#else stream_.get_io_service().post(boost::bind(read_success_callback_, stream)); +#endif // Resetting these values clears our state so that we know there isn't a callback pending. read_requested_bytes_ = 0; diff --git a/rosserial_server/include/rosserial_server/udp_stream.h b/rosserial_server/include/rosserial_server/udp_stream.h index 8e4bb0b7e..30034cbfc 100644 --- a/rosserial_server/include/rosserial_server/udp_stream.h +++ b/rosserial_server/include/rosserial_server/udp_stream.h @@ -48,7 +48,9 @@ namespace rosserial_server { using boost::asio::ip::udp; +#if BOOST_VERSION < 107000 using boost::asio::handler_type; +#endif class UdpStream : public udp::socket @@ -62,9 +64,11 @@ class UdpStream : public udp::socket { 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); + + udp::socket::bind(server_endpoint, ec); boost::asio::detail::throw_error(ec, "bind"); client_endpoint_ = client_endpoint; @@ -84,9 +88,8 @@ class UdpStream : public udp::socket boost::asio::async_completion init(handler); - this->get_service().async_send_to( - this->get_implementation(), buffers, client_endpoint_, 0, - init.completion_handler); + udp::socket::async_send_to( + buffers, client_endpoint_, 0, init.completion_handler); return init.result.get(); #else @@ -110,7 +113,7 @@ class UdpStream : public udp::socket boost::asio::async_completion init(handler); - this->get_service().async_receive(this->get_implementation(), + udp::socket::async_receive( buffers, 0, init.completion_handler); return init.result.get();