diff --git a/README.md b/README.md
index ebebc31..9698bfb 100644
--- a/README.md
+++ b/README.md
@@ -4,7 +4,6 @@
* scout_bringup: launch and configuration files to start ROS nodes
* scout_base: a ROS wrapper around Scout SDK to monitor and control the robot
-* scout_sdk: Scout SDK customized for ROS
* scout_msgs: scout related message definitions
* (scout_ros: meta package for the Scout robot ROS packages)
diff --git a/readme_zh.md b/readme_zh.md
index 9ae64ef..f01c68b 100644
--- a/readme_zh.md
+++ b/readme_zh.md
@@ -4,13 +4,12 @@
* scout_bringup: launch and configuration files to start ROS nodes
* scout_base: a ROS wrapper around Scout SDK to monitor and control the robot
-* scout_sdk: Scout SDK customized for ROS
* scout_msgs: scout related message definitions
* (scout_ros: meta package for the Scout robot ROS packages)
下图是是整个ros package的一个基本框架说明,或许它可以帮助你理解你理解整个ros package内部是如何工作的,他们之间的是相互联系的。
-其中最底层的是移动机器人底盘,它通过can或者usart实现运行在计算平台的sdK进行基本信息的获取,具体可以根据scout_sdk了解更多信息,进而对scout_sdk,仿真部分是基于Webots,构建起的仿真环境。
+其中最底层的是移动机器人底盘,它通过can或者usart实现运行在计算平台的sdk进行基本信息的获取,具体可以根据wrp_sdk了解更多信息。 仿真部分是基于Webots,构建起的仿真环境。
diff --git a/scout_base/CMakeLists.txt b/scout_base/CMakeLists.txt
index 8e858e2..c68f608 100644
--- a/scout_base/CMakeLists.txt
+++ b/scout_base/CMakeLists.txt
@@ -15,7 +15,7 @@ find_package(catkin REQUIRED COMPONENTS
std_msgs
geometry_msgs
scout_msgs
- scout_sdk
+ wrp_sdk
tf2
tf2_ros
)
@@ -29,7 +29,7 @@ find_package(catkin REQUIRED COMPONENTS
catkin_package(
INCLUDE_DIRS include
LIBRARIES scout_messenger
- CATKIN_DEPENDS scout_msgs roscpp sensor_msgs scout_sdk
+ CATKIN_DEPENDS scout_msgs roscpp sensor_msgs
# DEPENDS Boost
)
diff --git a/scout_base/include/scout_base/scout_messenger.hpp b/scout_base/include/scout_base/scout_messenger.hpp
index aaae791..498e381 100644
--- a/scout_base/include/scout_base/scout_messenger.hpp
+++ b/scout_base/include/scout_base/scout_messenger.hpp
@@ -18,9 +18,9 @@
#include
#include "scout_msgs/ScoutLightCmd.h"
-#include "scout_sdk/scout_base.hpp"
+#include "wrp_sdk/platforms/scout/scout_base.hpp"
-namespace wescore
+namespace westonrobot
{
class ScoutROSMessenger
{
@@ -68,6 +68,6 @@ private:
void LightCmdCallback(const scout_msgs::ScoutLightCmd::ConstPtr &msg);
void PublishOdometryToROS(double linear, double angular, double dt);
};
-} // namespace wescore
+} // namespace westonrobot
#endif /* SCOUT_MESSENGER_HPP */
diff --git a/scout_base/package.xml b/scout_base/package.xml
index e7a1105..fa76a29 100644
--- a/scout_base/package.xml
+++ b/scout_base/package.xml
@@ -19,13 +19,13 @@
roslaunchroslintsensor_msgs
- scout_sdk
+ wrp_sdkcontroller_managergeometry_msgsscout_msgsroscppsensor_msgstopic_tools
- scout_sdk
+ wrp_sdk
diff --git a/scout_base/src/imu_broadcast_node.cpp b/scout_base/src/imu_broadcast_node.cpp
deleted file mode 100644
index 93169fa..0000000
--- a/scout_base/src/imu_broadcast_node.cpp
+++ /dev/null
@@ -1,72 +0,0 @@
-/*
- * imu_broadcast_node.cpp
- *
- * Created on: Oct 02, 2019 19:09
- * Description:
- *
- * Copyright (c) 2019 Ruixiang Du (rdu)
- */
-
-#include
-
-#include
-#include "lcmtypes/wescore.hpp"
-
-#include
-#include
-
-ros::Publisher imu_pub;
-
-struct MessageBroadcaster
-{
- void IMULCMCallback(const lcm::ReceiveBuffer *rbuf, const std::string &chan, const wescore_lcm_msgs::IMU *msg)
- {
- static uint64_t count = 0;
- // std::cout << "imu msg received" << std::endl;
- sensor_msgs::Imu imu_msg;
- imu_msg.header.frame_id = "imu_link";
- imu_msg.header.stamp = ros::Time::now();
- imu_msg.header.seq = count++;
-
- imu_msg.angular_velocity.x = msg->angular_velocity.x;
- imu_msg.angular_velocity.y = msg->angular_velocity.y;
- imu_msg.angular_velocity.z = msg->angular_velocity.z;
-
- imu_msg.linear_acceleration.x = msg->linear_acceleration.x;
- imu_msg.linear_acceleration.y = msg->linear_acceleration.y;
- imu_msg.linear_acceleration.z = msg->linear_acceleration.z;
-
- for (int i = 0; i < 9; ++i)
- {
- imu_msg.orientation_covariance[i] = msg->orientation_covariance[i];
- imu_msg.angular_velocity_covariance[i] = msg->angular_velocity_covariance[i];
- imu_msg.linear_acceleration_covariance[i] = msg->linear_acceleration_covariance[i];
- }
-
- imu_pub.publish(imu_msg);
- }
-};
-
-int main(int argc, char **argv)
-{
- // setup LCM
- lcm::LCM lcm;
-
- if (!lcm.good())
- return 1;
- MessageBroadcaster mb;
- lcm.subscribe("sensor_hub_raw_imu", &MessageBroadcaster::IMULCMCallback, &mb);
-
- // setup ROS node
- ros::init(argc, argv, "imu_broadcast_node");
- ros::NodeHandle nh;
- imu_pub = nh.advertise("imu", 1000);
-
- ROS_INFO("Started broadcasting");
- while (ros::ok())
- {
- lcm.handleTimeout(5);
- }
-
- return 0;
-}
\ No newline at end of file
diff --git a/scout_base/src/scout_base_node.cpp b/scout_base/src/scout_base_node.cpp
index a3b7e05..c2cb104 100644
--- a/scout_base/src/scout_base_node.cpp
+++ b/scout_base/src/scout_base_node.cpp
@@ -5,10 +5,10 @@
#include
#include
-#include "scout_sdk/scout_base.hpp"
+#include "wrp_sdk/platforms/scout/scout_base.hpp"
#include "scout_base/scout_messenger.hpp"
-using namespace wescore;
+using namespace westonrobot;
int main(int argc, char **argv)
{
diff --git a/scout_base/src/scout_messenger.cpp b/scout_base/src/scout_messenger.cpp
index 585299b..02870b0 100644
--- a/scout_base/src/scout_messenger.cpp
+++ b/scout_base/src/scout_messenger.cpp
@@ -13,7 +13,7 @@
#include "scout_msgs/ScoutStatus.h"
-namespace wescore
+namespace westonrobot
{
ScoutROSMessenger::ScoutROSMessenger(ros::NodeHandle *nh) : scout_(nullptr), nh_(nh)
{
@@ -259,4 +259,4 @@ void ScoutROSMessenger::PublishOdometryToROS(double linear, double angular, doub
odom_publisher_.publish(odom_msg);
}
-} // namespace wescore
\ No newline at end of file
+} // namespace westonrobot
\ No newline at end of file
diff --git a/scout_sdk/CHANGELOG.md b/scout_sdk/CHANGELOG.md
deleted file mode 100644
index 622313a..0000000
--- a/scout_sdk/CHANGELOG.md
+++ /dev/null
@@ -1,26 +0,0 @@
-# Changelog for scout_sdk
-
-## 0.4 (2019-09-15)
-------------------
-* Unified implementation of UART/CAN for firmware and SDK
-* Improvements of code organization
-* Contributors: Ruixiang Du
-
-## 0.3 (2019-08-02)
-------------------
-* Added full UART support
-* Contributors: Ruixiang Du
-
-## 0.2 (2019-06-14)
-------------------
-* Deprecated initial serial interface support (new one under development)
-* Added full CAN support
-* Improved multi-threading implementation
-* Contributors: Ruixiang Du
-
-## 0.1 (2019-05-07)
-------------------
-
-* Added basic serial communication support
-* Provided C++ interface, ROS/LCM demo
-* Contributors: Ruixiang Du
diff --git a/scout_sdk/CMakeLists.txt b/scout_sdk/CMakeLists.txt
deleted file mode 100644
index 9074470..0000000
--- a/scout_sdk/CMakeLists.txt
+++ /dev/null
@@ -1,156 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(scout_sdk)
-
-## Compile as C++11, supported in ROS Kinetic and newer
-add_compile_options(-std=c++11)
-
-## Find catkin macros and libraries
-find_package(catkin REQUIRED COMPONENTS
- roscpp
- std_msgs
-)
-
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
-
-## Uncomment this if the package has a setup.py. This macro ensures
-## modules and global scripts declared therein get installed
-## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
-# catkin_python_setup()
-
-################################################
-## Declare ROS messages, services and actions ##
-################################################
-
-## To declare and build messages, services or actions from within this
-## package, follow these steps:
-## * Let MSG_DEP_SET be the set of packages whose message types you use in
-## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
-## * In the file package.xml:
-## * add a build_depend tag for "message_generation"
-## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
-## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
-## but can be declared for certainty nonetheless:
-## * add a exec_depend tag for "message_runtime"
-## * In this file (CMakeLists.txt):
-## * add "message_generation" and every package in MSG_DEP_SET to
-## find_package(catkin REQUIRED COMPONENTS ...)
-## * add "message_runtime" and every package in MSG_DEP_SET to
-## catkin_package(CATKIN_DEPENDS ...)
-## * uncomment the add_*_files sections below as needed
-## and list every .msg/.srv/.action file to be processed
-## * uncomment the generate_messages entry below
-## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
-
-## Generate messages in the 'msg' folder
-# add_message_files(
-# FILES
-# Message1.msg
-# Message2.msg
-# )
-
-## Generate services in the 'srv' folder
-# add_service_files(
-# FILES
-# Service1.srv
-# Service2.srv
-# )
-
-## Generate actions in the 'action' folder
-# add_action_files(
-# FILES
-# Action1.action
-# Action2.action
-# )
-
-## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# DEPENDENCIES
-# std_msgs
-# )
-
-################################################
-## Declare ROS dynamic reconfigure parameters ##
-################################################
-
-## To declare and build dynamic reconfigure parameters within this
-## package, follow these steps:
-## * In the file package.xml:
-## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
-## * In this file (CMakeLists.txt):
-## * add "dynamic_reconfigure" to
-## find_package(catkin REQUIRED COMPONENTS ...)
-## * uncomment the "generate_dynamic_reconfigure_options" section below
-## and list every .cfg file to be processed
-
-## Generate dynamic reconfigure parameters in the 'cfg' folder
-# generate_dynamic_reconfigure_options(
-# cfg/DynReconf1.cfg
-# cfg/DynReconf2.cfg
-# )
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## INCLUDE_DIRS: uncomment this if your package contains header files
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
-catkin_package(
- INCLUDE_DIRS include
- LIBRARIES scout_sdk
- CATKIN_DEPENDS roscpp std_msgs
-# DEPENDS system_lib
-)
-
-###########
-## Build ##
-###########
-
-## Specify additional locations of header files
-include_directories(
- include
- ${catkin_INCLUDE_DIRS}
-)
-
-## Declare a C++ library
-set(SCOUT_BASE_SRC
- src/scout_base.cpp
- src/scout_protocol/scout_can_parser.c
- src/scout_protocol/scout_uart_parser.c
- src/async_io/async_serial.cpp
- src/async_io/async_can.cpp
- src/async_io/asyncio_utils.cpp
-)
-add_library(scout_sdk STATIC ${SCOUT_BASE_SRC})
-set_target_properties(scout_sdk PROPERTIES POSITION_INDEPENDENT_CODE ON)
-target_compile_definitions(scout_sdk PUBLIC "-DASIO_ENABLE_OLD_SERVICES -DASIO_HAS_POSIX_STREAM_DESCRIPTOR")
-target_link_libraries(scout_sdk pthread ${catkin_LIBRARIES})
-target_include_directories(scout_sdk PUBLIC
- $
- $
- $
- PRIVATE src)
-
-#############
-## Install ##
-#############
-
-install(TARGETS scout_sdk
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
-
-install(DIRECTORY include/${PROJECT_NAME}/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})
-
-install(DIRECTORY asio/asio
- DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})
-
-install(FILES asio/asio.hpp
- DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})
-
-install(DIRECTORY scripts
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
\ No newline at end of file
diff --git a/scout_sdk/README.md b/scout_sdk/README.md
deleted file mode 100755
index 1e28c5c..0000000
--- a/scout_sdk/README.md
+++ /dev/null
@@ -1,99 +0,0 @@
-# SDK for AgileX Scout Mobile Base
-
-Copyright (c) 2019 [WestonRobot](https://www.westonrobot.com/)
-
-## Introduction
-
-This software packages provides a C++ interface to communicate with the Scout mobile base, for sending commands to the robot and acquiring the latest robot state. The SDK works on both x86 and ARM platforms.
-
-Generally, you only need to instantiate an object of "class ScoutBase", then use the object to programmatically control the robot. Internally, class ScoutBase manages two background threads, one to process CAN/UART messages of the robot state and accordingly update state variables in the ScoutState data structure, and the other to maintain a 50Hz loop and send the latest command to the robot base. User can iteratively perform tasks in the main thread and check the robot state or set control commands.
-
-Refer to "src/apps/scout_demo" for an example.
-
-## Package Structure
-
-* apps: demo to illustrate how to use the SDK, scout_monitor is a TUI application to monitor states of Scout
-* comm/async_io: manages raw data communication with robot
-* comm/scout_protocol: encoding and decoding of Scout UART/CAN protocols
-* scout_base: interface to send command to robot and receive robot state
-* third_party
- - asio: asynchronous IO management (serial and CAN)
- - googletest: for unit tests only (not required otherwise)
-
-## Setup CAN-To-USB adapter
-
-The instructions work for stm32f0-based adapter with [candleLight](https://github.com/HubertD/candleLight_fw) firmware on a host computer running Linux. (Refer to limitations listed at the bottom for more details.)
-
-1. Enable gs_usb kernel module
- ```
- $ sudo modprobe gs_usb
- ```
-2. Bringup can device
- ```
- $ sudo ip link set can0 up type can bitrate 500000
- ```
-3. If no error occured during the previous steps, you should be able to see the can device now by using command
- ```
- $ ifconfig -a
- ```
-4. Install and use can-utils to test the hardware
- ```
- $ sudo apt install can-utils
- ```
-5. Testing command
- ```
- # receiving data from can0
- $ candump can0
- # send data to can0
- $ cansend can0 001#1122334455667788
- ```
-
-Two scripts inside the "./scripts" folder are provided for easy setup. You can run "./setup_can2usb.bash" for the first-time setup and run "./bringup_can2usb.bash" to bring up the device each time you unplug and re-plug the adapter.
-
-## Build SDK
-
-Install compile tools
-
-```
-$ sudo apt install build-essential cmake
-```
-
-If you want to build the TUI monitor tool, install libncurses
-
-```
-$ sudo apt install libncurses5-dev
-```
-
-Configure and build
-
-```
-$ cd scout_sdk
-$ mkdir build
-$ cd build
-$ cmake ..
-$ make
-```
-
-## Known Limitations
-
-1. The CAN interface requires the hardware to appear as a CAN device in the system. You can use the command "ifconfig" to check the interface status. For example, you may see something like
-
- ```
- can1: flags=193 mtu 16
- unspec 00-00-00-00-00-00-00-00-00-00-00-00-00-00-00-00 txqueuelen 10 (UNSPEC)
- RX packets 4751634 bytes 38013072 (36.2 MiB)
- RX errors 0 dropped 0 overruns 0 frame 0
- TX packets 126269 bytes 1010152 (986.4 KiB)
- TX errors 0 dropped 0 overruns 0 carrier 0 collisions 0
- device interrupt 43
- ```
-
- If you use your own CAN-to-USB adapter, make sure it supports slcan or can be brought up as a native CAN device (for example, CANable https://www.canable.io/). Some adapters may use a custom-defined protocol and appear as a serial device in Linux. In such a case, you will have to translate the byte stream between CAN and UART by yourself. It would be difficult for us to provide support for them since not all manufacturers define this protocol in the same way.
-
-
-
-## Reference
-
-* [CAN command reference in Linux](https://wiki.rdu.im/_pages/Notes/Embedded-System/Linux/can-bus-in-linux.html)
\ No newline at end of file
diff --git a/scout_sdk/asio/asio.hpp b/scout_sdk/asio/asio.hpp
deleted file mode 100644
index 3356df0..0000000
--- a/scout_sdk/asio/asio.hpp
+++ /dev/null
@@ -1,152 +0,0 @@
-//
-// asio.hpp
-// ~~~~~~~~
-//
-// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com)
-//
-// Distributed under the Boost Software License, Version 1.0. (See accompanying
-// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
-//
-
-#ifndef ASIO_HPP
-#define ASIO_HPP
-
-#if defined(_MSC_VER) && (_MSC_VER >= 1200)
-# pragma once
-#endif // defined(_MSC_VER) && (_MSC_VER >= 1200)
-
-#include "asio/associated_allocator.hpp"
-#include "asio/associated_executor.hpp"
-#include "asio/async_result.hpp"
-#include "asio/basic_datagram_socket.hpp"
-#include "asio/basic_deadline_timer.hpp"
-#include "asio/basic_io_object.hpp"
-#include "asio/basic_raw_socket.hpp"
-#include "asio/basic_seq_packet_socket.hpp"
-#include "asio/basic_serial_port.hpp"
-#include "asio/basic_signal_set.hpp"
-#include "asio/basic_socket_acceptor.hpp"
-#include "asio/basic_socket_iostream.hpp"
-#include "asio/basic_socket_streambuf.hpp"
-#include "asio/basic_stream_socket.hpp"
-#include "asio/basic_streambuf.hpp"
-#include "asio/basic_waitable_timer.hpp"
-#include "asio/bind_executor.hpp"
-#include "asio/buffer.hpp"
-#include "asio/buffered_read_stream_fwd.hpp"
-#include "asio/buffered_read_stream.hpp"
-#include "asio/buffered_stream_fwd.hpp"
-#include "asio/buffered_stream.hpp"
-#include "asio/buffered_write_stream_fwd.hpp"
-#include "asio/buffered_write_stream.hpp"
-#include "asio/buffers_iterator.hpp"
-#include "asio/completion_condition.hpp"
-#include "asio/connect.hpp"
-#include "asio/coroutine.hpp"
-#include "asio/datagram_socket_service.hpp"
-#include "asio/deadline_timer_service.hpp"
-#include "asio/deadline_timer.hpp"
-#include "asio/defer.hpp"
-#include "asio/dispatch.hpp"
-#include "asio/error.hpp"
-#include "asio/error_code.hpp"
-#include "asio/execution_context.hpp"
-#include "asio/executor.hpp"
-#include "asio/executor_work_guard.hpp"
-#include "asio/generic/basic_endpoint.hpp"
-#include "asio/generic/datagram_protocol.hpp"
-#include "asio/generic/raw_protocol.hpp"
-#include "asio/generic/seq_packet_protocol.hpp"
-#include "asio/generic/stream_protocol.hpp"
-#include "asio/handler_alloc_hook.hpp"
-#include "asio/handler_continuation_hook.hpp"
-#include "asio/handler_invoke_hook.hpp"
-#include "asio/handler_type.hpp"
-#include "asio/high_resolution_timer.hpp"
-#include "asio/io_context.hpp"
-#include "asio/io_context_strand.hpp"
-#include "asio/io_service.hpp"
-#include "asio/io_service_strand.hpp"
-#include "asio/ip/address.hpp"
-#include "asio/ip/address_v4.hpp"
-#include "asio/ip/address_v4_iterator.hpp"
-#include "asio/ip/address_v4_range.hpp"
-#include "asio/ip/address_v6.hpp"
-#include "asio/ip/address_v6_iterator.hpp"
-#include "asio/ip/address_v6_range.hpp"
-#include "asio/ip/bad_address_cast.hpp"
-#include "asio/ip/basic_endpoint.hpp"
-#include "asio/ip/basic_resolver.hpp"
-#include "asio/ip/basic_resolver_entry.hpp"
-#include "asio/ip/basic_resolver_iterator.hpp"
-#include "asio/ip/basic_resolver_query.hpp"
-#include "asio/ip/host_name.hpp"
-#include "asio/ip/icmp.hpp"
-#include "asio/ip/multicast.hpp"
-#include "asio/ip/resolver_base.hpp"
-#include "asio/ip/resolver_query_base.hpp"
-#include "asio/ip/resolver_service.hpp"
-#include "asio/ip/tcp.hpp"
-#include "asio/ip/udp.hpp"
-#include "asio/ip/unicast.hpp"
-#include "asio/ip/v6_only.hpp"
-#include "asio/is_executor.hpp"
-#include "asio/is_read_buffered.hpp"
-#include "asio/is_write_buffered.hpp"
-#include "asio/local/basic_endpoint.hpp"
-#include "asio/local/connect_pair.hpp"
-#include "asio/local/datagram_protocol.hpp"
-#include "asio/local/stream_protocol.hpp"
-#include "asio/packaged_task.hpp"
-#include "asio/placeholders.hpp"
-#include "asio/posix/basic_descriptor.hpp"
-#include "asio/posix/basic_stream_descriptor.hpp"
-#include "asio/posix/descriptor.hpp"
-#include "asio/posix/descriptor_base.hpp"
-#include "asio/posix/stream_descriptor.hpp"
-#include "asio/posix/stream_descriptor_service.hpp"
-#include "asio/post.hpp"
-#include "asio/raw_socket_service.hpp"
-#include "asio/read.hpp"
-#include "asio/read_at.hpp"
-#include "asio/read_until.hpp"
-#include "asio/seq_packet_socket_service.hpp"
-#include "asio/serial_port.hpp"
-#include "asio/serial_port_base.hpp"
-#include "asio/serial_port_service.hpp"
-#include "asio/signal_set.hpp"
-#include "asio/signal_set_service.hpp"
-#include "asio/socket_acceptor_service.hpp"
-#include "asio/socket_base.hpp"
-#include "asio/steady_timer.hpp"
-#include "asio/strand.hpp"
-#include "asio/stream_socket_service.hpp"
-#include "asio/streambuf.hpp"
-#include "asio/system_context.hpp"
-#include "asio/system_error.hpp"
-#include "asio/system_executor.hpp"
-#include "asio/system_timer.hpp"
-#include "asio/thread.hpp"
-#include "asio/thread_pool.hpp"
-#include "asio/time_traits.hpp"
-#include "asio/use_future.hpp"
-#include "asio/uses_executor.hpp"
-#include "asio/version.hpp"
-#include "asio/wait_traits.hpp"
-#include "asio/waitable_timer_service.hpp"
-#include "asio/windows/basic_handle.hpp"
-#include "asio/windows/basic_object_handle.hpp"
-#include "asio/windows/basic_random_access_handle.hpp"
-#include "asio/windows/basic_stream_handle.hpp"
-#include "asio/windows/object_handle.hpp"
-#include "asio/windows/object_handle_service.hpp"
-#include "asio/windows/overlapped_handle.hpp"
-#include "asio/windows/overlapped_ptr.hpp"
-#include "asio/windows/random_access_handle.hpp"
-#include "asio/windows/random_access_handle_service.hpp"
-#include "asio/windows/stream_handle.hpp"
-#include "asio/windows/stream_handle_service.hpp"
-#include "asio/write.hpp"
-#include "asio/write_at.hpp"
-
-#endif // ASIO_HPP
diff --git a/scout_sdk/asio/asio/associated_allocator.hpp b/scout_sdk/asio/asio/associated_allocator.hpp
deleted file mode 100644
index 8b488bb..0000000
--- a/scout_sdk/asio/asio/associated_allocator.hpp
+++ /dev/null
@@ -1,131 +0,0 @@
-//
-// associated_allocator.hpp
-// ~~~~~~~~~~~~~~~~~~~~~~~~
-//
-// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com)
-//
-// Distributed under the Boost Software License, Version 1.0. (See accompanying
-// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
-//
-
-#ifndef ASIO_ASSOCIATED_ALLOCATOR_HPP
-#define ASIO_ASSOCIATED_ALLOCATOR_HPP
-
-#if defined(_MSC_VER) && (_MSC_VER >= 1200)
-# pragma once
-#endif // defined(_MSC_VER) && (_MSC_VER >= 1200)
-
-#include "asio/detail/config.hpp"
-#include
-#include "asio/detail/type_traits.hpp"
-
-#include "asio/detail/push_options.hpp"
-
-namespace asio {
-namespace detail {
-
-template
-struct associated_allocator_check
-{
- typedef void type;
-};
-
-template
-struct associated_allocator_impl
-{
- typedef E type;
-
- static type get(const T&, const E& e) ASIO_NOEXCEPT
- {
- return e;
- }
-};
-
-template
-struct associated_allocator_impl::type>
-{
- typedef typename T::allocator_type type;
-
- static type get(const T& t, const E&) ASIO_NOEXCEPT
- {
- return t.get_allocator();
- }
-};
-
-} // namespace detail
-
-/// Traits type used to obtain the allocator associated with an object.
-/**
- * A program may specialise this traits type if the @c T template parameter in
- * the specialisation is a user-defined type. The template parameter @c
- * Allocator shall be a type meeting the Allocator requirements.
- *
- * Specialisations shall meet the following requirements, where @c t is a const
- * reference to an object of type @c T, and @c a is an object of type @c
- * Allocator.
- *
- * @li Provide a nested typedef @c type that identifies a type meeting the
- * Allocator requirements.
- *
- * @li Provide a noexcept static member function named @c get, callable as @c
- * get(t) and with return type @c type.
- *
- * @li Provide a noexcept static member function named @c get, callable as @c
- * get(t,a) and with return type @c type.
- */
-template >
-struct associated_allocator
-{
- /// If @c T has a nested type @c allocator_type, T::allocator_type.
- /// Otherwise @c Allocator.
-#if defined(GENERATING_DOCUMENTATION)
- typedef see_below type;
-#else // defined(GENERATING_DOCUMENTATION)
- typedef typename detail::associated_allocator_impl::type type;
-#endif // defined(GENERATING_DOCUMENTATION)
-
- /// If @c T has a nested type @c allocator_type, returns
- /// t.get_allocator(). Otherwise returns @c a.
- static type get(const T& t,
- const Allocator& a = Allocator()) ASIO_NOEXCEPT
- {
- return detail::associated_allocator_impl::get(t, a);
- }
-};
-
-/// Helper function to obtain an object's associated allocator.
-/**
- * @returns associated_allocator::get(t)
- */
-template
-inline typename associated_allocator::type
-get_associated_allocator(const T& t) ASIO_NOEXCEPT
-{
- return associated_allocator::get(t);
-}
-
-/// Helper function to obtain an object's associated allocator.
-/**
- * @returns associated_allocator::get(t, a)
- */
-template
-inline typename associated_allocator::type
-get_associated_allocator(const T& t, const Allocator& a) ASIO_NOEXCEPT
-{
- return associated_allocator::get(t, a);
-}
-
-#if defined(ASIO_HAS_ALIAS_TEMPLATES)
-
-template >
-using associated_allocator_t
- = typename associated_allocator::type;
-
-#endif // defined(ASIO_HAS_ALIAS_TEMPLATES)
-
-} // namespace asio
-
-#include "asio/detail/pop_options.hpp"
-
-#endif // ASIO_ASSOCIATED_ALLOCATOR_HPP
diff --git a/scout_sdk/asio/asio/associated_executor.hpp b/scout_sdk/asio/asio/associated_executor.hpp
deleted file mode 100644
index 4c5c207..0000000
--- a/scout_sdk/asio/asio/associated_executor.hpp
+++ /dev/null
@@ -1,149 +0,0 @@
-//
-// associated_executor.hpp
-// ~~~~~~~~~~~~~~~~~~~~~~~
-//
-// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com)
-//
-// Distributed under the Boost Software License, Version 1.0. (See accompanying
-// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
-//
-
-#ifndef ASIO_ASSOCIATED_EXECUTOR_HPP
-#define ASIO_ASSOCIATED_EXECUTOR_HPP
-
-#if defined(_MSC_VER) && (_MSC_VER >= 1200)
-# pragma once
-#endif // defined(_MSC_VER) && (_MSC_VER >= 1200)
-
-#include "asio/detail/config.hpp"
-#include "asio/detail/type_traits.hpp"
-#include "asio/is_executor.hpp"
-#include "asio/system_executor.hpp"
-
-#include "asio/detail/push_options.hpp"
-
-namespace asio {
-namespace detail {
-
-template
-struct associated_executor_check
-{
- typedef void type;
-};
-
-template
-struct associated_executor_impl
-{
- typedef E type;
-
- static type get(const T&, const E& e) ASIO_NOEXCEPT
- {
- return e;
- }
-};
-
-template
-struct associated_executor_impl::type>
-{
- typedef typename T::executor_type type;
-
- static type get(const T& t, const E&) ASIO_NOEXCEPT
- {
- return t.get_executor();
- }
-};
-
-} // namespace detail
-
-/// Traits type used to obtain the executor associated with an object.
-/**
- * A program may specialise this traits type if the @c T template parameter in
- * the specialisation is a user-defined type. The template parameter @c
- * Executor shall be a type meeting the Executor requirements.
- *
- * Specialisations shall meet the following requirements, where @c t is a const
- * reference to an object of type @c T, and @c e is an object of type @c
- * Executor.
- *
- * @li Provide a nested typedef @c type that identifies a type meeting the
- * Executor requirements.
- *
- * @li Provide a noexcept static member function named @c get, callable as @c
- * get(t) and with return type @c type.
- *
- * @li Provide a noexcept static member function named @c get, callable as @c
- * get(t,e) and with return type @c type.
- */
-template
-struct associated_executor
-{
- /// If @c T has a nested type @c executor_type, T::executor_type.
- /// Otherwise @c Executor.
-#if defined(GENERATING_DOCUMENTATION)
- typedef see_below type;
-#else // defined(GENERATING_DOCUMENTATION)
- typedef typename detail::associated_executor_impl::type type;
-#endif // defined(GENERATING_DOCUMENTATION)
-
- /// If @c T has a nested type @c executor_type, returns
- /// t.get_executor(). Otherwise returns @c ex.
- static type get(const T& t,
- const Executor& ex = Executor()) ASIO_NOEXCEPT
- {
- return detail::associated_executor_impl::get(t, ex);
- }
-};
-
-/// Helper function to obtain an object's associated executor.
-/**
- * @returns associated_executor::get(t)
- */
-template
-inline typename associated_executor::type
-get_associated_executor(const T& t) ASIO_NOEXCEPT
-{
- return associated_executor::get(t);
-}
-
-/// Helper function to obtain an object's associated executor.
-/**
- * @returns associated_executor::get(t, ex)
- */
-template
-inline typename associated_executor::type
-get_associated_executor(const T& t, const Executor& ex,
- typename enable_if::value>::type* = 0) ASIO_NOEXCEPT
-{
- return associated_executor::get(t, ex);
-}
-
-/// Helper function to obtain an object's associated executor.
-/**
- * @returns associated_executor::get(t, ctx.get_executor())
- */
-template
-inline typename associated_executor::type
-get_associated_executor(const T& t, ExecutionContext& ctx,
- typename enable_if::value>::type* = 0) ASIO_NOEXCEPT
-{
- return associated_executor::get(t, ctx.get_executor());
-}
-
-#if defined(ASIO_HAS_ALIAS_TEMPLATES)
-
-template
-using associated_executor_t = typename associated_executor::type;
-
-#endif // defined(ASIO_HAS_ALIAS_TEMPLATES)
-
-} // namespace asio
-
-#include "asio/detail/pop_options.hpp"
-
-#endif // ASIO_ASSOCIATED_EXECUTOR_HPP
diff --git a/scout_sdk/asio/asio/async_result.hpp b/scout_sdk/asio/asio/async_result.hpp
deleted file mode 100644
index 18acdf2..0000000
--- a/scout_sdk/asio/asio/async_result.hpp
+++ /dev/null
@@ -1,221 +0,0 @@
-//
-// async_result.hpp
-// ~~~~~~~~~~~~~~~~
-//
-// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com)
-//
-// Distributed under the Boost Software License, Version 1.0. (See accompanying
-// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
-//
-
-#ifndef ASIO_ASYNC_RESULT_HPP
-#define ASIO_ASYNC_RESULT_HPP
-
-#if defined(_MSC_VER) && (_MSC_VER >= 1200)
-# pragma once
-#endif // defined(_MSC_VER) && (_MSC_VER >= 1200)
-
-#include "asio/detail/config.hpp"
-#include "asio/detail/type_traits.hpp"
-#include "asio/handler_type.hpp"
-
-#include "asio/detail/push_options.hpp"
-
-namespace asio {
-
-/// An interface for customising the behaviour of an initiating function.
-/**
- * The async_result traits class is used for determining:
- *
- * @li the concrete completion handler type to be called at the end of the
- * asynchronous operation;
- *
- * @li the initiating function return type; and
- *
- * @li how the return value of the initiating function is obtained.
- *
- * The trait allows the handler and return types to be determined at the point
- * where the specific completion handler signature is known.
- *
- * This template may be specialised for user-defined completion token types.
- * The primary template assumes that the CompletionToken is the completion
- * handler.
- */
-#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
-template
-#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
-template
-#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
-class async_result
-{
-public:
-#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- /// The concrete completion handler type for the specific signature.
- typedef CompletionToken completion_handler_type;
-
- /// The return type of the initiating function.
- typedef void return_type;
-#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- // For backward compatibility, determine the concrete completion handler type
- // by using the legacy handler_type trait.
- typedef typename handler_type::type
- completion_handler_type;
-
- // For backward compatibility, determine the initiating function return type
- // using the legacy single-parameter version of async_result.
- typedef typename async_result::type return_type;
-#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
-
- /// Construct an async result from a given handler.
- /**
- * When using a specalised async_result, the constructor has an opportunity
- * to initialise some state associated with the completion handler, which is
- * then returned from the initiating function.
- */
- explicit async_result(completion_handler_type& h)
-#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- // No data members to initialise.
-#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- : legacy_result_(h)
-#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- {
- (void)h;
- }
-
- /// Obtain the value to be returned from the initiating function.
- return_type get()
- {
-#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- // Nothing to do.
-#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- return legacy_result_.get();
-#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- }
-
-private:
- async_result(const async_result&) ASIO_DELETED;
- async_result& operator=(const async_result&) ASIO_DELETED;
-
-#if defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- // No data members.
-#else // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
- async_result legacy_result_;
-#endif // defined(ASIO_NO_DEPRECATED) || defined(GENERATING_DOCUMENTATION)
-};
-
-#if !defined(ASIO_NO_DEPRECATED)
-
-/// (Deprecated: Use two-parameter version of async_result.) An interface for
-/// customising the behaviour of an initiating function.
-/**
- * This template may be specialised for user-defined handler types.
- */
-template
-class async_result
-{
-public:
- /// The return type of the initiating function.
- typedef void type;
-
- /// Construct an async result from a given handler.
- /**
- * When using a specalised async_result, the constructor has an opportunity
- * to initialise some state associated with the handler, which is then
- * returned from the initiating function.
- */
- explicit async_result(Handler&)
- {
- }
-
- /// Obtain the value to be returned from the initiating function.
- type get()
- {
- }
-};
-
-#endif // !defined(ASIO_NO_DEPRECATED)
-
-/// Helper template to deduce the handler type from a CompletionToken, capture
-/// a local copy of the handler, and then create an async_result for the
-/// handler.
-template
-struct async_completion
-{
- /// The real handler type to be used for the asynchronous operation.
- typedef typename asio::async_result<
- typename decay::type,
- Signature>::completion_handler_type completion_handler_type;
-
-#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION)
- /// Constructor.
- /**
- * The constructor creates the concrete completion handler and makes the link
- * between the handler and the asynchronous result.
- */
- explicit async_completion(CompletionToken& token)
- : completion_handler(static_cast::value,
- completion_handler_type&, CompletionToken&&>::type>(token)),
- result(completion_handler)
- {
- }
-#else // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION)
- explicit async_completion(typename decay::type& token)
- : completion_handler(token),
- result(completion_handler)
- {
- }
-
- explicit async_completion(const typename decay::type& token)
- : completion_handler(token),
- result(completion_handler)
- {
- }
-#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION)
-
- /// A copy of, or reference to, a real handler object.
-#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION)
- typename conditional<
- is_same::value,
- completion_handler_type&, completion_handler_type>::type completion_handler;
-#else // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION)
- completion_handler_type completion_handler;
-#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION)
-
- /// The result of the asynchronous operation's initiating function.
- async_result::type, Signature> result;
-};
-
-namespace detail {
-
-template
-struct async_result_helper
- : async_result::type, Signature>
-{
-};
-
-} // namespace detail
-} // namespace asio
-
-#include "asio/detail/pop_options.hpp"
-
-#if defined(GENERATING_DOCUMENTATION)
-# define ASIO_INITFN_RESULT_TYPE(ct, sig) \
- void_or_deduced
-#elif defined(_MSC_VER) && (_MSC_VER < 1500)
-# define ASIO_INITFN_RESULT_TYPE(ct, sig) \
- typename ::asio::detail::async_result_helper< \
- ct, sig>::return_type
-#define ASIO_HANDLER_TYPE(ct, sig) \
- typename ::asio::detail::async_result_helper< \
- ct, sig>::completion_handler_type
-#else
-# define ASIO_INITFN_RESULT_TYPE(ct, sig) \
- typename ::asio::async_result< \
- typename ::asio::decay::type, sig>::return_type
-#define ASIO_HANDLER_TYPE(ct, sig) \
- typename ::asio::async_result< \
- typename ::asio::decay::type, sig>::completion_handler_type
-#endif
-
-#endif // ASIO_ASYNC_RESULT_HPP
diff --git a/scout_sdk/asio/asio/basic_datagram_socket.hpp b/scout_sdk/asio/asio/basic_datagram_socket.hpp
deleted file mode 100644
index 346cc35..0000000
--- a/scout_sdk/asio/asio/basic_datagram_socket.hpp
+++ /dev/null
@@ -1,1040 +0,0 @@
-//
-// basic_datagram_socket.hpp
-// ~~~~~~~~~~~~~~~~~~~~~~~~~
-//
-// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com)
-//
-// Distributed under the Boost Software License, Version 1.0. (See accompanying
-// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
-//
-
-#ifndef ASIO_BASIC_DATAGRAM_SOCKET_HPP
-#define ASIO_BASIC_DATAGRAM_SOCKET_HPP
-
-#if defined(_MSC_VER) && (_MSC_VER >= 1200)
-# pragma once
-#endif // defined(_MSC_VER) && (_MSC_VER >= 1200)
-
-#include "asio/detail/config.hpp"
-#include
-#include "asio/basic_socket.hpp"
-#include "asio/detail/handler_type_requirements.hpp"
-#include "asio/detail/throw_error.hpp"
-#include "asio/detail/type_traits.hpp"
-#include "asio/error.hpp"
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
-# include "asio/datagram_socket_service.hpp"
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
-
-#include "asio/detail/push_options.hpp"
-
-namespace asio {
-
-/// Provides datagram-oriented socket functionality.
-/**
- * The basic_datagram_socket class template provides asynchronous and blocking
- * datagram-oriented socket functionality.
- *
- * @par Thread Safety
- * @e Distinct @e objects: Safe.@n
- * @e Shared @e objects: Unsafe.
- */
-template )>
-class basic_datagram_socket
- : public basic_socket
-{
-public:
- /// The native representation of a socket.
-#if defined(GENERATING_DOCUMENTATION)
- typedef implementation_defined native_handle_type;
-#else
- typedef typename basic_socket<
- Protocol ASIO_SVC_TARG>::native_handle_type native_handle_type;
-#endif
-
- /// The protocol type.
- typedef Protocol protocol_type;
-
- /// The endpoint type.
- typedef typename Protocol::endpoint endpoint_type;
-
- /// Construct a basic_datagram_socket without opening it.
- /**
- * This constructor creates a datagram socket without opening it. The open()
- * function must be called before data can be sent or received on the socket.
- *
- * @param io_context The io_context object that the datagram socket will use
- * to dispatch handlers for any asynchronous operations performed on the
- * socket.
- */
- explicit basic_datagram_socket(asio::io_context& io_context)
- : basic_socket(io_context)
- {
- }
-
- /// Construct and open a basic_datagram_socket.
- /**
- * This constructor creates and opens a datagram socket.
- *
- * @param io_context The io_context object that the datagram socket will use
- * to dispatch handlers for any asynchronous operations performed on the
- * socket.
- *
- * @param protocol An object specifying protocol parameters to be used.
- *
- * @throws asio::system_error Thrown on failure.
- */
- basic_datagram_socket(asio::io_context& io_context,
- const protocol_type& protocol)
- : basic_socket(io_context, protocol)
- {
- }
-
- /// Construct a basic_datagram_socket, opening it and binding it to the given
- /// local endpoint.
- /**
- * This constructor creates a datagram socket and automatically opens it bound
- * to the specified endpoint on the local machine. The protocol used is the
- * protocol associated with the given endpoint.
- *
- * @param io_context The io_context object that the datagram socket will use
- * to dispatch handlers for any asynchronous operations performed on the
- * socket.
- *
- * @param endpoint An endpoint on the local machine to which the datagram
- * socket will be bound.
- *
- * @throws asio::system_error Thrown on failure.
- */
- basic_datagram_socket(asio::io_context& io_context,
- const endpoint_type& endpoint)
- : basic_socket(io_context, endpoint)
- {
- }
-
- /// Construct a basic_datagram_socket on an existing native socket.
- /**
- * This constructor creates a datagram socket object to hold an existing
- * native socket.
- *
- * @param io_context The io_context object that the datagram socket will use
- * to dispatch handlers for any asynchronous operations performed on the
- * socket.
- *
- * @param protocol An object specifying protocol parameters to be used.
- *
- * @param native_socket The new underlying socket implementation.
- *
- * @throws asio::system_error Thrown on failure.
- */
- basic_datagram_socket(asio::io_context& io_context,
- const protocol_type& protocol, const native_handle_type& native_socket)
- : basic_socket(
- io_context, protocol, native_socket)
- {
- }
-
-#if defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION)
- /// Move-construct a basic_datagram_socket from another.
- /**
- * This constructor moves a datagram socket from one object to another.
- *
- * @param other The other basic_datagram_socket object from which the move
- * will occur.
- *
- * @note Following the move, the moved-from object is in the same state as if
- * constructed using the @c basic_datagram_socket(io_context&) constructor.
- */
- basic_datagram_socket(basic_datagram_socket&& other)
- : basic_socket(std::move(other))
- {
- }
-
- /// Move-assign a basic_datagram_socket from another.
- /**
- * This assignment operator moves a datagram socket from one object to
- * another.
- *
- * @param other The other basic_datagram_socket object from which the move
- * will occur.
- *
- * @note Following the move, the moved-from object is in the same state as if
- * constructed using the @c basic_datagram_socket(io_context&) constructor.
- */
- basic_datagram_socket& operator=(basic_datagram_socket&& other)
- {
- basic_socket::operator=(std::move(other));
- return *this;
- }
-
- /// Move-construct a basic_datagram_socket from a socket of another protocol
- /// type.
- /**
- * This constructor moves a datagram socket from one object to another.
- *
- * @param other The other basic_datagram_socket object from which the move
- * will occur.
- *
- * @note Following the move, the moved-from object is in the same state as if
- * constructed using the @c basic_datagram_socket(io_context&) constructor.
- */
- template
- basic_datagram_socket(
- basic_datagram_socket&& other,
- typename enable_if::value>::type* = 0)
- : basic_socket(std::move(other))
- {
- }
-
- /// Move-assign a basic_datagram_socket from a socket of another protocol
- /// type.
- /**
- * This assignment operator moves a datagram socket from one object to
- * another.
- *
- * @param other The other basic_datagram_socket object from which the move
- * will occur.
- *
- * @note Following the move, the moved-from object is in the same state as if
- * constructed using the @c basic_datagram_socket(io_context&) constructor.
- */
- template
- typename enable_if::value,
- basic_datagram_socket>::type& operator=(
- basic_datagram_socket&& other)
- {
- basic_socket::operator=(std::move(other));
- return *this;
- }
-#endif // defined(ASIO_HAS_MOVE) || defined(GENERATING_DOCUMENTATION)
-
- /// Destroys the socket.
- /**
- * This function destroys the socket, cancelling any outstanding asynchronous
- * operations associated with the socket as if by calling @c cancel.
- */
- ~basic_datagram_socket()
- {
- }
-
- /// Send some data on a connected socket.
- /**
- * This function is used to send data on the datagram socket. The function
- * call will block until the data has been sent successfully or an error
- * occurs.
- *
- * @param buffers One ore more data buffers to be sent on the socket.
- *
- * @returns The number of bytes sent.
- *
- * @throws asio::system_error Thrown on failure.
- *
- * @note The send operation can only be used with a connected socket. Use
- * the send_to function to send data on an unconnected datagram socket.
- *
- * @par Example
- * To send a single data buffer use the @ref buffer function as follows:
- * @code socket.send(asio::buffer(data, size)); @endcode
- * See the @ref buffer documentation for information on sending multiple
- * buffers in one go, and how to use it with arrays, boost::array or
- * std::vector.
- */
- template
- std::size_t send(const ConstBufferSequence& buffers)
- {
- asio::error_code ec;
- std::size_t s = this->get_service().send(
- this->get_implementation(), buffers, 0, ec);
- asio::detail::throw_error(ec, "send");
- return s;
- }
-
- /// Send some data on a connected socket.
- /**
- * This function is used to send data on the datagram socket. The function
- * call will block until the data has been sent successfully or an error
- * occurs.
- *
- * @param buffers One ore more data buffers to be sent on the socket.
- *
- * @param flags Flags specifying how the send call is to be made.
- *
- * @returns The number of bytes sent.
- *
- * @throws asio::system_error Thrown on failure.
- *
- * @note The send operation can only be used with a connected socket. Use
- * the send_to function to send data on an unconnected datagram socket.
- */
- template
- std::size_t send(const ConstBufferSequence& buffers,
- socket_base::message_flags flags)
- {
- asio::error_code ec;
- std::size_t s = this->get_service().send(
- this->get_implementation(), buffers, flags, ec);
- asio::detail::throw_error(ec, "send");
- return s;
- }
-
- /// Send some data on a connected socket.
- /**
- * This function is used to send data on the datagram socket. The function
- * call will block until the data has been sent successfully or an error
- * occurs.
- *
- * @param buffers One or more data buffers to be sent on the socket.
- *
- * @param flags Flags specifying how the send call is to be made.
- *
- * @param ec Set to indicate what error occurred, if any.
- *
- * @returns The number of bytes sent.
- *
- * @note The send operation can only be used with a connected socket. Use
- * the send_to function to send data on an unconnected datagram socket.
- */
- template
- std::size_t send(const ConstBufferSequence& buffers,
- socket_base::message_flags flags, asio::error_code& ec)
- {
- return this->get_service().send(
- this->get_implementation(), buffers, flags, ec);
- }
-
- /// Start an asynchronous send on a connected socket.
- /**
- * This function is used to asynchronously send data on the datagram socket.
- * The function call always returns immediately.
- *
- * @param buffers One or more data buffers to be sent on the socket. Although
- * the buffers object may be copied as necessary, ownership of the underlying
- * memory blocks is retained by the caller, which must guarantee that they
- * remain valid until the handler is called.
- *
- * @param handler The handler to be called when the send operation completes.
- * Copies will be made of the handler as required. The function signature of
- * the handler must be:
- * @code void handler(
- * const asio::error_code& error, // Result of operation.
- * std::size_t bytes_transferred // Number of bytes sent.
- * ); @endcode
- * Regardless of whether the asynchronous operation completes immediately or
- * not, the handler will not be invoked from within this function. Invocation
- * of the handler will be performed in a manner equivalent to using
- * asio::io_context::post().
- *
- * @note The async_send operation can only be used with a connected socket.
- * Use the async_send_to function to send data on an unconnected datagram
- * socket.
- *
- * @par Example
- * To send a single data buffer use the @ref buffer function as follows:
- * @code
- * socket.async_send(asio::buffer(data, size), handler);
- * @endcode
- * See the @ref buffer documentation for information on sending multiple
- * buffers in one go, and how to use it with arrays, boost::array or
- * std::vector.
- */
- template
- ASIO_INITFN_RESULT_TYPE(WriteHandler,
- void (asio::error_code, std::size_t))
- async_send(const ConstBufferSequence& buffers,
- ASIO_MOVE_ARG(WriteHandler) handler)
- {
- // If you get an error on the following line it means that your handler does
- // not meet the documented type requirements for a WriteHandler.
- ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
- return this->get_service().async_send(this->get_implementation(),
- buffers, 0, ASIO_MOVE_CAST(WriteHandler)(handler));
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
- async_completion init(handler);
-
- this->get_service().async_send(this->get_implementation(),
- buffers, 0, init.completion_handler);
-
- return init.result.get();
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
- }
-
- /// Start an asynchronous send on a connected socket.
- /**
- * This function is used to asynchronously send data on the datagram socket.
- * The function call always returns immediately.
- *
- * @param buffers One or more data buffers to be sent on the socket. Although
- * the buffers object may be copied as necessary, ownership of the underlying
- * memory blocks is retained by the caller, which must guarantee that they
- * remain valid until the handler is called.
- *
- * @param flags Flags specifying how the send call is to be made.
- *
- * @param handler The handler to be called when the send operation completes.
- * Copies will be made of the handler as required. The function signature of
- * the handler must be:
- * @code void handler(
- * const asio::error_code& error, // Result of operation.
- * std::size_t bytes_transferred // Number of bytes sent.
- * ); @endcode
- * Regardless of whether the asynchronous operation completes immediately or
- * not, the handler will not be invoked from within this function. Invocation
- * of the handler will be performed in a manner equivalent to using
- * asio::io_context::post().
- *
- * @note The async_send operation can only be used with a connected socket.
- * Use the async_send_to function to send data on an unconnected datagram
- * socket.
- */
- template
- ASIO_INITFN_RESULT_TYPE(WriteHandler,
- void (asio::error_code, std::size_t))
- async_send(const ConstBufferSequence& buffers,
- socket_base::message_flags flags,
- ASIO_MOVE_ARG(WriteHandler) handler)
- {
- // If you get an error on the following line it means that your handler does
- // not meet the documented type requirements for a WriteHandler.
- ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
- return this->get_service().async_send(this->get_implementation(),
- buffers, flags, ASIO_MOVE_CAST(WriteHandler)(handler));
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
- async_completion init(handler);
-
- this->get_service().async_send(this->get_implementation(),
- buffers, flags, init.completion_handler);
-
- return init.result.get();
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
- }
-
- /// Send a datagram to the specified endpoint.
- /**
- * This function is used to send a datagram to the specified remote endpoint.
- * The function call will block until the data has been sent successfully or
- * an error occurs.
- *
- * @param buffers One or more data buffers to be sent to the remote endpoint.
- *
- * @param destination The remote endpoint to which the data will be sent.
- *
- * @returns The number of bytes sent.
- *
- * @throws asio::system_error Thrown on failure.
- *
- * @par Example
- * To send a single data buffer use the @ref buffer function as follows:
- * @code
- * asio::ip::udp::endpoint destination(
- * asio::ip::address::from_string("1.2.3.4"), 12345);
- * socket.send_to(asio::buffer(data, size), destination);
- * @endcode
- * See the @ref buffer documentation for information on sending multiple
- * buffers in one go, and how to use it with arrays, boost::array or
- * std::vector.
- */
- template
- std::size_t send_to(const ConstBufferSequence& buffers,
- const endpoint_type& destination)
- {
- asio::error_code ec;
- std::size_t s = this->get_service().send_to(
- this->get_implementation(), buffers, destination, 0, ec);
- asio::detail::throw_error(ec, "send_to");
- return s;
- }
-
- /// Send a datagram to the specified endpoint.
- /**
- * This function is used to send a datagram to the specified remote endpoint.
- * The function call will block until the data has been sent successfully or
- * an error occurs.
- *
- * @param buffers One or more data buffers to be sent to the remote endpoint.
- *
- * @param destination The remote endpoint to which the data will be sent.
- *
- * @param flags Flags specifying how the send call is to be made.
- *
- * @returns The number of bytes sent.
- *
- * @throws asio::system_error Thrown on failure.
- */
- template
- std::size_t send_to(const ConstBufferSequence& buffers,
- const endpoint_type& destination, socket_base::message_flags flags)
- {
- asio::error_code ec;
- std::size_t s = this->get_service().send_to(
- this->get_implementation(), buffers, destination, flags, ec);
- asio::detail::throw_error(ec, "send_to");
- return s;
- }
-
- /// Send a datagram to the specified endpoint.
- /**
- * This function is used to send a datagram to the specified remote endpoint.
- * The function call will block until the data has been sent successfully or
- * an error occurs.
- *
- * @param buffers One or more data buffers to be sent to the remote endpoint.
- *
- * @param destination The remote endpoint to which the data will be sent.
- *
- * @param flags Flags specifying how the send call is to be made.
- *
- * @param ec Set to indicate what error occurred, if any.
- *
- * @returns The number of bytes sent.
- */
- template
- std::size_t send_to(const ConstBufferSequence& buffers,
- const endpoint_type& destination, socket_base::message_flags flags,
- asio::error_code& ec)
- {
- return this->get_service().send_to(this->get_implementation(),
- buffers, destination, flags, ec);
- }
-
- /// Start an asynchronous send.
- /**
- * This function is used to asynchronously send a datagram to the specified
- * remote endpoint. The function call always returns immediately.
- *
- * @param buffers One or more data buffers to be sent to the remote endpoint.
- * Although the buffers object may be copied as necessary, ownership of the
- * underlying memory blocks is retained by the caller, which must guarantee
- * that they remain valid until the handler is called.
- *
- * @param destination The remote endpoint to which the data will be sent.
- * Copies will be made of the endpoint as required.
- *
- * @param handler The handler to be called when the send operation completes.
- * Copies will be made of the handler as required. The function signature of
- * the handler must be:
- * @code void handler(
- * const asio::error_code& error, // Result of operation.
- * std::size_t bytes_transferred // Number of bytes sent.
- * ); @endcode
- * Regardless of whether the asynchronous operation completes immediately or
- * not, the handler will not be invoked from within this function. Invocation
- * of the handler will be performed in a manner equivalent to using
- * asio::io_context::post().
- *
- * @par Example
- * To send a single data buffer use the @ref buffer function as follows:
- * @code
- * asio::ip::udp::endpoint destination(
- * asio::ip::address::from_string("1.2.3.4"), 12345);
- * socket.async_send_to(
- * asio::buffer(data, size), destination, handler);
- * @endcode
- * See the @ref buffer documentation for information on sending multiple
- * buffers in one go, and how to use it with arrays, boost::array or
- * std::vector.
- */
- template
- ASIO_INITFN_RESULT_TYPE(WriteHandler,
- void (asio::error_code, std::size_t))
- async_send_to(const ConstBufferSequence& buffers,
- const endpoint_type& destination,
- ASIO_MOVE_ARG(WriteHandler) handler)
- {
- // If you get an error on the following line it means that your handler does
- // not meet the documented type requirements for a WriteHandler.
- ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
- return this->get_service().async_send_to(
- this->get_implementation(), buffers, destination, 0,
- ASIO_MOVE_CAST(WriteHandler)(handler));
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
- async_completion init(handler);
-
- this->get_service().async_send_to(
- this->get_implementation(), buffers, destination, 0,
- init.completion_handler);
-
- return init.result.get();
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
- }
-
- /// Start an asynchronous send.
- /**
- * This function is used to asynchronously send a datagram to the specified
- * remote endpoint. The function call always returns immediately.
- *
- * @param buffers One or more data buffers to be sent to the remote endpoint.
- * Although the buffers object may be copied as necessary, ownership of the
- * underlying memory blocks is retained by the caller, which must guarantee
- * that they remain valid until the handler is called.
- *
- * @param flags Flags specifying how the send call is to be made.
- *
- * @param destination The remote endpoint to which the data will be sent.
- * Copies will be made of the endpoint as required.
- *
- * @param handler The handler to be called when the send operation completes.
- * Copies will be made of the handler as required. The function signature of
- * the handler must be:
- * @code void handler(
- * const asio::error_code& error, // Result of operation.
- * std::size_t bytes_transferred // Number of bytes sent.
- * ); @endcode
- * Regardless of whether the asynchronous operation completes immediately or
- * not, the handler will not be invoked from within this function. Invocation
- * of the handler will be performed in a manner equivalent to using
- * asio::io_context::post().
- */
- template
- ASIO_INITFN_RESULT_TYPE(WriteHandler,
- void (asio::error_code, std::size_t))
- async_send_to(const ConstBufferSequence& buffers,
- const endpoint_type& destination, socket_base::message_flags flags,
- ASIO_MOVE_ARG(WriteHandler) handler)
- {
- // If you get an error on the following line it means that your handler does
- // not meet the documented type requirements for a WriteHandler.
- ASIO_WRITE_HANDLER_CHECK(WriteHandler, handler) type_check;
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
- return this->get_service().async_send_to(
- this->get_implementation(), buffers, destination, flags,
- ASIO_MOVE_CAST(WriteHandler)(handler));
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
- async_completion init(handler);
-
- this->get_service().async_send_to(
- this->get_implementation(), buffers, destination, flags,
- init.completion_handler);
-
- return init.result.get();
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
- }
-
- /// Receive some data on a connected socket.
- /**
- * This function is used to receive data on the datagram socket. The function
- * call will block until data has been received successfully or an error
- * occurs.
- *
- * @param buffers One or more buffers into which the data will be received.
- *
- * @returns The number of bytes received.
- *
- * @throws asio::system_error Thrown on failure.
- *
- * @note The receive operation can only be used with a connected socket. Use
- * the receive_from function to receive data on an unconnected datagram
- * socket.
- *
- * @par Example
- * To receive into a single data buffer use the @ref buffer function as
- * follows:
- * @code socket.receive(asio::buffer(data, size)); @endcode
- * See the @ref buffer documentation for information on receiving into
- * multiple buffers in one go, and how to use it with arrays, boost::array or
- * std::vector.
- */
- template
- std::size_t receive(const MutableBufferSequence& buffers)
- {
- asio::error_code ec;
- std::size_t s = this->get_service().receive(
- this->get_implementation(), buffers, 0, ec);
- asio::detail::throw_error(ec, "receive");
- return s;
- }
-
- /// Receive some data on a connected socket.
- /**
- * This function is used to receive data on the datagram socket. The function
- * call will block until data has been received successfully or an error
- * occurs.
- *
- * @param buffers One or more buffers into which the data will be received.
- *
- * @param flags Flags specifying how the receive call is to be made.
- *
- * @returns The number of bytes received.
- *
- * @throws asio::system_error Thrown on failure.
- *
- * @note The receive operation can only be used with a connected socket. Use
- * the receive_from function to receive data on an unconnected datagram
- * socket.
- */
- template
- std::size_t receive(const MutableBufferSequence& buffers,
- socket_base::message_flags flags)
- {
- asio::error_code ec;
- std::size_t s = this->get_service().receive(
- this->get_implementation(), buffers, flags, ec);
- asio::detail::throw_error(ec, "receive");
- return s;
- }
-
- /// Receive some data on a connected socket.
- /**
- * This function is used to receive data on the datagram socket. The function
- * call will block until data has been received successfully or an error
- * occurs.
- *
- * @param buffers One or more buffers into which the data will be received.
- *
- * @param flags Flags specifying how the receive call is to be made.
- *
- * @param ec Set to indicate what error occurred, if any.
- *
- * @returns The number of bytes received.
- *
- * @note The receive operation can only be used with a connected socket. Use
- * the receive_from function to receive data on an unconnected datagram
- * socket.
- */
- template
- std::size_t receive(const MutableBufferSequence& buffers,
- socket_base::message_flags flags, asio::error_code& ec)
- {
- return this->get_service().receive(
- this->get_implementation(), buffers, flags, ec);
- }
-
- /// Start an asynchronous receive on a connected socket.
- /**
- * This function is used to asynchronously receive data from the datagram
- * socket. The function call always returns immediately.
- *
- * @param buffers One or more buffers into which the data will be received.
- * Although the buffers object may be copied as necessary, ownership of the
- * underlying memory blocks is retained by the caller, which must guarantee
- * that they remain valid until the handler is called.
- *
- * @param handler The handler to be called when the receive operation
- * completes. Copies will be made of the handler as required. The function
- * signature of the handler must be:
- * @code void handler(
- * const asio::error_code& error, // Result of operation.
- * std::size_t bytes_transferred // Number of bytes received.
- * ); @endcode
- * Regardless of whether the asynchronous operation completes immediately or
- * not, the handler will not be invoked from within this function. Invocation
- * of the handler will be performed in a manner equivalent to using
- * asio::io_context::post().
- *
- * @note The async_receive operation can only be used with a connected socket.
- * Use the async_receive_from function to receive data on an unconnected
- * datagram socket.
- *
- * @par Example
- * To receive into a single data buffer use the @ref buffer function as
- * follows:
- * @code
- * socket.async_receive(asio::buffer(data, size), handler);
- * @endcode
- * See the @ref buffer documentation for information on receiving into
- * multiple buffers in one go, and how to use it with arrays, boost::array or
- * std::vector.
- */
- template
- ASIO_INITFN_RESULT_TYPE(ReadHandler,
- void (asio::error_code, std::size_t))
- async_receive(const MutableBufferSequence& buffers,
- ASIO_MOVE_ARG(ReadHandler) handler)
- {
- // If you get an error on the following line it means that your handler does
- // not meet the documented type requirements for a ReadHandler.
- ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
- return this->get_service().async_receive(this->get_implementation(),
- buffers, 0, ASIO_MOVE_CAST(ReadHandler)(handler));
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
- async_completion init(handler);
-
- this->get_service().async_receive(this->get_implementation(),
- buffers, 0, init.completion_handler);
-
- return init.result.get();
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
- }
-
- /// Start an asynchronous receive on a connected socket.
- /**
- * This function is used to asynchronously receive data from the datagram
- * socket. The function call always returns immediately.
- *
- * @param buffers One or more buffers into which the data will be received.
- * Although the buffers object may be copied as necessary, ownership of the
- * underlying memory blocks is retained by the caller, which must guarantee
- * that they remain valid until the handler is called.
- *
- * @param flags Flags specifying how the receive call is to be made.
- *
- * @param handler The handler to be called when the receive operation
- * completes. Copies will be made of the handler as required. The function
- * signature of the handler must be:
- * @code void handler(
- * const asio::error_code& error, // Result of operation.
- * std::size_t bytes_transferred // Number of bytes received.
- * ); @endcode
- * Regardless of whether the asynchronous operation completes immediately or
- * not, the handler will not be invoked from within this function. Invocation
- * of the handler will be performed in a manner equivalent to using
- * asio::io_context::post().
- *
- * @note The async_receive operation can only be used with a connected socket.
- * Use the async_receive_from function to receive data on an unconnected
- * datagram socket.
- */
- template
- ASIO_INITFN_RESULT_TYPE(ReadHandler,
- void (asio::error_code, std::size_t))
- async_receive(const MutableBufferSequence& buffers,
- socket_base::message_flags flags,
- ASIO_MOVE_ARG(ReadHandler) handler)
- {
- // If you get an error on the following line it means that your handler does
- // not meet the documented type requirements for a ReadHandler.
- ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
- return this->get_service().async_receive(this->get_implementation(),
- buffers, flags, ASIO_MOVE_CAST(ReadHandler)(handler));
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
- async_completion init(handler);
-
- this->get_service().async_receive(this->get_implementation(),
- buffers, flags, init.completion_handler);
-
- return init.result.get();
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
- }
-
- /// Receive a datagram with the endpoint of the sender.
- /**
- * This function is used to receive a datagram. The function call will block
- * until data has been received successfully or an error occurs.
- *
- * @param buffers One or more buffers into which the data will be received.
- *
- * @param sender_endpoint An endpoint object that receives the endpoint of
- * the remote sender of the datagram.
- *
- * @returns The number of bytes received.
- *
- * @throws asio::system_error Thrown on failure.
- *
- * @par Example
- * To receive into a single data buffer use the @ref buffer function as
- * follows:
- * @code
- * asio::ip::udp::endpoint sender_endpoint;
- * socket.receive_from(
- * asio::buffer(data, size), sender_endpoint);
- * @endcode
- * See the @ref buffer documentation for information on receiving into
- * multiple buffers in one go, and how to use it with arrays, boost::array or
- * std::vector.
- */
- template
- std::size_t receive_from(const MutableBufferSequence& buffers,
- endpoint_type& sender_endpoint)
- {
- asio::error_code ec;
- std::size_t s = this->get_service().receive_from(
- this->get_implementation(), buffers, sender_endpoint, 0, ec);
- asio::detail::throw_error(ec, "receive_from");
- return s;
- }
-
- /// Receive a datagram with the endpoint of the sender.
- /**
- * This function is used to receive a datagram. The function call will block
- * until data has been received successfully or an error occurs.
- *
- * @param buffers One or more buffers into which the data will be received.
- *
- * @param sender_endpoint An endpoint object that receives the endpoint of
- * the remote sender of the datagram.
- *
- * @param flags Flags specifying how the receive call is to be made.
- *
- * @returns The number of bytes received.
- *
- * @throws asio::system_error Thrown on failure.
- */
- template
- std::size_t receive_from(const MutableBufferSequence& buffers,
- endpoint_type& sender_endpoint, socket_base::message_flags flags)
- {
- asio::error_code ec;
- std::size_t s = this->get_service().receive_from(
- this->get_implementation(), buffers, sender_endpoint, flags, ec);
- asio::detail::throw_error(ec, "receive_from");
- return s;
- }
-
- /// Receive a datagram with the endpoint of the sender.
- /**
- * This function is used to receive a datagram. The function call will block
- * until data has been received successfully or an error occurs.
- *
- * @param buffers One or more buffers into which the data will be received.
- *
- * @param sender_endpoint An endpoint object that receives the endpoint of
- * the remote sender of the datagram.
- *
- * @param flags Flags specifying how the receive call is to be made.
- *
- * @param ec Set to indicate what error occurred, if any.
- *
- * @returns The number of bytes received.
- */
- template
- std::size_t receive_from(const MutableBufferSequence& buffers,
- endpoint_type& sender_endpoint, socket_base::message_flags flags,
- asio::error_code& ec)
- {
- return this->get_service().receive_from(this->get_implementation(),
- buffers, sender_endpoint, flags, ec);
- }
-
- /// Start an asynchronous receive.
- /**
- * This function is used to asynchronously receive a datagram. The function
- * call always returns immediately.
- *
- * @param buffers One or more buffers into which the data will be received.
- * Although the buffers object may be copied as necessary, ownership of the
- * underlying memory blocks is retained by the caller, which must guarantee
- * that they remain valid until the handler is called.
- *
- * @param sender_endpoint An endpoint object that receives the endpoint of
- * the remote sender of the datagram. Ownership of the sender_endpoint object
- * is retained by the caller, which must guarantee that it is valid until the
- * handler is called.
- *
- * @param handler The handler to be called when the receive operation
- * completes. Copies will be made of the handler as required. The function
- * signature of the handler must be:
- * @code void handler(
- * const asio::error_code& error, // Result of operation.
- * std::size_t bytes_transferred // Number of bytes received.
- * ); @endcode
- * Regardless of whether the asynchronous operation completes immediately or
- * not, the handler will not be invoked from within this function. Invocation
- * of the handler will be performed in a manner equivalent to using
- * asio::io_context::post().
- *
- * @par Example
- * To receive into a single data buffer use the @ref buffer function as
- * follows:
- * @code socket.async_receive_from(
- * asio::buffer(data, size), sender_endpoint, handler); @endcode
- * See the @ref buffer documentation for information on receiving into
- * multiple buffers in one go, and how to use it with arrays, boost::array or
- * std::vector.
- */
- template
- ASIO_INITFN_RESULT_TYPE(ReadHandler,
- void (asio::error_code, std::size_t))
- async_receive_from(const MutableBufferSequence& buffers,
- endpoint_type& sender_endpoint,
- ASIO_MOVE_ARG(ReadHandler) handler)
- {
- // If you get an error on the following line it means that your handler does
- // not meet the documented type requirements for a ReadHandler.
- ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
- return this->get_service().async_receive_from(
- this->get_implementation(), buffers, sender_endpoint, 0,
- ASIO_MOVE_CAST(ReadHandler)(handler));
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
- async_completion init(handler);
-
- this->get_service().async_receive_from(
- this->get_implementation(), buffers, sender_endpoint, 0,
- init.completion_handler);
-
- return init.result.get();
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
- }
-
- /// Start an asynchronous receive.
- /**
- * This function is used to asynchronously receive a datagram. The function
- * call always returns immediately.
- *
- * @param buffers One or more buffers into which the data will be received.
- * Although the buffers object may be copied as necessary, ownership of the
- * underlying memory blocks is retained by the caller, which must guarantee
- * that they remain valid until the handler is called.
- *
- * @param sender_endpoint An endpoint object that receives the endpoint of
- * the remote sender of the datagram. Ownership of the sender_endpoint object
- * is retained by the caller, which must guarantee that it is valid until the
- * handler is called.
- *
- * @param flags Flags specifying how the receive call is to be made.
- *
- * @param handler The handler to be called when the receive operation
- * completes. Copies will be made of the handler as required. The function
- * signature of the handler must be:
- * @code void handler(
- * const asio::error_code& error, // Result of operation.
- * std::size_t bytes_transferred // Number of bytes received.
- * ); @endcode
- * Regardless of whether the asynchronous operation completes immediately or
- * not, the handler will not be invoked from within this function. Invocation
- * of the handler will be performed in a manner equivalent to using
- * asio::io_context::post().
- */
- template
- ASIO_INITFN_RESULT_TYPE(ReadHandler,
- void (asio::error_code, std::size_t))
- async_receive_from(const MutableBufferSequence& buffers,
- endpoint_type& sender_endpoint, socket_base::message_flags flags,
- ASIO_MOVE_ARG(ReadHandler) handler)
- {
- // If you get an error on the following line it means that your handler does
- // not meet the documented type requirements for a ReadHandler.
- ASIO_READ_HANDLER_CHECK(ReadHandler, handler) type_check;
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
- return this->get_service().async_receive_from(
- this->get_implementation(), buffers, sender_endpoint, flags,
- ASIO_MOVE_CAST(ReadHandler)(handler));
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
- async_completion init(handler);
-
- this->get_service().async_receive_from(
- this->get_implementation(), buffers, sender_endpoint, flags,
- init.completion_handler);
-
- return init.result.get();
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
- }
-};
-
-} // namespace asio
-
-#include "asio/detail/pop_options.hpp"
-
-#endif // ASIO_BASIC_DATAGRAM_SOCKET_HPP
diff --git a/scout_sdk/asio/asio/basic_deadline_timer.hpp b/scout_sdk/asio/asio/basic_deadline_timer.hpp
deleted file mode 100644
index 5b20066..0000000
--- a/scout_sdk/asio/asio/basic_deadline_timer.hpp
+++ /dev/null
@@ -1,628 +0,0 @@
-//
-// basic_deadline_timer.hpp
-// ~~~~~~~~~~~~~~~~~~~~~~~~
-//
-// Copyright (c) 2003-2018 Christopher M. Kohlhoff (chris at kohlhoff dot com)
-//
-// Distributed under the Boost Software License, Version 1.0. (See accompanying
-// file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt)
-//
-
-#ifndef ASIO_BASIC_DEADLINE_TIMER_HPP
-#define ASIO_BASIC_DEADLINE_TIMER_HPP
-
-#if defined(_MSC_VER) && (_MSC_VER >= 1200)
-# pragma once
-#endif // defined(_MSC_VER) && (_MSC_VER >= 1200)
-
-#include "asio/detail/config.hpp"
-
-#if defined(ASIO_HAS_BOOST_DATE_TIME) \
- || defined(GENERATING_DOCUMENTATION)
-
-#include
-#include "asio/basic_io_object.hpp"
-#include "asio/detail/handler_type_requirements.hpp"
-#include "asio/detail/throw_error.hpp"
-#include "asio/error.hpp"
-#include "asio/time_traits.hpp"
-
-#if defined(ASIO_ENABLE_OLD_SERVICES)
-# include "asio/deadline_timer_service.hpp"
-#else // defined(ASIO_ENABLE_OLD_SERVICES)
-# include "asio/detail/deadline_timer_service.hpp"
-# define ASIO_SVC_T detail::deadline_timer_service
-#endif // defined(ASIO_ENABLE_OLD_SERVICES)
-
-#include "asio/detail/push_options.hpp"
-
-namespace asio {
-
-/// Provides waitable timer functionality.
-/**
- * The basic_deadline_timer class template provides the ability to perform a
- * blocking or asynchronous wait for a timer to expire.
- *
- * A deadline timer is always in one of two states: "expired" or "not expired".
- * If the wait() or async_wait() function is called on an expired timer, the
- * wait operation will complete immediately.
- *
- * Most applications will use the asio::deadline_timer typedef.
- *
- * @par Thread Safety
- * @e Distinct @e objects: Safe.@n
- * @e Shared @e objects: Unsafe.
- *
- * @par Examples
- * Performing a blocking wait:
- * @code
- * // Construct a timer without setting an expiry time.
- * asio::deadline_timer timer(io_context);
- *
- * // Set an expiry time relative to now.
- * timer.expires_from_now(boost::posix_time::seconds(5));
- *
- * // Wait for the timer to expire.
- * timer.wait();
- * @endcode
- *
- * @par
- * Performing an asynchronous wait:
- * @code
- * void handler(const asio::error_code& error)
- * {
- * if (!error)
- * {
- * // Timer expired.
- * }
- * }
- *
- * ...
- *
- * // Construct a timer with an absolute expiry time.
- * asio::deadline_timer timer(io_context,
- * boost::posix_time::time_from_string("2005-12-07 23:59:59.000"));
- *
- * // Start an asynchronous wait.
- * timer.async_wait(handler);
- * @endcode
- *
- * @par Changing an active deadline_timer's expiry time
- *
- * Changing the expiry time of a timer while there are pending asynchronous
- * waits causes those wait operations to be cancelled. To ensure that the action
- * associated with the timer is performed only once, use something like this:
- * used:
- *
- * @code
- * void on_some_event()
- * {
- * if (my_timer.expires_from_now(seconds(5)) > 0)
- * {
- * // We managed to cancel the timer. Start new asynchronous wait.
- * my_timer.async_wait(on_timeout);
- * }
- * else
- * {
- * // Too late, timer has already expired!
- * }
- * }
- *
- * void on_timeout(const asio::error_code& e)
- * {
- * if (e != asio::error::operation_aborted)
- * {
- * // Timer was not cancelled, take necessary action.
- * }
- * }
- * @endcode
- *
- * @li The asio::basic_deadline_timer::expires_from_now() function
- * cancels any pending asynchronous waits, and returns the number of
- * asynchronous waits that were cancelled. If it returns 0 then you were too
- * late and the wait handler has already been executed, or will soon be
- * executed. If it returns 1 then the wait handler was successfully cancelled.
- *
- * @li If a wait handler is cancelled, the asio::error_code passed to
- * it contains the value asio::error::operation_aborted.
- */
-template
- ASIO_SVC_TPARAM_DEF2(= deadline_timer_service