mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
updated ros wrapper to work with can sdk
This commit is contained in:
@@ -2,66 +2,21 @@ cmake_minimum_required(VERSION 2.8.3)
|
|||||||
project(scout_base)
|
project(scout_base)
|
||||||
|
|
||||||
## Compile as C++11, supported in ROS Kinetic and newer
|
## Compile as C++11, supported in ROS Kinetic and newer
|
||||||
# add_compile_options(-std=c++11)
|
add_compile_options(-std=c++11)
|
||||||
|
|
||||||
## Find catkin macros and libraries
|
|
||||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
|
||||||
## is used, also find other catkin packages
|
|
||||||
find_package(catkin REQUIRED COMPONENTS
|
find_package(catkin REQUIRED COMPONENTS
|
||||||
geometry_msgs
|
controller_manager
|
||||||
|
hardware_interface
|
||||||
|
husky_msgs
|
||||||
|
diagnostic_updater
|
||||||
|
roslaunch
|
||||||
|
roslint
|
||||||
roscpp
|
roscpp
|
||||||
rospy
|
sensor_msgs
|
||||||
std_msgs
|
std_msgs
|
||||||
tf
|
geometry_msgs
|
||||||
)
|
tf)
|
||||||
|
find_package(Boost REQUIRED COMPONENTS chrono)
|
||||||
## 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 ##
|
|
||||||
################################################
|
|
||||||
|
|
||||||
## Generate messages in the 'msg' folder
|
|
||||||
add_message_files(
|
|
||||||
FILES
|
|
||||||
Encode.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
|
|
||||||
geometry_msgs # std_msgs
|
|
||||||
)
|
|
||||||
|
|
||||||
################################################
|
|
||||||
## Declare ROS dynamic reconfigure parameters ##
|
|
||||||
################################################
|
|
||||||
|
|
||||||
## Generate dynamic reconfigure parameters in the 'cfg' folder
|
|
||||||
# generate_dynamic_reconfigure_options(
|
|
||||||
# cfg/DynReconf1.cfg
|
|
||||||
# cfg/DynReconf2.cfg
|
|
||||||
# )
|
|
||||||
|
|
||||||
###################################
|
###################################
|
||||||
## catkin specific configuration ##
|
## catkin specific configuration ##
|
||||||
@@ -70,8 +25,8 @@ generate_messages(
|
|||||||
catkin_package(
|
catkin_package(
|
||||||
INCLUDE_DIRS include
|
INCLUDE_DIRS include
|
||||||
# LIBRARIES scout_base
|
# LIBRARIES scout_base
|
||||||
CATKIN_DEPENDS message_runtime geometry_msgs roscpp rospy std_msgs tf
|
CATKIN_DEPENDS diagnostic_updater hardware_interface scout_msgs roscpp sensor_msgs
|
||||||
# DEPENDS system_lib
|
# DEPENDS Boost
|
||||||
)
|
)
|
||||||
|
|
||||||
###########
|
###########
|
||||||
@@ -88,56 +43,25 @@ include_directories(
|
|||||||
# add scout sdk
|
# add scout sdk
|
||||||
add_subdirectory(src/scout_sdk)
|
add_subdirectory(src/scout_sdk)
|
||||||
|
|
||||||
add_executable(scout_ros src/scout_ros.cpp)
|
add_executable(scout_base_node src/scout_base_node.cpp src/scout_messenger.cpp)
|
||||||
target_link_libraries(scout_ros scoutcpp ${catkin_LIBRARIES})
|
target_link_libraries(scout_base_node scout_base ${catkin_LIBRARIES})
|
||||||
|
|
||||||
add_executable(keybord src/keybord.cpp)
|
# add_executable(keybord src/keybord.cpp)
|
||||||
target_link_libraries(keybord ${catkin_LIBRARIES})
|
# target_link_libraries(keybord ${catkin_LIBRARIES})
|
||||||
|
|
||||||
#############
|
#############
|
||||||
## Install ##
|
## Install ##
|
||||||
#############
|
#############
|
||||||
|
|
||||||
# all install targets should use catkin DESTINATION variables
|
# roslaunch_add_file_check(launch)
|
||||||
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
|
|
||||||
|
|
||||||
## Mark executable scripts (Python etc.) for installation
|
# install(TARGETS scoutcpp scoutio scout_base
|
||||||
## in contrast to setup.py, you can choose the destination
|
|
||||||
# install(PROGRAMS
|
|
||||||
# scripts/my_python_script
|
|
||||||
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
|
||||||
# )
|
|
||||||
|
|
||||||
## Mark executables and/or libraries for installation
|
|
||||||
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
|
|
||||||
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
|
||||||
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
|
||||||
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||||
# )
|
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||||
|
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
|
||||||
|
|
||||||
## Mark cpp header files for installation
|
|
||||||
# install(DIRECTORY include/${PROJECT_NAME}/
|
# install(DIRECTORY include/${PROJECT_NAME}/
|
||||||
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})
|
||||||
# FILES_MATCHING PATTERN "*.h"
|
|
||||||
# PATTERN ".svn" EXCLUDE
|
|
||||||
# )
|
|
||||||
|
|
||||||
## Mark other files for installation (e.g. launch and bag files, etc.)
|
# install(DIRECTORY launch config
|
||||||
# install(FILES
|
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
||||||
# # myfile1
|
|
||||||
# # myfile2
|
|
||||||
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
|
|
||||||
# )
|
|
||||||
|
|
||||||
#############
|
|
||||||
## Testing ##
|
|
||||||
#############
|
|
||||||
|
|
||||||
## Add gtest based cpp test target and link libraries
|
|
||||||
# catkin_add_gtest(${PROJECT_NAME}-test test/test_scout_base.cpp)
|
|
||||||
# if(TARGET ${PROJECT_NAME}-test)
|
|
||||||
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
|
|
||||||
# endif()
|
|
||||||
|
|
||||||
## Add folders to be run by python nosetests
|
|
||||||
# catkin_add_nosetests(test)
|
|
||||||
|
|||||||
@@ -1,16 +0,0 @@
|
|||||||
# Prerequisites
|
|
||||||
|
|
||||||
* Make sure your user account has access to
|
|
||||||
* serial port (to communicate with robot base)
|
|
||||||
* keyboard input (to use keyboard control)
|
|
||||||
|
|
||||||
* Grant access to serial port
|
|
||||||
```
|
|
||||||
# Note: you can use "ls /dev/ttyUSB*" to check the serial port number on your computer
|
|
||||||
$ sudo chmod 666 /dev/ttyUSB0
|
|
||||||
```
|
|
||||||
|
|
||||||
* Add user to "input" group
|
|
||||||
```
|
|
||||||
$ sudo adduser <your-user-name> input
|
|
||||||
```
|
|
||||||
64
scout_base/include/scout_base/scout_messenger.hpp
Normal file
64
scout_base/include/scout_base/scout_messenger.hpp
Normal file
@@ -0,0 +1,64 @@
|
|||||||
|
/*
|
||||||
|
* scout_messenger.hpp
|
||||||
|
*
|
||||||
|
* Created on: Jun 14, 2019 10:24
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SCOUT_MESSENGER_HPP
|
||||||
|
#define SCOUT_MESSENGER_HPP
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <boost/thread.hpp>
|
||||||
|
|
||||||
|
#include <ros/ros.h>
|
||||||
|
#include <sensor_msgs/JointState.h>
|
||||||
|
#include <tf/transform_broadcaster.h>
|
||||||
|
#include <nav_msgs/Odometry.h>
|
||||||
|
|
||||||
|
#include "scout/scout_base.hpp"
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
class ScoutROSMessenger
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
ScoutROSMessenger(ScoutBase &scout, ros::NodeHandle nh);
|
||||||
|
|
||||||
|
int control_rate_;
|
||||||
|
std::string odom_frame_;
|
||||||
|
std::string base_frame_;
|
||||||
|
|
||||||
|
void SetupSubscription();
|
||||||
|
void PublishStateToROS();
|
||||||
|
|
||||||
|
private:
|
||||||
|
ScoutBase &scout_;
|
||||||
|
ros::NodeHandle nh_;
|
||||||
|
int32_t cmd_timeout_counter_ = 0;
|
||||||
|
|
||||||
|
std::mutex twist_mutex_;
|
||||||
|
geometry_msgs::Twist current_twist_;
|
||||||
|
|
||||||
|
ros::Publisher odom_publisher_;
|
||||||
|
ros::Subscriber cmd_subscriber_;
|
||||||
|
tf::TransformBroadcaster tf_broadcaster_;
|
||||||
|
|
||||||
|
private:
|
||||||
|
// speed variables
|
||||||
|
double linear_speed_ = 0.0;
|
||||||
|
double angular_speed_ = 0.0;
|
||||||
|
double position_x_ = 0.0;
|
||||||
|
double position_y_ = 0.0;
|
||||||
|
double theta_ = 0.0;
|
||||||
|
|
||||||
|
ros::Time last_time_;
|
||||||
|
ros::Time current_time_;
|
||||||
|
|
||||||
|
void TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg);
|
||||||
|
};
|
||||||
|
} // namespace scout
|
||||||
|
|
||||||
|
#endif /* SCOUT_MESSENGER_HPP */
|
||||||
@@ -1,14 +0,0 @@
|
|||||||
<launch>
|
|
||||||
<node name="keybord" pkg="scout_base" type="keybord" output="screen">
|
|
||||||
|
|
||||||
<param name="input" value="/dev/input/event3" />
|
|
||||||
|
|
||||||
<param name="walk_vel" value="0.5" />
|
|
||||||
<param name="run_vel" value="0.5" />
|
|
||||||
|
|
||||||
<param name="max_tv" value="2.0" />
|
|
||||||
<param name="max_rv" value="2.6" />
|
|
||||||
|
|
||||||
</node>
|
|
||||||
|
|
||||||
</launch>
|
|
||||||
@@ -1,15 +1,10 @@
|
|||||||
<launch>
|
<launch>
|
||||||
|
<node name="scout_odom" pkg="scout_base" type="scout_base_node" output="screen">
|
||||||
<node name="scout_odom" pkg="scout_base" type="scout_ros" output="screen">
|
<param name="port_name" type="string" value="can1" />
|
||||||
|
|
||||||
<param name="port_name" type="string" value="/dev/ttyUSB0" />
|
|
||||||
<param name="baud_rate" value="115200" />
|
|
||||||
|
|
||||||
<param name="odom_frame" type="string" value="odom" />
|
<param name="odom_frame" type="string" value="odom" />
|
||||||
<param name="base_frame" type="string" value="base_footprint" />
|
<param name="base_frame" type="string" value="base_footprint" />
|
||||||
|
|
||||||
<param name="control_rate" value="10" />
|
<param name="control_rate" value="10" />
|
||||||
|
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
4
scout_base/launch/teleop_keyboard.launch
Normal file
4
scout_base/launch/teleop_keyboard.launch
Normal file
@@ -0,0 +1,4 @@
|
|||||||
|
<launch>
|
||||||
|
<node name="teleop_keybord" pkg="teleop_twist_keyboard" type="teleop_twist_keyboard.py" output="screen">
|
||||||
|
</node>
|
||||||
|
</launch>
|
||||||
@@ -1,2 +0,0 @@
|
|||||||
int64 left
|
|
||||||
int64 right
|
|
||||||
@@ -1,76 +1,46 @@
|
|||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<package format="2">
|
<package>
|
||||||
<name>scout_base</name>
|
<name>scout_base</name>
|
||||||
<version>0.0.0</version>
|
<version>0.3.3</version>
|
||||||
<description>The scout_base package</description>
|
<description>AgileX Scout robot driver</description>
|
||||||
|
|
||||||
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
<author email="mpurvis@clearpathrobotics.com">Mike Purvis</author>
|
||||||
<!-- Example: -->
|
<author email="paul@bovbel.com">Paul Bovbel</author>
|
||||||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
|
||||||
<maintainer email="rdu@todo.todo">rdu</maintainer>
|
<maintainer email="paul@bovbel.com">Paul Bovbel</maintainer>
|
||||||
|
<maintainer email="tbaltovski@clearpathrobotics.com">Tony Baltovski</maintainer>
|
||||||
|
|
||||||
|
|
||||||
<!-- One license tag required, multiple allowed, one license per tag -->
|
<license>BSD</license>
|
||||||
<!-- Commonly used license strings: -->
|
|
||||||
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
|
|
||||||
<license>TODO</license>
|
|
||||||
|
|
||||||
|
<url type="website">http://ros.org/wiki/husky_base</url>
|
||||||
|
<url type="bugtracker">https://github.com/husky/husky_robot/issues</url>
|
||||||
|
<url type="repository">https://github.com/husky/husky_robot</url>
|
||||||
|
|
||||||
<!-- Url tags are optional, but multiple are allowed, one per tag -->
|
|
||||||
<!-- Optional attribute type can be: website, bugtracker, or repository -->
|
|
||||||
<!-- Example: -->
|
|
||||||
<!-- <url type="website">http://wiki.ros.org/scout_base</url> -->
|
|
||||||
|
|
||||||
|
|
||||||
<!-- Author tags are optional, multiple are allowed, one per tag -->
|
|
||||||
<!-- Authors do not have to be maintainers, but could be -->
|
|
||||||
<!-- Example: -->
|
|
||||||
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
|
|
||||||
|
|
||||||
|
|
||||||
<!-- The *depend tags are used to specify dependencies -->
|
|
||||||
<!-- Dependencies can be catkin packages or system dependencies -->
|
|
||||||
<!-- Examples: -->
|
|
||||||
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
|
|
||||||
<!-- <depend>roscpp</depend> -->
|
|
||||||
<!-- Note that this is equivalent to the following: -->
|
|
||||||
<!-- <build_depend>roscpp</build_depend> -->
|
|
||||||
<!-- <exec_depend>roscpp</exec_depend> -->
|
|
||||||
<!-- Use build_depend for packages you need at compile time: -->
|
|
||||||
<!-- <build_depend>message_generation</build_depend> -->
|
|
||||||
<!-- Use build_export_depend for packages you need in order to build against this package: -->
|
|
||||||
<!-- <build_export_depend>message_generation</build_export_depend> -->
|
|
||||||
<!-- Use buildtool_depend for build tool packages: -->
|
|
||||||
<!-- <buildtool_depend>catkin</buildtool_depend> -->
|
|
||||||
<!-- Use exec_depend for packages you need at runtime: -->
|
|
||||||
<!-- <exec_depend>message_runtime</exec_depend> -->
|
|
||||||
<!-- Use test_depend for packages you need only for testing: -->
|
|
||||||
<!-- <test_depend>gtest</test_depend> -->
|
|
||||||
<!-- Use doc_depend for packages you need only for building documentation: -->
|
|
||||||
<!-- <doc_depend>doxygen</doc_depend> -->
|
|
||||||
<buildtool_depend>catkin</buildtool_depend>
|
<buildtool_depend>catkin</buildtool_depend>
|
||||||
<build_depend>geometry_msgs</build_depend>
|
<build_depend>controller_manager</build_depend>
|
||||||
|
<build_depend>diagnostic_updater</build_depend>
|
||||||
|
<build_depend>diagnostic_msgs</build_depend>
|
||||||
|
<build_depend>hardware_interface</build_depend>
|
||||||
|
<build_depend>scout_msgs</build_depend>
|
||||||
<build_depend>roscpp</build_depend>
|
<build_depend>roscpp</build_depend>
|
||||||
<build_depend>rospy</build_depend>
|
<build_depend>roslaunch</build_depend>
|
||||||
<build_depend>std_msgs</build_depend>
|
<build_depend>roslint</build_depend>
|
||||||
<build_depend>tf</build_depend>
|
<build_depend>sensor_msgs</build_depend>
|
||||||
<build_depend>message_generation</build_depend>
|
|
||||||
<build_export_depend>geometry_msgs</build_export_depend>
|
|
||||||
<build_export_depend>roscpp</build_export_depend>
|
|
||||||
<build_export_depend>rospy</build_export_depend>
|
|
||||||
<build_export_depend>std_msgs</build_export_depend>
|
|
||||||
<build_export_depend>tf</build_export_depend>
|
|
||||||
<exec_depend>message_runtime</exec_depend>
|
|
||||||
<exec_depend>geometry_msgs</exec_depend>
|
|
||||||
<exec_depend>roscpp</exec_depend>
|
|
||||||
<exec_depend>rospy</exec_depend>
|
|
||||||
<exec_depend>std_msgs</exec_depend>
|
|
||||||
<exec_depend>tf</exec_depend>
|
|
||||||
|
|
||||||
|
<run_depend>controller_manager</run_depend>
|
||||||
|
<run_depend>diagnostic_updater</run_depend>
|
||||||
|
<run_depend>diagnostic_msgs</run_depend>
|
||||||
|
<run_depend>diagnostic_aggregator</run_depend>
|
||||||
|
<run_depend>diff_drive_controller</run_depend>
|
||||||
|
<run_depend>geometry_msgs</run_depend>
|
||||||
|
<run_depend>hardware_interface</run_depend>
|
||||||
|
<run_depend>scout_control</run_depend>
|
||||||
|
<run_depend>scout_msgs</run_depend>
|
||||||
|
<run_depend>scout_description</run_depend>
|
||||||
|
<run_depend>roscpp</run_depend>
|
||||||
|
<run_depend>sensor_msgs</run_depend>
|
||||||
|
<run_depend>topic_tools</run_depend>
|
||||||
|
|
||||||
<!-- The export tag contains other, unspecified, tags -->
|
<export></export>
|
||||||
<export>
|
|
||||||
<!-- Other tools can request additional information be placed here -->
|
|
||||||
|
|
||||||
</export>
|
|
||||||
</package>
|
</package>
|
||||||
|
|||||||
@@ -1,203 +0,0 @@
|
|||||||
#include <termios.h>
|
|
||||||
#include <signal.h>
|
|
||||||
#include <math.h>
|
|
||||||
#include <stdio.h>
|
|
||||||
#include <stdlib.h>
|
|
||||||
#include <sys/poll.h>
|
|
||||||
#include <boost/thread/thread.hpp>
|
|
||||||
#include <ros/ros.h>
|
|
||||||
#include <geometry_msgs/Twist.h>
|
|
||||||
#include <linux/input.h>
|
|
||||||
#include <sys/types.h>
|
|
||||||
#include <errno.h>
|
|
||||||
#include <fcntl.h>
|
|
||||||
|
|
||||||
#define KEY_W 17
|
|
||||||
#define KEY_A 30
|
|
||||||
#define KEY_S 31
|
|
||||||
#define KEY_D 32
|
|
||||||
#define KEY_UP 103
|
|
||||||
#define KEY_LEFT 105
|
|
||||||
#define KEY_DOWN 108
|
|
||||||
#define KEY_RIGHT 106
|
|
||||||
|
|
||||||
#define DEBUG 0
|
|
||||||
|
|
||||||
using namespace std;
|
|
||||||
class Keyboard
|
|
||||||
{
|
|
||||||
private:
|
|
||||||
double walk_vel_;
|
|
||||||
double run_vel_;
|
|
||||||
double max_tv;
|
|
||||||
double max_rv;
|
|
||||||
std::string input;
|
|
||||||
|
|
||||||
int kfd;
|
|
||||||
struct termios cooked, raw;
|
|
||||||
struct input_event t;
|
|
||||||
|
|
||||||
geometry_msgs::Twist cmdvel_;
|
|
||||||
ros::NodeHandle n_;
|
|
||||||
ros::Publisher pub_;
|
|
||||||
|
|
||||||
public:
|
|
||||||
Keyboard()
|
|
||||||
{
|
|
||||||
pub_ = n_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
|
|
||||||
ros::NodeHandle n_private("~");
|
|
||||||
n_private.param("walk_vel", walk_vel_, 0.5);
|
|
||||||
n_private.param("run_vel", run_vel_, 0.5);
|
|
||||||
n_private.param("max_tv", max_tv, 2.0);
|
|
||||||
n_private.param("max_rv", max_rv, 2.6);
|
|
||||||
n_private.param("input", input, std::string("/dev/input/event3"));
|
|
||||||
|
|
||||||
Hidden_Character();
|
|
||||||
}
|
|
||||||
~Keyboard()
|
|
||||||
{
|
|
||||||
tcsetattr(kfd, TCSANOW, &cooked); //恢复参数
|
|
||||||
}
|
|
||||||
|
|
||||||
void keyboardLoop();
|
|
||||||
void stopRobot()
|
|
||||||
{
|
|
||||||
cmdvel_.linear.x = 0.0;
|
|
||||||
cmdvel_.angular.z = 0.0;
|
|
||||||
pub_.publish(cmdvel_);
|
|
||||||
}
|
|
||||||
void Hidden_Character()
|
|
||||||
{
|
|
||||||
//隐藏字符
|
|
||||||
tcgetattr(kfd, &cooked);
|
|
||||||
memcpy(&raw, &cooked, sizeof(struct termios));
|
|
||||||
raw.c_lflag &= ~(ICANON | ECHO);
|
|
||||||
raw.c_cc[VEOL] = 1;
|
|
||||||
raw.c_cc[VEOF] = 2;
|
|
||||||
tcsetattr(kfd, TCSANOW, &raw);
|
|
||||||
}
|
|
||||||
};
|
|
||||||
string msg = "\n\
|
|
||||||
Reading from the keyboard and Publishing to Twist!\n\
|
|
||||||
---------------------------\n\
|
|
||||||
Moving around:\n\
|
|
||||||
\n\
|
|
||||||
w \n\
|
|
||||||
a s d \n\
|
|
||||||
\n\
|
|
||||||
UP/DOWN : increase/decrease only linear speed by 0.2\n\
|
|
||||||
LEFT/RIGHT : increase/decrease only angular speed by 0.2\n\
|
|
||||||
CTRL-C to quit";
|
|
||||||
|
|
||||||
void Keyboard::keyboardLoop()
|
|
||||||
{
|
|
||||||
char c;
|
|
||||||
int speed = 0, turn = 0;
|
|
||||||
int keys_fd;
|
|
||||||
char ret[2];
|
|
||||||
|
|
||||||
ROS_INFO_STREAM(msg);
|
|
||||||
|
|
||||||
keys_fd = open(input.c_str(), O_RDONLY);
|
|
||||||
if (keys_fd <= 0)
|
|
||||||
{
|
|
||||||
ROS_INFO_STREAM("open " << input << " device error");
|
|
||||||
}
|
|
||||||
|
|
||||||
for (;;)
|
|
||||||
{
|
|
||||||
if (read(keys_fd, &t, sizeof(t)) == sizeof(t))
|
|
||||||
{
|
|
||||||
if (t.type == EV_KEY)
|
|
||||||
{
|
|
||||||
if (t.value == 0 || t.value == 1)
|
|
||||||
{
|
|
||||||
#if DEBUG
|
|
||||||
printf("key %d %d\n", t.code, t.value);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (t.code == KEY_W)
|
|
||||||
{
|
|
||||||
if (t.value == 1)
|
|
||||||
speed = 1;
|
|
||||||
else
|
|
||||||
speed = 0;
|
|
||||||
}
|
|
||||||
else if (t.code == KEY_S)
|
|
||||||
{
|
|
||||||
if (t.value == 1)
|
|
||||||
speed = -1;
|
|
||||||
else
|
|
||||||
speed = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (t.code == KEY_A)
|
|
||||||
{
|
|
||||||
if (t.value == 1)
|
|
||||||
turn = -1;
|
|
||||||
else
|
|
||||||
turn = 0;
|
|
||||||
}
|
|
||||||
else if (t.code == KEY_D)
|
|
||||||
{
|
|
||||||
if (t.value == 1)
|
|
||||||
turn = 1;
|
|
||||||
else
|
|
||||||
turn = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (t.code == KEY_UP)
|
|
||||||
{
|
|
||||||
if (t.value == 1)
|
|
||||||
{
|
|
||||||
max_tv += 0.2;
|
|
||||||
if (max_tv > 2)
|
|
||||||
max_tv = 2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else if (t.code == KEY_DOWN)
|
|
||||||
{
|
|
||||||
if (t.value == 1)
|
|
||||||
{
|
|
||||||
max_tv -= 0.2;
|
|
||||||
if (max_tv < 0.2)
|
|
||||||
max_tv = 0.2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (t.code == KEY_LEFT)
|
|
||||||
{
|
|
||||||
if (t.value == 1)
|
|
||||||
{
|
|
||||||
max_rv -= 0.2;
|
|
||||||
if (max_rv < 0.2)
|
|
||||||
max_rv = 0.2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else if (t.code == KEY_RIGHT)
|
|
||||||
{
|
|
||||||
if (t.value == 1)
|
|
||||||
{
|
|
||||||
max_rv += 0.2;
|
|
||||||
if (max_rv > 3)
|
|
||||||
max_rv = 3;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
cmdvel_.linear.x = speed * max_tv;
|
|
||||||
cmdvel_.angular.z = turn * max_rv;
|
|
||||||
pub_.publish(cmdvel_);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
close(keys_fd);
|
|
||||||
}
|
|
||||||
|
|
||||||
int main(int argc, char **argv)
|
|
||||||
{
|
|
||||||
ros::init(argc, argv, "keybord");
|
|
||||||
Keyboard tbk;
|
|
||||||
boost::thread t = boost::thread(boost::bind(&Keyboard::keyboardLoop, &tbk));
|
|
||||||
ros::spin();
|
|
||||||
return (0);
|
|
||||||
}
|
|
||||||
43
scout_base/src/scout_base_node.cpp
Normal file
43
scout_base/src/scout_base_node.cpp
Normal file
@@ -0,0 +1,43 @@
|
|||||||
|
#include <string>
|
||||||
|
#include <boost/thread.hpp>
|
||||||
|
|
||||||
|
#include <ros/ros.h>
|
||||||
|
#include <sensor_msgs/JointState.h>
|
||||||
|
#include <tf/transform_broadcaster.h>
|
||||||
|
#include <nav_msgs/Odometry.h>
|
||||||
|
|
||||||
|
#include "scout/scout_base.hpp"
|
||||||
|
#include "scout_base/scout_messenger.hpp"
|
||||||
|
|
||||||
|
using namespace wescore;
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
// setup ROS node
|
||||||
|
ros::init(argc, argv, "scout_odom");
|
||||||
|
ros::NodeHandle node("scout_robot"), private_node("~");
|
||||||
|
|
||||||
|
// instantiate a robot
|
||||||
|
ScoutBase robot;
|
||||||
|
ScoutROSMessenger messenger(robot, node);
|
||||||
|
|
||||||
|
std::string scout_can_port;
|
||||||
|
private_node.param<std::string>("port_name_", scout_can_port, std::string("can1"));
|
||||||
|
private_node.param<std::string>("odom_frame_", messenger.odom_frame_, std::string("odom"));
|
||||||
|
private_node.param<std::string>("base_frame_", messenger.base_frame_, std::string("base_footprint"));
|
||||||
|
|
||||||
|
// connect to scout and setup ROS subscription
|
||||||
|
robot.ConnectCANBus(scout_can_port);
|
||||||
|
messenger.SetupSubscription();
|
||||||
|
|
||||||
|
// publish robot state at 20Hz while listening to twist commands
|
||||||
|
ros::Rate rt(20); // 20Hz
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
messenger.PublishStateToROS();
|
||||||
|
ros::spinOnce();
|
||||||
|
rt.sleep();
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
93
scout_base/src/scout_messenger.cpp
Normal file
93
scout_base/src/scout_messenger.cpp
Normal file
@@ -0,0 +1,93 @@
|
|||||||
|
/*
|
||||||
|
* scout_messenger.cpp
|
||||||
|
*
|
||||||
|
* Created on: Apr 26, 2019 22:14
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "scout_base/scout_messenger.hpp"
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
ScoutROSMessenger::ScoutROSMessenger(ScoutBase &scout, ros::NodeHandle nh) : scout_(scout), nh_(nh)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutROSMessenger::SetupSubscription()
|
||||||
|
{
|
||||||
|
// odometry publisher
|
||||||
|
odom_publisher_ = nh_.advertise<nav_msgs::Odometry>(odom_frame_, 50);
|
||||||
|
|
||||||
|
// cmd subscriber
|
||||||
|
cmd_subscriber_ = nh_.subscribe<geometry_msgs::Twist>("/cmd_vel", 5, &ScoutROSMessenger::TwistCmdCallback, this); //不启用平滑包则订阅“cmd_vel”
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutROSMessenger::TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg)
|
||||||
|
{
|
||||||
|
scout_.SetMotionCommand(msg->linear.x, msg->angular.z);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutROSMessenger::PublishStateToROS()
|
||||||
|
{
|
||||||
|
current_time_ = ros::Time::now();
|
||||||
|
double dt = (current_time_ - last_time_).toSec();
|
||||||
|
|
||||||
|
static bool init_run = true;
|
||||||
|
if (init_run)
|
||||||
|
{
|
||||||
|
last_time_ = current_time_;
|
||||||
|
init_run = false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
auto state = scout_.GetScoutState();
|
||||||
|
double linear = state.linear_velocity;
|
||||||
|
double angular = state.angular_velocity;
|
||||||
|
|
||||||
|
double d_x = linear_speed_ * std::cos(theta_) * dt;
|
||||||
|
double d_y = linear_speed_ * std::sin(theta_) * dt;
|
||||||
|
double d_theta = angular_speed_ * dt;
|
||||||
|
|
||||||
|
position_x_ += d_x;
|
||||||
|
position_y_ += d_y;
|
||||||
|
theta_ += d_theta;
|
||||||
|
|
||||||
|
//since all odometry is 6DOF we'll need a quaternion created from yaw
|
||||||
|
geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(theta_);
|
||||||
|
|
||||||
|
//first, we'll publish the transform over tf
|
||||||
|
geometry_msgs::TransformStamped tf_msg;
|
||||||
|
tf_msg.header.stamp = current_time_;
|
||||||
|
tf_msg.header.frame_id = odom_frame_;
|
||||||
|
tf_msg.child_frame_id = base_frame_;
|
||||||
|
|
||||||
|
tf_msg.transform.translation.x = position_x_;
|
||||||
|
tf_msg.transform.translation.y = position_y_;
|
||||||
|
tf_msg.transform.translation.z = 0.0;
|
||||||
|
tf_msg.transform.rotation = odom_quat;
|
||||||
|
|
||||||
|
tf_broadcaster_.sendTransform(tf_msg);
|
||||||
|
|
||||||
|
//next, we'll publish the odometry message over ROS
|
||||||
|
nav_msgs::Odometry odom_msg;
|
||||||
|
odom_msg.header.stamp = current_time_;
|
||||||
|
odom_msg.header.frame_id = odom_frame_;
|
||||||
|
odom_msg.child_frame_id = base_frame_;
|
||||||
|
|
||||||
|
odom_msg.pose.pose.position.x = position_x_;
|
||||||
|
odom_msg.pose.pose.position.y = position_y_;
|
||||||
|
odom_msg.pose.pose.position.z = 0.0;
|
||||||
|
odom_msg.pose.pose.orientation = odom_quat;
|
||||||
|
|
||||||
|
odom_msg.twist.twist.linear.x = linear_speed_;
|
||||||
|
odom_msg.twist.twist.linear.y = 0.0;
|
||||||
|
odom_msg.twist.twist.angular.z = angular_speed_;
|
||||||
|
|
||||||
|
//publish the message
|
||||||
|
odom_publisher_.publish(odom_msg);
|
||||||
|
|
||||||
|
last_time_ = current_time_;
|
||||||
|
}
|
||||||
|
} // namespace scout
|
||||||
@@ -1,197 +0,0 @@
|
|||||||
#include <string>
|
|
||||||
#include <boost/thread.hpp>
|
|
||||||
|
|
||||||
#include <ros/ros.h>
|
|
||||||
#include <sensor_msgs/JointState.h>
|
|
||||||
#include <tf/transform_broadcaster.h>
|
|
||||||
#include <nav_msgs/Odometry.h>
|
|
||||||
|
|
||||||
#include "scout/scout_robot.h"
|
|
||||||
|
|
||||||
#define Send_Speed_Debug 0
|
|
||||||
|
|
||||||
using namespace std;
|
|
||||||
using namespace scout;
|
|
||||||
|
|
||||||
class ScoutROSMessenger
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
void run(void);
|
|
||||||
|
|
||||||
void TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg);
|
|
||||||
void SendSpeedCmdCallback(const ros::TimerEvent &);
|
|
||||||
void PublishOdometry(void);
|
|
||||||
|
|
||||||
private:
|
|
||||||
ScoutRobot robot_;
|
|
||||||
|
|
||||||
boost::mutex twist_mutex_;
|
|
||||||
geometry_msgs::Twist current_twist_;
|
|
||||||
ros::Publisher odom_publisher_;
|
|
||||||
tf::TransformBroadcaster tf_broadcaster_;
|
|
||||||
|
|
||||||
std::string odom_frame_;
|
|
||||||
std::string base_frame_;
|
|
||||||
|
|
||||||
int ctrl_rate_;
|
|
||||||
std::string port_name_;
|
|
||||||
int baud_rate_;
|
|
||||||
|
|
||||||
double x;
|
|
||||||
double y;
|
|
||||||
double th;
|
|
||||||
double vx;
|
|
||||||
double vy;
|
|
||||||
double vth;
|
|
||||||
|
|
||||||
ros::Time last_time_;
|
|
||||||
ros::Time current_time_;
|
|
||||||
|
|
||||||
void PublishStateToROS(short linear, short angular);
|
|
||||||
void SendCmdToRobot(geometry_msgs::Twist *current_twist_);
|
|
||||||
};
|
|
||||||
|
|
||||||
void ScoutROSMessenger::TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg)
|
|
||||||
{
|
|
||||||
twist_mutex_.lock();
|
|
||||||
current_twist_ = *msg.get();
|
|
||||||
twist_mutex_.unlock();
|
|
||||||
}
|
|
||||||
|
|
||||||
void ScoutROSMessenger::SendSpeedCmdCallback(const ros::TimerEvent &)
|
|
||||||
{
|
|
||||||
SendCmdToRobot(¤t_twist_);
|
|
||||||
}
|
|
||||||
|
|
||||||
void ScoutROSMessenger::PublishOdometry(void)
|
|
||||||
{
|
|
||||||
RobotState data;
|
|
||||||
while (1)
|
|
||||||
{
|
|
||||||
if (robot_.QueryRobotState(&data))
|
|
||||||
PublishStateToROS(data.linear, data.angular);
|
|
||||||
boost::this_thread::sleep(boost::posix_time::milliseconds(5));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void ScoutROSMessenger::PublishStateToROS(short linear, short angular)
|
|
||||||
{
|
|
||||||
current_time_ = ros::Time::now();
|
|
||||||
double dt = (current_time_ - last_time_).toSec();
|
|
||||||
|
|
||||||
static bool init_run = true;
|
|
||||||
if (init_run)
|
|
||||||
{
|
|
||||||
last_time_ = current_time_;
|
|
||||||
init_run = false;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
double Angular = angular;
|
|
||||||
double Linear = linear;
|
|
||||||
Angular /= 10000;
|
|
||||||
Linear /= 10000;
|
|
||||||
|
|
||||||
vth = Angular; //旋转角速度,在角度很小的情况下。约等于(SPEED右 - SPEED左)/ 轮子间距
|
|
||||||
vx = Linear; //直线X轴的速度 = (SPEED右 - SPEED左) / 2
|
|
||||||
vy = 0.0; //2轮差速车,不能左右横移
|
|
||||||
|
|
||||||
double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
|
|
||||||
double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
|
|
||||||
double delta_th = vth * dt;
|
|
||||||
|
|
||||||
x += delta_x;
|
|
||||||
y += delta_y;
|
|
||||||
th += delta_th;
|
|
||||||
|
|
||||||
//since all odometry is 6DOF we'll need a quaternion created from yaw
|
|
||||||
geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
|
|
||||||
|
|
||||||
//first, we'll publish the transform over tf
|
|
||||||
geometry_msgs::TransformStamped odom_trans;
|
|
||||||
odom_trans.header.stamp = current_time_;
|
|
||||||
odom_trans.header.frame_id = odom_frame_;
|
|
||||||
odom_trans.child_frame_id = base_frame_;
|
|
||||||
|
|
||||||
odom_trans.transform.translation.x = x;
|
|
||||||
odom_trans.transform.translation.y = y;
|
|
||||||
odom_trans.transform.translation.z = 0.0;
|
|
||||||
odom_trans.transform.rotation = odom_quat;
|
|
||||||
|
|
||||||
//send the transform
|
|
||||||
tf_broadcaster_.sendTransform(odom_trans);
|
|
||||||
|
|
||||||
//next, we'll publish the odometry message over ROS
|
|
||||||
nav_msgs::Odometry odom;
|
|
||||||
odom.header.stamp = current_time_;
|
|
||||||
odom.header.frame_id = odom_frame_;
|
|
||||||
odom.child_frame_id = base_frame_;
|
|
||||||
|
|
||||||
//set the position
|
|
||||||
odom.pose.pose.position.x = x;
|
|
||||||
odom.pose.pose.position.y = y;
|
|
||||||
odom.pose.pose.position.z = 0.0;
|
|
||||||
odom.pose.pose.orientation = odom_quat;
|
|
||||||
|
|
||||||
//set the velocity
|
|
||||||
|
|
||||||
odom.twist.twist.linear.x = vx;
|
|
||||||
odom.twist.twist.linear.y = 0.0;
|
|
||||||
odom.twist.twist.angular.z = vth;
|
|
||||||
|
|
||||||
//publish the message
|
|
||||||
odom_publisher_.publish(odom);
|
|
||||||
|
|
||||||
last_time_ = current_time_;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ScoutROSMessenger::SendCmdToRobot(geometry_msgs::Twist *current_twist_)
|
|
||||||
{
|
|
||||||
static unsigned char index = 0;
|
|
||||||
index++;
|
|
||||||
robot_.SendCommand({current_twist_->linear.x, current_twist_->angular.z, index++});
|
|
||||||
#if Send_Speed_Debug
|
|
||||||
ROS_INFO_STREAM("send -> linear: " << cent_speed << "; angular: " << cmd_twist_rotation);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
void ScoutROSMessenger::run(void)
|
|
||||||
{
|
|
||||||
ros::NodeHandle private_node("~");
|
|
||||||
ros::NodeHandle node;
|
|
||||||
|
|
||||||
private_node.param<std::string>("port_name_", port_name_, std::string("/dev/ttyUSB0"));
|
|
||||||
private_node.param<std::string>("odom_frame_", odom_frame_, std::string("odom"));
|
|
||||||
private_node.param<std::string>("base_frame_", base_frame_, std::string("base_footprint"));
|
|
||||||
private_node.param<int>("baud_rate_", baud_rate_, 115200);
|
|
||||||
private_node.param<int>("ctrl_rate_", ctrl_rate_, 10);
|
|
||||||
|
|
||||||
// connect to scout
|
|
||||||
robot_.ConnectSerialPort(port_name_, baud_rate_);
|
|
||||||
if (!robot_.IsConnectionActive())
|
|
||||||
{
|
|
||||||
std::cerr << "Failed to connect to robot" << std::endl;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Odometry publisher
|
|
||||||
odom_publisher_ = node.advertise<nav_msgs::Odometry>(odom_frame_, 50);
|
|
||||||
boost::thread parse_thread(boost::bind(&ScoutROSMessenger::PublishOdometry, this));
|
|
||||||
|
|
||||||
// Cmd subscriber
|
|
||||||
ros::Subscriber cmd_sub = node.subscribe<geometry_msgs::Twist>("cmd_vel", 5, &ScoutROSMessenger::TwistCmdCallback, this); //不启用平滑包则订阅“cmd_vel”
|
|
||||||
ros::Timer send_speed_timer = node.createTimer(ros::Duration(1.0 / ctrl_rate_), &ScoutROSMessenger::SendSpeedCmdCallback, this);
|
|
||||||
|
|
||||||
ros::spin();
|
|
||||||
}
|
|
||||||
|
|
||||||
int main(int argc, char **argv)
|
|
||||||
{
|
|
||||||
ros::init(argc, argv, "scout_odom");
|
|
||||||
|
|
||||||
// start ROS messenger
|
|
||||||
ScoutROSMessenger scout_ros;
|
|
||||||
scout_ros.run();
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
7
scout_base/src/scout_sdk/CMakeLists.txt
Normal file → Executable file
7
scout_base/src/scout_sdk/CMakeLists.txt
Normal file → Executable file
@@ -5,9 +5,14 @@ project(scout_sdk)
|
|||||||
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||||
set(RUNTIME_OUTPUT_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/devel)
|
set(RUNTIME_OUTPUT_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/devel)
|
||||||
|
|
||||||
|
## Put all binary files into /bin and libraries into /lib
|
||||||
|
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||||
|
set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
|
||||||
## Chosse build type
|
## Chosse build type
|
||||||
# set(CMAKE_BUILD_TYPE Release)
|
# set(CMAKE_BUILD_TYPE Release)
|
||||||
set(CMAKE_BUILD_TYPE Debug)
|
# set(CMAKE_BUILD_TYPE Debug)
|
||||||
|
|
||||||
## Optionally built modules: ON/OFF
|
## Optionally built modules: ON/OFF
|
||||||
set(BUILD_TESTS OFF)
|
set(BUILD_TESTS OFF)
|
||||||
|
|||||||
61
scout_base/src/scout_sdk/README.md
Normal file → Executable file
61
scout_base/src/scout_sdk/README.md
Normal file → Executable file
@@ -1,37 +1,39 @@
|
|||||||
# Introduction
|
# SDK for AgileX Scout Mobile Base
|
||||||
|
|
||||||

|
## Introduction
|
||||||
|
|
||||||
* Data from the chassis:
|
This software packages provides a C++ interface to communicate with the Scout mobile base, for sending commands to the robot and acquiring latest robot state.
|
||||||
* Odometry (position, velocity estimation)
|
|
||||||
* Data to the chassis:
|
|
||||||
* Motion command (linear/angular velocity)
|
|
||||||
|
|
||||||
# Prerequisites
|
Generally, you only need to instantiate an object of "class ScoutBase", then use the object to programmatically control the robot. Conceptually, class ScoutBase manages two background threads, one to process CAN messages of the robot state and accordingly update state variables in the ScoutState data structre, and the other to maintain a 50Hz loop and send latest command to the robot base. User can check the robot state or set control commands, as well as other tasks, in the main thread.
|
||||||
|
|
||||||
* Make sure your user account has access to
|
See "src/demo/demo_scout_can.cpp" for an example.
|
||||||
* serial port (to communicate with robot base)
|
|
||||||
* keyboard input (to use keyboard control)
|
|
||||||
|
|
||||||
* Grant access to serial port
|
## Package Structure
|
||||||
```
|
|
||||||
# Note: you can use "ls /dev/ttyUSB*" to check the serial port number on your computer
|
|
||||||
$ sudo chmod 666 /dev/ttyUSB0
|
|
||||||
```
|
|
||||||
|
|
||||||
* Add user to "input" group
|
* scout: interface to send command to robot and receive robot state
|
||||||
```
|
* driver: manages raw data communication with robot
|
||||||
$ sudo adduser <your-user-name> input
|
* third_party
|
||||||
```
|
- asio: asynchronous IO management (serial and CAN)
|
||||||
|
- stopwatch: timing control
|
||||||
|
- googletest: for unit tests only (not required otherwise)
|
||||||
|
|
||||||
# Build SDK
|
## Hardware Interface
|
||||||
|
|
||||||
|
* CAN: full support
|
||||||
|
* RS-232: under development
|
||||||
|
|
||||||
|
A easy and low-cost option to use the CAN interface would be using a Raspberry Pi or Beaglebone board with CAN Hat/Cape. The SDK can compile on both x86 and ARM platforms. Then you can use whatever interface you prefer (serial, USB, Ethernet etc.) for the communication between the single-board computer and your main PC.
|
||||||
|
|
||||||
|
## Build SDK
|
||||||
|
|
||||||
Install compile tools
|
Install compile tools
|
||||||
|
|
||||||
```
|
```
|
||||||
$ sudo apt install build-essential cmake
|
$ sudo apt install build-essential cmake
|
||||||
```
|
```
|
||||||
|
|
||||||
Configure and build
|
Configure and build
|
||||||
|
|
||||||
```
|
```
|
||||||
$ cd scout_sdk
|
$ cd scout_sdk
|
||||||
$ mkdir build
|
$ mkdir build
|
||||||
@@ -40,7 +42,20 @@ $ cmake ..
|
|||||||
$ make
|
$ make
|
||||||
```
|
```
|
||||||
|
|
||||||
# Third-Party Components
|
## Known Limitations
|
||||||
|
|
||||||
* serial - https://github.com/wjwwood/serial: serial read/write
|
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
|
||||||
* stopwatch - https://github.com/rxdu/stopwatch: for timing control in demo
|
|
||||||
|
```
|
||||||
|
can1: flags=193<UP,RUNNING,NOARP> 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 a 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 case, you will have to translate the bytes between CAN and UART by yourself. It would be difficult for us to provide support for them since not all manufactures define this protocol in the same way.
|
||||||
|
|
||||||
|
2. Release v0.1 of this SDK provided a serial interface to talk with the robot. Front/rear light on the robot cannot be controlled and only a small subset of all robot states can be acquired throught that interface. Full support of the serial interface is still under development and requires additional work in both the SDK and firmware.
|
||||||
|
|||||||
Binary file not shown.
|
Before Width: | Height: | Size: 53 KiB |
8
scout_base/src/scout_sdk/src/CMakeLists.txt
Normal file → Executable file
8
scout_base/src/scout_sdk/src/CMakeLists.txt
Normal file → Executable file
@@ -1,5 +1,9 @@
|
|||||||
# Add source directories
|
# Add source directories
|
||||||
add_subdirectory(demo)
|
add_subdirectory(demo)
|
||||||
add_subdirectory(scout_cpp)
|
add_subdirectory(scout)
|
||||||
add_subdirectory(scout_io)
|
add_subdirectory(driver)
|
||||||
add_subdirectory(third_party)
|
add_subdirectory(third_party)
|
||||||
|
|
||||||
|
if(BUILD_TESTS)
|
||||||
|
add_subdirectory(unit_tests)
|
||||||
|
endif()
|
||||||
4
scout_base/src/scout_sdk/src/demo/CMakeLists.txt
Normal file → Executable file
4
scout_base/src/scout_sdk/src/demo/CMakeLists.txt
Normal file → Executable file
@@ -2,5 +2,5 @@
|
|||||||
#find_package(LIBRARY_NAME REQUIRED)
|
#find_package(LIBRARY_NAME REQUIRED)
|
||||||
|
|
||||||
# tests
|
# tests
|
||||||
add_executable(demo_scout_cpp demo_scout_cpp.cpp)
|
add_executable(demo_scout_can demo_scout_can.cpp)
|
||||||
target_link_libraries(demo_scout_cpp scoutcpp stopwatch)
|
target_link_libraries(demo_scout_can scout_base)
|
||||||
|
|||||||
42
scout_base/src/scout_sdk/src/demo/demo_scout_can.cpp
Normal file
42
scout_base/src/scout_sdk/src/demo/demo_scout_can.cpp
Normal file
@@ -0,0 +1,42 @@
|
|||||||
|
/*
|
||||||
|
* demo_scout_can.cpp
|
||||||
|
*
|
||||||
|
* Created on: Jun 12, 2019 05:03
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "scout/scout_base.hpp"
|
||||||
|
|
||||||
|
using namespace wescore;
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
ScoutBase scout;
|
||||||
|
scout.ConnectCANBus("can1");
|
||||||
|
scout.StartCmdThread(10);
|
||||||
|
|
||||||
|
scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_ON, 0, ScoutLightCmd::LightMode::CONST_ON, 0});
|
||||||
|
|
||||||
|
int count = 0;
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
scout.SetMotionCommand(0.5, 0.2);
|
||||||
|
|
||||||
|
if (count == 10)
|
||||||
|
scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_OFF, 0, ScoutLightCmd::LightMode::CONST_OFF, 0});
|
||||||
|
|
||||||
|
auto state = scout.GetScoutState();
|
||||||
|
std::cout << "-------------------------------" << std::endl;
|
||||||
|
std::cout << "control mode: " << static_cast<int>(state.control_mode) << " , base state: " << static_cast<int>(state.base_state) << std::endl;
|
||||||
|
std::cout << "battery voltage: " << state.battery_voltage << std::endl;
|
||||||
|
std::cout << "velocity (linear, angular): " << state.linear_velocity << ", " << state.angular_velocity << std::endl;
|
||||||
|
std::cout << "-------------------------------" << std::endl;
|
||||||
|
|
||||||
|
sleep(1);
|
||||||
|
++count;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
@@ -1,149 +0,0 @@
|
|||||||
#include <unistd.h>
|
|
||||||
|
|
||||||
#include <thread>
|
|
||||||
#include <mutex>
|
|
||||||
#include <functional>
|
|
||||||
#include <string>
|
|
||||||
#include <iostream>
|
|
||||||
#include <chrono>
|
|
||||||
#include <cmath>
|
|
||||||
|
|
||||||
#include "stopwatch/stopwatch.h"
|
|
||||||
|
|
||||||
#include "scout/scout_robot.h"
|
|
||||||
|
|
||||||
using namespace scout;
|
|
||||||
|
|
||||||
class ScoutMessenger
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
ScoutMessenger(ScoutRobot &robot, int32_t ctrl_freq = 10, int32_t odom_query_freq = 200)
|
|
||||||
: robot_(robot), ctrl_freq_(ctrl_freq), odom_query_freq_(odom_query_freq){};
|
|
||||||
~ScoutMessenger() = default;
|
|
||||||
|
|
||||||
using Clock = std::chrono::high_resolution_clock;
|
|
||||||
using time_point = typename Clock::time_point;
|
|
||||||
|
|
||||||
void PublishOdometry()
|
|
||||||
{
|
|
||||||
RobotState data;
|
|
||||||
stopwatch::StopWatch swatch;
|
|
||||||
|
|
||||||
bool init_run = true;
|
|
||||||
|
|
||||||
/* Odometry Publish Loop */
|
|
||||||
while (true)
|
|
||||||
{
|
|
||||||
swatch.tic();
|
|
||||||
|
|
||||||
if (robot_.QueryRobotState(&data))
|
|
||||||
{
|
|
||||||
short linear = data.linear;
|
|
||||||
short angular = data.angular;
|
|
||||||
|
|
||||||
current_time_ = Clock::now();
|
|
||||||
double dt = std::chrono::duration_cast<std::chrono::milliseconds>(current_time_ - last_time_).count() / 1000.0;
|
|
||||||
|
|
||||||
if (init_run)
|
|
||||||
{
|
|
||||||
last_time_ = current_time_;
|
|
||||||
init_run = false;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Velocity estimation
|
|
||||||
double Angular = angular;
|
|
||||||
double Linear = linear;
|
|
||||||
Angular /= 10000;
|
|
||||||
Linear /= 10000;
|
|
||||||
|
|
||||||
vth = Angular; // Angular velocity, when angle is small, approximately = (SPEED_RIGHT - SPEED_LEFT)/ WHEEL_DISTANCE
|
|
||||||
vx = Linear; // Linear velocity (along x axis) = (SPEED_RIGHT - SPEED_LEFT) / 2
|
|
||||||
vy = 0.0; // No lateral motion
|
|
||||||
|
|
||||||
// Pose estimation (by integration)
|
|
||||||
double delta_x = (vx * std::cos(th) - vy * std::sin(th)) * dt;
|
|
||||||
double delta_y = (vx * std::sin(th) + vy * std::cos(th)) * dt;
|
|
||||||
double delta_th = vth * dt;
|
|
||||||
x += delta_x;
|
|
||||||
y += delta_y;
|
|
||||||
th += delta_th;
|
|
||||||
|
|
||||||
// Publish/print result
|
|
||||||
std::cout << "pose: (x,y) " << x << " , " << y << " ; yaw: " << th << std::endl;
|
|
||||||
std::cout << "velocity: linear " << vx << " , angular " << vth << std::endl;
|
|
||||||
|
|
||||||
last_time_ = current_time_;
|
|
||||||
}
|
|
||||||
|
|
||||||
swatch.sleep_until_ms(1000.0 / odom_query_freq_);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void UpdateCommandCallback()
|
|
||||||
{
|
|
||||||
// Update linear_x, angular_z via your IPC method
|
|
||||||
// Note: be careful about the sync (using mutex)
|
|
||||||
std::lock_guard<std::mutex> lock(cmd_mutex_);
|
|
||||||
cmd_linear_x_ = 0;
|
|
||||||
cmd_angular_z_ = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
void SendMotionCommand()
|
|
||||||
{
|
|
||||||
stopwatch::StopWatch swatch;
|
|
||||||
static unsigned char index = 0;
|
|
||||||
|
|
||||||
/* Command Updating Loop */
|
|
||||||
while (true)
|
|
||||||
{
|
|
||||||
swatch.tic();
|
|
||||||
|
|
||||||
cmd_mutex_.lock();
|
|
||||||
robot_.SendCommand({cmd_linear_x_, cmd_angular_z_, index++});
|
|
||||||
cmd_mutex_.unlock();
|
|
||||||
|
|
||||||
swatch.sleep_until_ms(1000.0 / ctrl_freq_);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
private:
|
|
||||||
ScoutRobot &robot_;
|
|
||||||
int32_t ctrl_freq_;
|
|
||||||
int32_t odom_query_freq_;
|
|
||||||
|
|
||||||
std::mutex cmd_mutex_;
|
|
||||||
double cmd_linear_x_ = 0;
|
|
||||||
double cmd_angular_z_ = 0;
|
|
||||||
|
|
||||||
double x = 0;
|
|
||||||
double y = 0;
|
|
||||||
double th = 0;
|
|
||||||
double vx = 0;
|
|
||||||
double vy = 0;
|
|
||||||
double vth = 0;
|
|
||||||
|
|
||||||
time_point current_time_;
|
|
||||||
time_point last_time_;
|
|
||||||
};
|
|
||||||
|
|
||||||
int main(int argc, char **argv)
|
|
||||||
{
|
|
||||||
/* Connect to a scout robot */
|
|
||||||
ScoutRobot scout;
|
|
||||||
scout.ConnectSerialPort("/dev/ttyUSB0", 115200);
|
|
||||||
if (!scout.IsConnectionActive())
|
|
||||||
{
|
|
||||||
std::cerr << "Failed to connect to robot" << std::endl;
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Instantiate the messenger and start data distribution */
|
|
||||||
ScoutMessenger messenger(scout);
|
|
||||||
std::thread odom_thread(std::bind(&ScoutMessenger::PublishOdometry, &messenger));
|
|
||||||
std::thread cmd_thread(std::bind(&ScoutMessenger::SendMotionCommand, &messenger));
|
|
||||||
odom_thread.join();
|
|
||||||
cmd_thread.join();
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
10
scout_base/src/scout_sdk/src/driver/CMakeLists.txt
Normal file
10
scout_base/src/scout_sdk/src/driver/CMakeLists.txt
Normal file
@@ -0,0 +1,10 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.0.0)
|
||||||
|
project(driver)
|
||||||
|
|
||||||
|
## Put all binary files into /bin and libraries into /lib
|
||||||
|
#set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||||
|
set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
|
||||||
|
## Add sub source directories
|
||||||
|
add_subdirectory(async_io)
|
||||||
20
scout_base/src/scout_sdk/src/driver/async_io/CMakeLists.txt
Normal file
20
scout_base/src/scout_sdk/src/driver/async_io/CMakeLists.txt
Normal file
@@ -0,0 +1,20 @@
|
|||||||
|
# Dependency libraries
|
||||||
|
# find_package(LIB_NAME REQUIRED)
|
||||||
|
|
||||||
|
# Add libraries
|
||||||
|
set(ASYNC_IO_LIB_SRC
|
||||||
|
src/async_serial.cpp
|
||||||
|
src/async_can.cpp
|
||||||
|
)
|
||||||
|
add_library(asyncio STATIC ${ASYNC_IO_LIB_SRC})
|
||||||
|
target_link_libraries(asyncio asio pthread)
|
||||||
|
target_compile_definitions(asyncio PUBLIC "-DASIO_ENABLE_OLD_SERVICES -DASIO_HAS_POSIX_STREAM_DESCRIPTOR")
|
||||||
|
target_include_directories(asyncio PUBLIC
|
||||||
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
|
$<INSTALL_INTERFACE:include>
|
||||||
|
PRIVATE src)
|
||||||
|
|
||||||
|
# Add executables
|
||||||
|
if(BUILD_TESTS)
|
||||||
|
add_subdirectory(tests)
|
||||||
|
endif()
|
||||||
@@ -0,0 +1,130 @@
|
|||||||
|
/*
|
||||||
|
* async_can.hpp
|
||||||
|
*
|
||||||
|
* Created on: Jun 10, 2019 02:16
|
||||||
|
* Description: code based on uavcan and libmavconn
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Copyright (c) 2016 UAVCAN Team
|
||||||
|
*
|
||||||
|
* Distributed under the MIT License, available in the file LICENSE.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* libmavconn
|
||||||
|
* Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of the mavros package and subject to the license terms
|
||||||
|
* in the top-level LICENSE file of the mavros repository.
|
||||||
|
* https://github.com/mavlink/mavros/tree/master/LICENSE.md
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef ASYNC_CAN_HPP
|
||||||
|
#define ASYNC_CAN_HPP
|
||||||
|
|
||||||
|
#include <linux/can.h>
|
||||||
|
|
||||||
|
#include <atomic>
|
||||||
|
#include <chrono>
|
||||||
|
#include <thread>
|
||||||
|
#include <mutex>
|
||||||
|
#include <deque>
|
||||||
|
#include <functional>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "asio.hpp"
|
||||||
|
#include "asio/posix/basic_stream_descriptor.hpp"
|
||||||
|
|
||||||
|
// #include "async_io/device_error.hpp"
|
||||||
|
// #include "async_io/msg_buffer.hpp"
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
using steady_clock = std::chrono::steady_clock;
|
||||||
|
using lock_guard = std::lock_guard<std::recursive_mutex>;
|
||||||
|
|
||||||
|
class ASyncCAN : public std::enable_shared_from_this<ASyncCAN>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
static constexpr auto DEFAULT_DEVICE = "can1";
|
||||||
|
static constexpr std::size_t MAX_TXQ_SIZE = 1000;
|
||||||
|
|
||||||
|
using ReceiveCallback = std::function<void(can_frame *rx_frame)>;
|
||||||
|
using ClosedCallback = std::function<void(void)>;
|
||||||
|
|
||||||
|
using Ptr = std::shared_ptr<ASyncCAN>;
|
||||||
|
using ConstPtr = std::shared_ptr<ASyncCAN const>;
|
||||||
|
using WeakPtr = std::weak_ptr<ASyncCAN>;
|
||||||
|
|
||||||
|
struct IOStat
|
||||||
|
{
|
||||||
|
std::size_t tx_total_frames; // total bytes transferred
|
||||||
|
std::size_t rx_total_frames; // total bytes received
|
||||||
|
float tx_speed; // current transfer speed [Frames/s]
|
||||||
|
float rx_speed; // current receive speed [Frames/s]
|
||||||
|
};
|
||||||
|
|
||||||
|
public:
|
||||||
|
ASyncCAN(std::string device = DEFAULT_DEVICE);
|
||||||
|
~ASyncCAN();
|
||||||
|
|
||||||
|
// do not allow copy
|
||||||
|
ASyncCAN(const ASyncCAN &other) = delete;
|
||||||
|
ASyncCAN &operator=(const ASyncCAN &other) = delete;
|
||||||
|
|
||||||
|
std::size_t conn_id;
|
||||||
|
int can_fd_;
|
||||||
|
|
||||||
|
static Ptr open_url(std::string url);
|
||||||
|
void open(std::string device);
|
||||||
|
void close();
|
||||||
|
|
||||||
|
void set_receive_callback(ReceiveCallback cb) { receive_cb = cb; }
|
||||||
|
void set_closed_callback(ClosedCallback cb) { port_closed_cb = cb; }
|
||||||
|
|
||||||
|
inline bool is_open() { return true; }
|
||||||
|
IOStat get_iostat();
|
||||||
|
|
||||||
|
void send_frame(const can_frame &tx_frame);
|
||||||
|
|
||||||
|
private:
|
||||||
|
// monotonic counter (increment only)
|
||||||
|
bool can_interface_opened_ = false;
|
||||||
|
static std::atomic<std::size_t> conn_id_counter;
|
||||||
|
|
||||||
|
struct can_frame rcv_frame;
|
||||||
|
|
||||||
|
// port statistics
|
||||||
|
std::atomic<std::size_t> tx_total_frames;
|
||||||
|
std::atomic<std::size_t> rx_total_frames;
|
||||||
|
std::size_t last_tx_total_frames;
|
||||||
|
std::size_t last_rx_total_frames;
|
||||||
|
std::chrono::time_point<steady_clock> last_iostat;
|
||||||
|
std::recursive_mutex iostat_mutex;
|
||||||
|
|
||||||
|
// io service
|
||||||
|
asio::io_service io_service;
|
||||||
|
asio::posix::basic_stream_descriptor<> stream;
|
||||||
|
std::thread io_thread;
|
||||||
|
|
||||||
|
// callback objects
|
||||||
|
ClosedCallback port_closed_cb;
|
||||||
|
ReceiveCallback receive_cb;
|
||||||
|
|
||||||
|
// internal processing
|
||||||
|
void do_read(struct can_frame &rec_frame, asio::posix::basic_stream_descriptor<> &stream);
|
||||||
|
void do_write(bool check_tx_state);
|
||||||
|
|
||||||
|
void call_receive_callback(can_frame *rx_frame);
|
||||||
|
void default_receive_callback(can_frame *rx_frame);
|
||||||
|
|
||||||
|
void iostat_tx_add(std::size_t bytes);
|
||||||
|
void iostat_rx_add(std::size_t bytes);
|
||||||
|
};
|
||||||
|
} // namespace wescore
|
||||||
|
|
||||||
|
#endif /* ASYNC_CAN_HPP */
|
||||||
@@ -0,0 +1,131 @@
|
|||||||
|
/*
|
||||||
|
* async_serial.hpp
|
||||||
|
*
|
||||||
|
* Created on: Nov 23, 2018 22:18
|
||||||
|
* Description: asynchronous serial communication using asio
|
||||||
|
* adapted from code in libmavconn
|
||||||
|
*
|
||||||
|
* Main changes: 1. Removed dependency on Boost (asio standalone
|
||||||
|
* and C++ STL only)
|
||||||
|
* 2. Removed dependency on console-bridge
|
||||||
|
* 3. Removed mavlink related code
|
||||||
|
* 4. Removed UDP/TCP related code
|
||||||
|
*
|
||||||
|
* Author: Vladimir Ermakov <vooon341@gmail.com>
|
||||||
|
* Ruixiang Du <ruixiang.du@gmail.com>
|
||||||
|
*
|
||||||
|
* Additioanl reference:
|
||||||
|
* [1] http://www.webalice.it/fede.tft/serial_port/serial_port.html
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* libmavconn
|
||||||
|
* Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of the mavros package and subject to the license terms
|
||||||
|
* in the top-level LICENSE file of the mavros repository.
|
||||||
|
* https://github.com/mavlink/mavros/tree/master/LICENSE.md
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef ASYNC_SERIAL_HPP
|
||||||
|
#define ASYNC_SERIAL_HPP
|
||||||
|
|
||||||
|
#include <atomic>
|
||||||
|
#include <chrono>
|
||||||
|
#include <thread>
|
||||||
|
#include <mutex>
|
||||||
|
#include <deque>
|
||||||
|
#include <functional>
|
||||||
|
|
||||||
|
#include "asio.hpp"
|
||||||
|
|
||||||
|
#include "async_io/device_error.hpp"
|
||||||
|
#include "async_io/msg_buffer.hpp"
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
using steady_clock = std::chrono::steady_clock;
|
||||||
|
using lock_guard = std::lock_guard<std::recursive_mutex>;
|
||||||
|
|
||||||
|
class ASyncSerial : public std::enable_shared_from_this<ASyncSerial>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
static constexpr auto DEFAULT_DEVICE = "/dev/ttyUSB0";
|
||||||
|
static constexpr auto DEFAULT_BAUDRATE = 115200;
|
||||||
|
static constexpr std::size_t MAX_TXQ_SIZE = 1000;
|
||||||
|
|
||||||
|
using ReceiveCallback = std::function<void(uint8_t *buf, const size_t bufsize, size_t bytes_received)>;
|
||||||
|
using ClosedCallback = std::function<void(void)>;
|
||||||
|
|
||||||
|
using Ptr = std::shared_ptr<ASyncSerial>;
|
||||||
|
using ConstPtr = std::shared_ptr<ASyncSerial const>;
|
||||||
|
using WeakPtr = std::weak_ptr<ASyncSerial>;
|
||||||
|
|
||||||
|
struct IOStat
|
||||||
|
{
|
||||||
|
std::size_t tx_total_bytes; //!< total bytes transferred
|
||||||
|
std::size_t rx_total_bytes; //!< total bytes received
|
||||||
|
float tx_speed; //!< current transfer speed [B/s]
|
||||||
|
float rx_speed; //!< current receive speed [B/s]
|
||||||
|
};
|
||||||
|
|
||||||
|
public:
|
||||||
|
ASyncSerial(std::string device = DEFAULT_DEVICE, unsigned baudrate = DEFAULT_BAUDRATE, bool hwflow = false);
|
||||||
|
~ASyncSerial();
|
||||||
|
|
||||||
|
// do not allow copy
|
||||||
|
ASyncSerial(const ASyncSerial &other) = delete;
|
||||||
|
ASyncSerial &operator=(const ASyncSerial &other) = delete;
|
||||||
|
|
||||||
|
std::size_t conn_id;
|
||||||
|
|
||||||
|
static Ptr open_url(std::string url);
|
||||||
|
void open(std::string device, unsigned baudrate, bool hwflow);
|
||||||
|
void close();
|
||||||
|
|
||||||
|
void send_bytes(const uint8_t *bytes, size_t length);
|
||||||
|
void set_receive_callback(ReceiveCallback cb) { receive_cb = cb; }
|
||||||
|
void set_closed_callback(ClosedCallback cb) { port_closed_cb = cb; }
|
||||||
|
|
||||||
|
inline bool is_open() { return serial_dev.is_open(); }
|
||||||
|
IOStat get_iostat();
|
||||||
|
|
||||||
|
private:
|
||||||
|
// monotonic counter (increment only)
|
||||||
|
static std::atomic<std::size_t> conn_id_counter;
|
||||||
|
|
||||||
|
// port statistics
|
||||||
|
std::atomic<std::size_t> tx_total_bytes;
|
||||||
|
std::atomic<std::size_t> rx_total_bytes;
|
||||||
|
std::size_t last_tx_total_bytes;
|
||||||
|
std::size_t last_rx_total_bytes;
|
||||||
|
std::chrono::time_point<steady_clock> last_iostat;
|
||||||
|
std::recursive_mutex iostat_mutex;
|
||||||
|
|
||||||
|
// io service
|
||||||
|
asio::io_service io_service;
|
||||||
|
std::thread io_thread;
|
||||||
|
asio::serial_port serial_dev;
|
||||||
|
|
||||||
|
std::atomic<bool> tx_in_progress;
|
||||||
|
std::deque<MsgBuffer> tx_q;
|
||||||
|
std::array<uint8_t, MsgBuffer::MAX_SIZE> rx_buf;
|
||||||
|
std::recursive_mutex mutex;
|
||||||
|
|
||||||
|
// callback objects
|
||||||
|
ClosedCallback port_closed_cb;
|
||||||
|
ReceiveCallback receive_cb;
|
||||||
|
|
||||||
|
// internal processing
|
||||||
|
void do_read();
|
||||||
|
void do_write(bool check_tx_state);
|
||||||
|
|
||||||
|
void call_receive_callback(uint8_t *buf, const std::size_t bufsize, std::size_t bytes_received);
|
||||||
|
void default_receive_callback(uint8_t *buf, const std::size_t bufsize, std::size_t bytes_received);
|
||||||
|
|
||||||
|
void iostat_tx_add(std::size_t bytes);
|
||||||
|
void iostat_rx_add(std::size_t bytes);
|
||||||
|
};
|
||||||
|
} // namespace wescore
|
||||||
|
|
||||||
|
#endif /* ASYNC_SERIAL_HPP */
|
||||||
@@ -0,0 +1,57 @@
|
|||||||
|
/**
|
||||||
|
* @brief MAVConn device error class
|
||||||
|
* @file device_error.hpp
|
||||||
|
* @author Vladimir Ermakov <vooon341@gmail.com>
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* libmavconn
|
||||||
|
* Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of the mavros package and subject to the license terms
|
||||||
|
* in the top-level LICENSE file of the mavros repository.
|
||||||
|
* https://github.com/mavlink/mavros/tree/master/LICENSE.md
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef DEVICE_ERROR_HPP
|
||||||
|
#define DEVICE_ERROR_HPP
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <cstring>
|
||||||
|
#include <stdexcept>
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
class DeviceError : public std::runtime_error
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
template <typename T>
|
||||||
|
DeviceError(const char *module, T msg) : std::runtime_error(make_message(module, msg))
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
static std::string make_message(const char *module, T msg)
|
||||||
|
{
|
||||||
|
std::ostringstream ss;
|
||||||
|
ss << "DeviceError:" << module << ":" << msg_to_string(msg);
|
||||||
|
return ss.str();
|
||||||
|
}
|
||||||
|
|
||||||
|
static std::string msg_to_string(const char *description)
|
||||||
|
{
|
||||||
|
return description;
|
||||||
|
}
|
||||||
|
|
||||||
|
static std::string msg_to_string(int errnum)
|
||||||
|
{
|
||||||
|
return std::strerror(errnum);
|
||||||
|
}
|
||||||
|
|
||||||
|
static std::string msg_to_string(std::system_error &err)
|
||||||
|
{
|
||||||
|
return err.what();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
} // namespace mavconn
|
||||||
|
|
||||||
|
#endif /* DEVICE_ERROR_HPP */
|
||||||
@@ -0,0 +1,69 @@
|
|||||||
|
/**
|
||||||
|
* @brief MAVConn message buffer class (internal)
|
||||||
|
* @file msgbuffer.hpp
|
||||||
|
* @author Vladimir Ermakov <vooon341@gmail.com>
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* libmavconn
|
||||||
|
* Copyright 2014,2015,2016 Vladimir Ermakov, All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of the mavros package and subject to the license terms
|
||||||
|
* in the top-level LICENSE file of the mavros repository.
|
||||||
|
* https://github.com/mavlink/mavros/tree/master/LICENSE.md
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <cstdint>
|
||||||
|
#include <cstring>
|
||||||
|
#include <cassert>
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Message buffer for internal use in libmavconn
|
||||||
|
*/
|
||||||
|
struct MsgBuffer
|
||||||
|
{
|
||||||
|
//! Maximum buffer size with padding for CRC bytes (280 + padding)
|
||||||
|
static constexpr ssize_t MAX_PACKET_LEN = 255;
|
||||||
|
static constexpr ssize_t MAX_SIZE = MAX_PACKET_LEN + 16;
|
||||||
|
uint8_t data[MAX_SIZE];
|
||||||
|
ssize_t len;
|
||||||
|
ssize_t pos;
|
||||||
|
|
||||||
|
MsgBuffer() : pos(0),
|
||||||
|
len(0)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Buffer constructor for send_bytes()
|
||||||
|
* @param[in] nbytes should be less than MAX_SIZE
|
||||||
|
*/
|
||||||
|
MsgBuffer(const uint8_t *bytes, ssize_t nbytes) : pos(0),
|
||||||
|
len(nbytes)
|
||||||
|
{
|
||||||
|
assert(0 < nbytes && nbytes < MAX_SIZE);
|
||||||
|
std::memcpy(data, bytes, nbytes);
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual ~MsgBuffer()
|
||||||
|
{
|
||||||
|
pos = 0;
|
||||||
|
len = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t *dpos()
|
||||||
|
{
|
||||||
|
return data + pos;
|
||||||
|
}
|
||||||
|
|
||||||
|
ssize_t nbytes()
|
||||||
|
{
|
||||||
|
return len - pos;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
} // namespace wescore
|
||||||
202
scout_base/src/scout_sdk/src/driver/async_io/src/async_can.cpp
Normal file
202
scout_base/src/scout_sdk/src/driver/async_io/src/async_can.cpp
Normal file
@@ -0,0 +1,202 @@
|
|||||||
|
/*
|
||||||
|
* async_can.cpp
|
||||||
|
*
|
||||||
|
* Created on: Jun 10, 2019 02:25
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
* Copyright (c) 2016 UAVCAN Team
|
||||||
|
*/
|
||||||
|
|
||||||
|
// This is needed to enable necessary declarations in sys/
|
||||||
|
#ifndef _GNU_SOURCE
|
||||||
|
#define _GNU_SOURCE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "async_io/async_can.hpp"
|
||||||
|
|
||||||
|
#include <net/if.h>
|
||||||
|
#include <poll.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
|
||||||
|
#include <cassert>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "asyncio_utils.hpp"
|
||||||
|
|
||||||
|
using namespace wescore;
|
||||||
|
|
||||||
|
using asio::buffer;
|
||||||
|
using asio::io_service;
|
||||||
|
using std::error_code;
|
||||||
|
|
||||||
|
std::atomic<size_t> ASyncCAN::conn_id_counter{0};
|
||||||
|
|
||||||
|
ASyncCAN::ASyncCAN(std::string device) : tx_total_frames(0),
|
||||||
|
rx_total_frames(0),
|
||||||
|
last_tx_total_frames(0),
|
||||||
|
last_rx_total_frames(0),
|
||||||
|
last_iostat(steady_clock::now()),
|
||||||
|
io_service(),
|
||||||
|
stream(io_service)
|
||||||
|
{
|
||||||
|
conn_id = conn_id_counter.fetch_add(1);
|
||||||
|
open(device);
|
||||||
|
}
|
||||||
|
|
||||||
|
ASyncCAN::~ASyncCAN()
|
||||||
|
{
|
||||||
|
close();
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncCAN::open(std::string device)
|
||||||
|
{
|
||||||
|
const size_t iface_name_size = strlen(device.c_str()) + 1;
|
||||||
|
if (iface_name_size > IFNAMSIZ)
|
||||||
|
return;
|
||||||
|
|
||||||
|
can_fd_ = socket(PF_CAN, SOCK_RAW | SOCK_NONBLOCK, CAN_RAW);
|
||||||
|
if (can_fd_ < 0)
|
||||||
|
return;
|
||||||
|
|
||||||
|
struct ifreq ifr;
|
||||||
|
memset(&ifr, 0, sizeof(ifr));
|
||||||
|
memcpy(ifr.ifr_name, device.c_str(), iface_name_size);
|
||||||
|
|
||||||
|
const int ioctl_result = ioctl(can_fd_, SIOCGIFINDEX, &ifr);
|
||||||
|
if (ioctl_result < 0)
|
||||||
|
close();
|
||||||
|
|
||||||
|
struct sockaddr_can addr;
|
||||||
|
memset(&addr, 0, sizeof(addr));
|
||||||
|
addr.can_family = AF_CAN;
|
||||||
|
addr.can_ifindex = ifr.ifr_ifindex;
|
||||||
|
|
||||||
|
const int bind_result = bind(can_fd_, (struct sockaddr *)&addr, sizeof(addr));
|
||||||
|
if (bind_result < 0)
|
||||||
|
close();
|
||||||
|
;
|
||||||
|
|
||||||
|
can_interface_opened_ = true;
|
||||||
|
|
||||||
|
// NOTE: shared_from_this() should not be used in constructors
|
||||||
|
|
||||||
|
// give some work to io_service before start
|
||||||
|
stream.assign(can_fd_);
|
||||||
|
io_service.post(std::bind(&ASyncCAN::do_read, this, std::ref(rcv_frame), std::ref(stream)));
|
||||||
|
|
||||||
|
// run io_service for async io
|
||||||
|
io_thread = std::thread([this]() {
|
||||||
|
set_this_thread_name("mcan%zu", conn_id);
|
||||||
|
io_service.run();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncCAN::close()
|
||||||
|
{
|
||||||
|
// lock_guard lock(mutex);
|
||||||
|
// if (!is_open())
|
||||||
|
// return;
|
||||||
|
|
||||||
|
const int close_result = ::close(can_fd_);
|
||||||
|
can_fd_ = -1;
|
||||||
|
|
||||||
|
io_service.stop();
|
||||||
|
|
||||||
|
if (io_thread.joinable())
|
||||||
|
io_thread.join();
|
||||||
|
|
||||||
|
io_service.reset();
|
||||||
|
|
||||||
|
can_interface_opened_ = false;
|
||||||
|
|
||||||
|
if (port_closed_cb)
|
||||||
|
port_closed_cb();
|
||||||
|
}
|
||||||
|
|
||||||
|
ASyncCAN::IOStat ASyncCAN::get_iostat()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::recursive_mutex> lock(iostat_mutex);
|
||||||
|
IOStat stat;
|
||||||
|
|
||||||
|
stat.tx_total_frames = tx_total_frames;
|
||||||
|
stat.rx_total_frames = rx_total_frames;
|
||||||
|
|
||||||
|
auto d_tx = stat.tx_total_frames - last_tx_total_frames;
|
||||||
|
auto d_rx = stat.rx_total_frames - last_rx_total_frames;
|
||||||
|
last_tx_total_frames = stat.tx_total_frames;
|
||||||
|
last_rx_total_frames = stat.rx_total_frames;
|
||||||
|
|
||||||
|
auto now = steady_clock::now();
|
||||||
|
auto dt = now - last_iostat;
|
||||||
|
last_iostat = now;
|
||||||
|
|
||||||
|
float dt_s = std::chrono::duration_cast<std::chrono::seconds>(dt).count();
|
||||||
|
|
||||||
|
stat.tx_speed = d_tx / dt_s;
|
||||||
|
stat.rx_speed = d_rx / dt_s;
|
||||||
|
|
||||||
|
return stat;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncCAN::iostat_tx_add(size_t frame)
|
||||||
|
{
|
||||||
|
tx_total_frames += frame;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncCAN::iostat_rx_add(size_t frame)
|
||||||
|
{
|
||||||
|
rx_total_frames += frame;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncCAN::send_frame(const can_frame &tx_frame)
|
||||||
|
{
|
||||||
|
iostat_tx_add(1);
|
||||||
|
stream.async_write_some(asio::buffer(&tx_frame, sizeof(tx_frame)),
|
||||||
|
[](error_code error, size_t bytes_transferred) {
|
||||||
|
// std::cout << "frame sent" << std::endl;
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncCAN::call_receive_callback(can_frame *rx_frame)
|
||||||
|
{
|
||||||
|
// keep track of statistics
|
||||||
|
iostat_rx_add(1);
|
||||||
|
|
||||||
|
// call the actual parser
|
||||||
|
if (receive_cb)
|
||||||
|
receive_cb(rx_frame);
|
||||||
|
else
|
||||||
|
default_receive_callback(rx_frame);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncCAN::default_receive_callback(can_frame *rx_frame)
|
||||||
|
{
|
||||||
|
// do nothing
|
||||||
|
// std::cerr << "no callback function set" << std::endl;
|
||||||
|
std::cout << std::hex << rx_frame->can_id << " ";
|
||||||
|
for (int i = 0; i < rx_frame->can_dlc; i++)
|
||||||
|
std::cout << std::hex << int(rx_frame->data[i]) << " ";
|
||||||
|
std::cout << std::dec << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncCAN::do_read(struct can_frame &rec_frame, asio::posix::basic_stream_descriptor<> &stream)
|
||||||
|
{
|
||||||
|
auto sthis = shared_from_this();
|
||||||
|
stream.async_read_some(
|
||||||
|
asio::buffer(&rcv_frame, sizeof(rcv_frame)),
|
||||||
|
[sthis](error_code error, size_t bytes_transferred) {
|
||||||
|
if (error)
|
||||||
|
{
|
||||||
|
std::cerr << "read error in connection " << sthis->conn_id << " : "
|
||||||
|
<< error.message().c_str() << std::endl;
|
||||||
|
sthis->close();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
sthis->call_receive_callback(&sthis->rcv_frame);
|
||||||
|
sthis->do_read(std::ref(sthis->rcv_frame), std::ref(sthis->stream));
|
||||||
|
});
|
||||||
|
}
|
||||||
@@ -0,0 +1,340 @@
|
|||||||
|
/*
|
||||||
|
* async_serial.cpp
|
||||||
|
*
|
||||||
|
* Created on: Nov 23, 2018 22:24
|
||||||
|
* Description: asynchronous serial communication using asio
|
||||||
|
* adapted from code in libmavconn
|
||||||
|
*
|
||||||
|
* Main changes: 1. Removed dependency on Boost (asio standalone
|
||||||
|
* and C++ STL only)
|
||||||
|
* 2. Removed dependency on console-bridge
|
||||||
|
* 3. Removed mavlink related code
|
||||||
|
* 4. Removed UDP/TCP related code
|
||||||
|
*
|
||||||
|
* Author: Vladimir Ermakov <vooon341@gmail.com>
|
||||||
|
* Ruixiang Du <ruixiang.du@gmail.com>
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* libmavconn
|
||||||
|
* Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of the mavros package and subject to the license terms
|
||||||
|
* in the top-level LICENSE file of the mavros repository.
|
||||||
|
* https://github.com/mavlink/mavros/tree/master/LICENSE.md
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <cassert>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "async_io/async_serial.hpp"
|
||||||
|
#include "asyncio_utils.hpp"
|
||||||
|
|
||||||
|
#if defined(__linux__)
|
||||||
|
#include <linux/serial.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
using namespace wescore;
|
||||||
|
|
||||||
|
using asio::buffer;
|
||||||
|
using asio::io_service;
|
||||||
|
using std::error_code;
|
||||||
|
|
||||||
|
std::atomic<size_t> ASyncSerial::conn_id_counter{0};
|
||||||
|
|
||||||
|
ASyncSerial::ASyncSerial(std::string device, unsigned baudrate, bool hwflow) : tx_total_bytes(0),
|
||||||
|
rx_total_bytes(0),
|
||||||
|
last_tx_total_bytes(0),
|
||||||
|
last_rx_total_bytes(0),
|
||||||
|
last_iostat(steady_clock::now()),
|
||||||
|
tx_in_progress(false),
|
||||||
|
tx_q{},
|
||||||
|
rx_buf{},
|
||||||
|
io_service(),
|
||||||
|
serial_dev(io_service)
|
||||||
|
{
|
||||||
|
conn_id = conn_id_counter.fetch_add(1);
|
||||||
|
open(device, baudrate, hwflow);
|
||||||
|
}
|
||||||
|
|
||||||
|
ASyncSerial::~ASyncSerial()
|
||||||
|
{
|
||||||
|
close();
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::open(std::string device, unsigned baudrate, bool hwflow)
|
||||||
|
{
|
||||||
|
using SPB = asio::serial_port_base;
|
||||||
|
|
||||||
|
std::cout << "connection: " << conn_id << " , device: " << device.c_str() << " @ " << baudrate << "bps" << std::endl;
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
serial_dev.open(device);
|
||||||
|
|
||||||
|
// Set baudrate and 8N1 mode
|
||||||
|
serial_dev.set_option(SPB::baud_rate(baudrate));
|
||||||
|
serial_dev.set_option(SPB::character_size(8));
|
||||||
|
serial_dev.set_option(SPB::parity(SPB::parity::none));
|
||||||
|
serial_dev.set_option(SPB::stop_bits(SPB::stop_bits::one));
|
||||||
|
serial_dev.set_option(SPB::flow_control((hwflow) ? SPB::flow_control::hardware : SPB::flow_control::none));
|
||||||
|
|
||||||
|
#if defined(__linux__)
|
||||||
|
// Enable low latency mode on Linux
|
||||||
|
{
|
||||||
|
int fd = serial_dev.native_handle();
|
||||||
|
|
||||||
|
struct serial_struct ser_info;
|
||||||
|
ioctl(fd, TIOCGSERIAL, &ser_info);
|
||||||
|
|
||||||
|
ser_info.flags |= ASYNC_LOW_LATENCY;
|
||||||
|
|
||||||
|
ioctl(fd, TIOCSSERIAL, &ser_info);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
catch (std::system_error &err)
|
||||||
|
{
|
||||||
|
throw DeviceError("serial", err);
|
||||||
|
}
|
||||||
|
|
||||||
|
// NOTE: shared_from_this() should not be used in constructors
|
||||||
|
|
||||||
|
// give some work to io_service before start
|
||||||
|
io_service.post(std::bind(&ASyncSerial::do_read, this));
|
||||||
|
|
||||||
|
// run io_service for async io
|
||||||
|
io_thread = std::thread([this]() {
|
||||||
|
set_this_thread_name("mserial%zu", conn_id);
|
||||||
|
io_service.run();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::close()
|
||||||
|
{
|
||||||
|
lock_guard lock(mutex);
|
||||||
|
if (!is_open())
|
||||||
|
return;
|
||||||
|
|
||||||
|
serial_dev.cancel();
|
||||||
|
serial_dev.close();
|
||||||
|
|
||||||
|
io_service.stop();
|
||||||
|
|
||||||
|
if (io_thread.joinable())
|
||||||
|
io_thread.join();
|
||||||
|
|
||||||
|
io_service.reset();
|
||||||
|
|
||||||
|
if (port_closed_cb)
|
||||||
|
port_closed_cb();
|
||||||
|
}
|
||||||
|
|
||||||
|
ASyncSerial::IOStat ASyncSerial::get_iostat()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::recursive_mutex> lock(iostat_mutex);
|
||||||
|
IOStat stat;
|
||||||
|
|
||||||
|
stat.tx_total_bytes = tx_total_bytes;
|
||||||
|
stat.rx_total_bytes = rx_total_bytes;
|
||||||
|
|
||||||
|
auto d_tx = stat.tx_total_bytes - last_tx_total_bytes;
|
||||||
|
auto d_rx = stat.rx_total_bytes - last_rx_total_bytes;
|
||||||
|
last_tx_total_bytes = stat.tx_total_bytes;
|
||||||
|
last_rx_total_bytes = stat.rx_total_bytes;
|
||||||
|
|
||||||
|
auto now = steady_clock::now();
|
||||||
|
auto dt = now - last_iostat;
|
||||||
|
last_iostat = now;
|
||||||
|
|
||||||
|
float dt_s = std::chrono::duration_cast<std::chrono::seconds>(dt).count();
|
||||||
|
|
||||||
|
stat.tx_speed = d_tx / dt_s;
|
||||||
|
stat.rx_speed = d_rx / dt_s;
|
||||||
|
|
||||||
|
return stat;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::iostat_tx_add(size_t bytes)
|
||||||
|
{
|
||||||
|
tx_total_bytes += bytes;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::iostat_rx_add(size_t bytes)
|
||||||
|
{
|
||||||
|
rx_total_bytes += bytes;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::send_bytes(const uint8_t *bytes, size_t length)
|
||||||
|
{
|
||||||
|
if (!is_open())
|
||||||
|
{
|
||||||
|
std::cerr << "send: channel closed!"
|
||||||
|
<< " connection id: " << conn_id << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
{
|
||||||
|
lock_guard lock(mutex);
|
||||||
|
|
||||||
|
if (tx_q.size() >= MAX_TXQ_SIZE)
|
||||||
|
throw std::length_error("ASyncSerial::send_bytes: TX queue overflow");
|
||||||
|
|
||||||
|
tx_q.emplace_back(bytes, length);
|
||||||
|
}
|
||||||
|
io_service.post(std::bind(&ASyncSerial::do_write, shared_from_this(), true));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::call_receive_callback(uint8_t *buf, const std::size_t bufsize, std::size_t bytes_received)
|
||||||
|
{
|
||||||
|
assert(bufsize >= bytes_received);
|
||||||
|
|
||||||
|
// keep track of statistics
|
||||||
|
iostat_rx_add(bytes_received);
|
||||||
|
|
||||||
|
// call the actual parser
|
||||||
|
if (receive_cb)
|
||||||
|
receive_cb(buf, bufsize, bytes_received);
|
||||||
|
else
|
||||||
|
default_receive_callback(buf, bufsize, bytes_received);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::default_receive_callback(uint8_t *buf, const size_t bufsize, size_t bytes_received)
|
||||||
|
{
|
||||||
|
// do nothing
|
||||||
|
std::cerr << "no callback function set" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::do_read(void)
|
||||||
|
{
|
||||||
|
auto sthis = shared_from_this();
|
||||||
|
serial_dev.async_read_some(
|
||||||
|
buffer(rx_buf),
|
||||||
|
[sthis](error_code error, size_t bytes_transferred) {
|
||||||
|
if (error)
|
||||||
|
{
|
||||||
|
std::cerr << "read error in connection " << sthis->conn_id << " : "
|
||||||
|
<< error.message().c_str() << std::endl;
|
||||||
|
sthis->close();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
sthis->call_receive_callback(sthis->rx_buf.data(), sthis->rx_buf.size(), bytes_transferred);
|
||||||
|
sthis->do_read();
|
||||||
|
});
|
||||||
|
|
||||||
|
// std::cout << rx_buf.data() << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ASyncSerial::do_write(bool check_tx_state)
|
||||||
|
{
|
||||||
|
if (check_tx_state && tx_in_progress)
|
||||||
|
return;
|
||||||
|
|
||||||
|
lock_guard lock(mutex);
|
||||||
|
if (tx_q.empty())
|
||||||
|
return;
|
||||||
|
|
||||||
|
tx_in_progress = true;
|
||||||
|
auto sthis = shared_from_this();
|
||||||
|
auto &buf_ref = tx_q.front();
|
||||||
|
serial_dev.async_write_some(
|
||||||
|
buffer(buf_ref.dpos(), buf_ref.nbytes()),
|
||||||
|
[sthis, &buf_ref](error_code error, size_t bytes_transferred) {
|
||||||
|
assert(bytes_transferred <= buf_ref.len);
|
||||||
|
|
||||||
|
if (error)
|
||||||
|
{
|
||||||
|
std::cerr << "write error in connection " << sthis->conn_id << " : "
|
||||||
|
<< error.message().c_str() << std::endl;
|
||||||
|
sthis->close();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
sthis->iostat_tx_add(bytes_transferred);
|
||||||
|
lock_guard lock(sthis->mutex);
|
||||||
|
|
||||||
|
if (sthis->tx_q.empty())
|
||||||
|
{
|
||||||
|
sthis->tx_in_progress = false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
buf_ref.pos += bytes_transferred;
|
||||||
|
if (buf_ref.nbytes() == 0)
|
||||||
|
{
|
||||||
|
sthis->tx_q.pop_front();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!sthis->tx_q.empty())
|
||||||
|
sthis->do_write(false);
|
||||||
|
else
|
||||||
|
sthis->tx_in_progress = false;
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
//---------------------------------------------------------------------------------------//
|
||||||
|
|
||||||
|
namespace
|
||||||
|
{
|
||||||
|
ASyncSerial::Ptr url_parse_serial(
|
||||||
|
std::string path, std::string query, bool hwflow)
|
||||||
|
{
|
||||||
|
std::string file_path;
|
||||||
|
int baudrate;
|
||||||
|
|
||||||
|
url_parse_host(path, file_path, baudrate, ASyncSerial::DEFAULT_DEVICE, ASyncSerial::DEFAULT_BAUDRATE);
|
||||||
|
url_parse_query(query);
|
||||||
|
|
||||||
|
return std::make_shared<ASyncSerial>(file_path, baudrate, hwflow);
|
||||||
|
}
|
||||||
|
} // namespace
|
||||||
|
|
||||||
|
ASyncSerial::Ptr ASyncSerial::open_url(std::string url)
|
||||||
|
{
|
||||||
|
/* Based on code found here:
|
||||||
|
* http://stackoverflow.com/questions/2616011/easy-way-to-parse-a-url-in-c-cross-platform
|
||||||
|
*/
|
||||||
|
|
||||||
|
const std::string proto_end("://");
|
||||||
|
std::string proto;
|
||||||
|
std::string host;
|
||||||
|
std::string path;
|
||||||
|
std::string query;
|
||||||
|
|
||||||
|
auto proto_it = std::search(
|
||||||
|
url.begin(), url.end(),
|
||||||
|
proto_end.begin(), proto_end.end());
|
||||||
|
if (proto_it == url.end())
|
||||||
|
{
|
||||||
|
// looks like file path
|
||||||
|
std::cout << "URL: " << url.c_str() << " looks like file path" << std::endl;
|
||||||
|
return url_parse_serial(url, "", false);
|
||||||
|
}
|
||||||
|
|
||||||
|
// copy protocol
|
||||||
|
proto.reserve(std::distance(url.begin(), proto_it));
|
||||||
|
std::transform(url.begin(), proto_it,
|
||||||
|
std::back_inserter(proto),
|
||||||
|
std::ref(tolower));
|
||||||
|
|
||||||
|
// copy host
|
||||||
|
std::advance(proto_it, proto_end.length());
|
||||||
|
auto path_it = std::find(proto_it, url.end(), '/');
|
||||||
|
std::transform(proto_it, path_it,
|
||||||
|
std::back_inserter(host),
|
||||||
|
std::ref(tolower));
|
||||||
|
|
||||||
|
// copy path, and query if exists
|
||||||
|
auto query_it = std::find(path_it, url.end(), '?');
|
||||||
|
path.assign(path_it, query_it);
|
||||||
|
if (query_it != url.end())
|
||||||
|
++query_it;
|
||||||
|
query.assign(query_it, url.end());
|
||||||
|
|
||||||
|
if (proto == "serial")
|
||||||
|
return url_parse_serial(path, query, false);
|
||||||
|
else if (proto == "serial-hwfc")
|
||||||
|
return url_parse_serial(path, query, true);
|
||||||
|
else
|
||||||
|
throw DeviceError("url", "Unknown URL type");
|
||||||
|
}
|
||||||
@@ -0,0 +1,123 @@
|
|||||||
|
/**
|
||||||
|
* @brief MAVConn async serial utility class
|
||||||
|
* @file async_utils.hpp
|
||||||
|
* @author Vladimir Ermakov <vooon341@gmail.com>
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* libmavconn
|
||||||
|
* Copyright 2013,2014,2015,2016 Vladimir Ermakov, All rights reserved.
|
||||||
|
*
|
||||||
|
* This file is part of the mavros package and subject to the license terms
|
||||||
|
* in the top-level LICENSE file of the mavros repository.
|
||||||
|
* https://github.com/mavlink/mavros/tree/master/LICENSE.md
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef ASYNCIO_UTILS_HPP
|
||||||
|
#define ASYNCIO_UTILS_HPP
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <algorithm>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
template <typename... Args>
|
||||||
|
std::string format(const std::string &fmt, Args... args)
|
||||||
|
{
|
||||||
|
// C++11 specify that string store elements continously
|
||||||
|
std::string ret;
|
||||||
|
|
||||||
|
auto sz = std::snprintf(nullptr, 0, fmt.c_str(), args...);
|
||||||
|
ret.reserve(sz + 1);
|
||||||
|
ret.resize(sz); // to be sure there have room for \0
|
||||||
|
std::snprintf(&ret.front(), ret.capacity() + 1, fmt.c_str(), args...);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename... Args>
|
||||||
|
bool set_this_thread_name(const std::string &name, Args &&... args)
|
||||||
|
{
|
||||||
|
auto new_name = format(name, std::forward<Args>(args)...);
|
||||||
|
|
||||||
|
#ifdef __APPLE__
|
||||||
|
return pthread_setname_np(new_name.c_str()) == 0;
|
||||||
|
#else
|
||||||
|
pthread_t pth = pthread_self();
|
||||||
|
return pthread_setname_np(pth, new_name.c_str()) == 0;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse host:port pairs
|
||||||
|
*/
|
||||||
|
void url_parse_host(std::string host,
|
||||||
|
std::string &host_out, int &port_out,
|
||||||
|
const std::string def_host, const int def_port)
|
||||||
|
{
|
||||||
|
std::string port;
|
||||||
|
|
||||||
|
auto sep_it = std::find(host.begin(), host.end(), ':');
|
||||||
|
if (sep_it == host.end())
|
||||||
|
{
|
||||||
|
// host
|
||||||
|
if (!host.empty())
|
||||||
|
{
|
||||||
|
host_out = host;
|
||||||
|
port_out = def_port;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
host_out = def_host;
|
||||||
|
port_out = def_port;
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sep_it == host.begin())
|
||||||
|
{
|
||||||
|
// :port
|
||||||
|
host_out = def_host;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// host:port
|
||||||
|
host_out.assign(host.begin(), sep_it);
|
||||||
|
}
|
||||||
|
|
||||||
|
port.assign(sep_it + 1, host.end());
|
||||||
|
port_out = std::stoi(port);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parse ?ids=sid,cid
|
||||||
|
*/
|
||||||
|
void url_parse_query(std::string query)
|
||||||
|
{
|
||||||
|
const std::string ids_end("ids=");
|
||||||
|
std::string sys, comp;
|
||||||
|
|
||||||
|
if (query.empty())
|
||||||
|
return;
|
||||||
|
|
||||||
|
auto ids_it = std::search(query.begin(), query.end(),
|
||||||
|
ids_end.begin(), ids_end.end());
|
||||||
|
if (ids_it == query.end())
|
||||||
|
{
|
||||||
|
std::cerr << "URL: unknown query arguments" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::advance(ids_it, ids_end.length());
|
||||||
|
auto comma_it = std::find(ids_it, query.end(), ',');
|
||||||
|
if (comma_it == query.end())
|
||||||
|
{
|
||||||
|
std::cerr << "URL: no comma in ids= query" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
sys.assign(ids_it, comma_it);
|
||||||
|
comp.assign(comma_it + 1, query.end());
|
||||||
|
}
|
||||||
|
} // namespace wescore
|
||||||
|
|
||||||
|
#endif /* ASYNCIO_UTILS_HPP */
|
||||||
@@ -0,0 +1,9 @@
|
|||||||
|
# Add executables
|
||||||
|
add_executable(test_aserial test_aserial.cpp)
|
||||||
|
target_link_libraries(test_aserial asyncio)
|
||||||
|
|
||||||
|
add_executable(test_asio_can test_asio_can.cpp)
|
||||||
|
target_link_libraries(test_asio_can asio pthread)
|
||||||
|
|
||||||
|
add_executable(test_acan test_acan.cpp)
|
||||||
|
target_link_libraries(test_acan asyncio)
|
||||||
@@ -0,0 +1,60 @@
|
|||||||
|
#include <iostream>
|
||||||
|
#include "async_io/async_can.hpp"
|
||||||
|
|
||||||
|
using namespace wescore;
|
||||||
|
|
||||||
|
void parse_buffer(uint8_t *buf, const size_t bufsize, size_t bytes_received)
|
||||||
|
{
|
||||||
|
std::cout << "parser called" << std::endl;
|
||||||
|
|
||||||
|
// mavlink::mavlink_status_t status;
|
||||||
|
// mavlink::mavlink_message_t message;
|
||||||
|
|
||||||
|
for (; bytes_received > 0; bytes_received--)
|
||||||
|
{
|
||||||
|
auto c = *buf++;
|
||||||
|
|
||||||
|
// // based on mavlink_parse_char()
|
||||||
|
// auto msg_received = static_cast<Framing>(mavlink::mavlink_frame_char_buffer(&m_buffer, &m_status, c, &message, &status));
|
||||||
|
// if (msg_received == Framing::bad_crc || msg_received == Framing::bad_signature) {
|
||||||
|
// mavlink::_mav_parse_error(&m_status);
|
||||||
|
// m_status.msg_received = mavlink::MAVLINK_FRAMING_INCOMPLETE;
|
||||||
|
// m_status.parse_state = mavlink::MAVLINK_PARSE_STATE_IDLE;
|
||||||
|
// if (c == MAVLINK_STX) {
|
||||||
|
// m_status.parse_state = mavlink::MAVLINK_PARSE_STATE_GOT_STX;
|
||||||
|
// m_buffer.len = 0;
|
||||||
|
// mavlink::mavlink_start_checksum(&m_buffer);
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
|
||||||
|
// if (msg_received != Framing::incomplete) {
|
||||||
|
// log_recv(pfx, message, msg_received);
|
||||||
|
|
||||||
|
// if (message_received_cb)
|
||||||
|
// message_received_cb(&message, msg_received);
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
std::shared_ptr<ASyncCAN> canbus = std::make_shared<ASyncCAN>("can1");
|
||||||
|
|
||||||
|
// canbus->set_receive_callback(parse_buffer);
|
||||||
|
|
||||||
|
// if (canbus->is_open())
|
||||||
|
// std::cout << "can bus connected" << std::endl;
|
||||||
|
|
||||||
|
struct can_frame frame;
|
||||||
|
frame.can_id = 0x123;
|
||||||
|
frame.can_dlc = 2;
|
||||||
|
frame.data[0] = 0x11;
|
||||||
|
frame.data[1] = 0x23;
|
||||||
|
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
// canbus->send_bytes(data, 3);
|
||||||
|
canbus->send_frame(frame);
|
||||||
|
sleep(1);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,64 @@
|
|||||||
|
/*
|
||||||
|
* test_interface.cpp
|
||||||
|
*
|
||||||
|
* Created on: Dec 25, 2016
|
||||||
|
* Author: rdu
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "async_io/async_serial.hpp"
|
||||||
|
|
||||||
|
using namespace wescore;
|
||||||
|
|
||||||
|
void parse_buffer(uint8_t *buf, const size_t bufsize, size_t bytes_received)
|
||||||
|
{
|
||||||
|
std::cout << "parser called" << std::endl;
|
||||||
|
|
||||||
|
// mavlink::mavlink_status_t status;
|
||||||
|
// mavlink::mavlink_message_t message;
|
||||||
|
|
||||||
|
for (; bytes_received > 0; bytes_received--)
|
||||||
|
{
|
||||||
|
auto c = *buf++;
|
||||||
|
|
||||||
|
// // based on mavlink_parse_char()
|
||||||
|
// auto msg_received = static_cast<Framing>(mavlink::mavlink_frame_char_buffer(&m_buffer, &m_status, c, &message, &status));
|
||||||
|
// if (msg_received == Framing::bad_crc || msg_received == Framing::bad_signature) {
|
||||||
|
// mavlink::_mav_parse_error(&m_status);
|
||||||
|
// m_status.msg_received = mavlink::MAVLINK_FRAMING_INCOMPLETE;
|
||||||
|
// m_status.parse_state = mavlink::MAVLINK_PARSE_STATE_IDLE;
|
||||||
|
// if (c == MAVLINK_STX) {
|
||||||
|
// m_status.parse_state = mavlink::MAVLINK_PARSE_STATE_GOT_STX;
|
||||||
|
// m_buffer.len = 0;
|
||||||
|
// mavlink::mavlink_start_checksum(&m_buffer);
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
|
||||||
|
// if (msg_received != Framing::incomplete) {
|
||||||
|
// log_recv(pfx, message, msg_received);
|
||||||
|
|
||||||
|
// if (message_received_cb)
|
||||||
|
// message_received_cb(&message, msg_received);
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
// ASyncSerial::Ptr serial = ASyncSerial::open_url("/dev/ttyUSB0:115200");
|
||||||
|
std::shared_ptr<ASyncSerial> serial = std::make_shared<ASyncSerial>("/dev/pts/6", 115200);
|
||||||
|
|
||||||
|
serial->set_receive_callback(parse_buffer);
|
||||||
|
|
||||||
|
if (serial->is_open())
|
||||||
|
std::cout << "serial port opened" << std::endl;
|
||||||
|
|
||||||
|
uint8_t data[8] = {'a','b','c'};
|
||||||
|
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
serial->send_bytes(data, 3);
|
||||||
|
sleep(1);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,79 @@
|
|||||||
|
// source: https://stackoverflow.com/questions/10467178/boostasio-over-socketcan
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include <net/if.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <sys/socket.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
|
||||||
|
#include <linux/can.h>
|
||||||
|
#include <linux/can/raw.h>
|
||||||
|
|
||||||
|
#define ASIO_ENABLE_OLD_SERVICES
|
||||||
|
#define ASIO_HAS_POSIX_STREAM_DESCRIPTOR
|
||||||
|
|
||||||
|
#include "asio.hpp"
|
||||||
|
#include <functional>
|
||||||
|
|
||||||
|
#include "asio/posix/basic_stream_descriptor.hpp"
|
||||||
|
|
||||||
|
void data_send(void)
|
||||||
|
{
|
||||||
|
std::cout << "omg sent" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
void data_rec(struct can_frame &rec_frame,
|
||||||
|
asio::posix::basic_stream_descriptor<> &stream)
|
||||||
|
{
|
||||||
|
std::cout << std::hex << rec_frame.can_id << " ";
|
||||||
|
for (int i = 0; i < rec_frame.can_dlc; i++)
|
||||||
|
{
|
||||||
|
std::cout << std::hex << int(rec_frame.data[i]) << " ";
|
||||||
|
}
|
||||||
|
std::cout << std::dec << std::endl;
|
||||||
|
stream.async_read_some(
|
||||||
|
asio::buffer(&rec_frame, sizeof(rec_frame)),
|
||||||
|
std::bind(data_rec, std::ref(rec_frame), std::ref(stream)));
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(void)
|
||||||
|
{
|
||||||
|
struct sockaddr_can addr;
|
||||||
|
struct can_frame frame;
|
||||||
|
struct can_frame rec_frame;
|
||||||
|
struct ifreq ifr;
|
||||||
|
|
||||||
|
int natsock = socket(PF_CAN, SOCK_RAW, CAN_RAW);
|
||||||
|
|
||||||
|
strcpy(ifr.ifr_name, "can1");
|
||||||
|
ioctl(natsock, SIOCGIFINDEX, &ifr);
|
||||||
|
|
||||||
|
addr.can_family = AF_CAN;
|
||||||
|
addr.can_ifindex = ifr.ifr_ifindex;
|
||||||
|
if (bind(natsock, (struct sockaddr *)&addr, sizeof(addr)) < 0)
|
||||||
|
{
|
||||||
|
perror("Error in socket bind");
|
||||||
|
return -2;
|
||||||
|
}
|
||||||
|
|
||||||
|
frame.can_id = 0x123;
|
||||||
|
frame.can_dlc = 2;
|
||||||
|
frame.data[0] = 0x11;
|
||||||
|
frame.data[1] = 0x23;
|
||||||
|
|
||||||
|
asio::io_service ios;
|
||||||
|
asio::posix::basic_stream_descriptor<> stream(ios);
|
||||||
|
stream.assign(natsock);
|
||||||
|
|
||||||
|
stream.async_write_some(asio::buffer(&frame, sizeof(frame)),
|
||||||
|
std::bind(data_send));
|
||||||
|
stream.async_read_some(
|
||||||
|
asio::buffer(&rec_frame, sizeof(rec_frame)),
|
||||||
|
std::bind(data_rec, std::ref(rec_frame), std::ref(stream)));
|
||||||
|
ios.run();
|
||||||
|
}
|
||||||
13
scout_base/src/scout_sdk/src/scout_cpp/CMakeLists.txt → scout_base/src/scout_sdk/src/scout/CMakeLists.txt
Normal file → Executable file
13
scout_base/src/scout_sdk/src/scout_cpp/CMakeLists.txt → scout_base/src/scout_sdk/src/scout/CMakeLists.txt
Normal file → Executable file
@@ -1,5 +1,5 @@
|
|||||||
cmake_minimum_required(VERSION 3.0.0)
|
cmake_minimum_required(VERSION 3.0.0)
|
||||||
project(scout_cpp)
|
project(scout_base)
|
||||||
|
|
||||||
## Put all binary files into /bin and libraries into /lib
|
## Put all binary files into /bin and libraries into /lib
|
||||||
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||||
@@ -22,12 +22,13 @@ else()
|
|||||||
endif()
|
endif()
|
||||||
|
|
||||||
## Add libraries
|
## Add libraries
|
||||||
set(SCOUT_CPP_SRC
|
set(SCOUT_BASE_SRC
|
||||||
src/scout_robot.cpp
|
src/scout_base.cpp
|
||||||
|
# src/scout_serial.cpp
|
||||||
)
|
)
|
||||||
add_library(scoutcpp STATIC ${SCOUT_CPP_SRC})
|
add_library(scout_base STATIC ${SCOUT_BASE_SRC})
|
||||||
target_link_libraries(scoutcpp scoutio)
|
target_link_libraries(scout_base asyncio stopwatch)
|
||||||
target_include_directories(scoutcpp PUBLIC
|
target_include_directories(scout_base PUBLIC
|
||||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
$<BUILD_INTERFACE:${Boost_INCLUDE_DIRS}>
|
$<BUILD_INTERFACE:${Boost_INCLUDE_DIRS}>
|
||||||
$<INSTALL_INTERFACE:include>
|
$<INSTALL_INTERFACE:include>
|
||||||
@@ -0,0 +1,80 @@
|
|||||||
|
/*
|
||||||
|
* scout_base.hpp
|
||||||
|
*
|
||||||
|
* Created on: Jun 04, 2019 01:22
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SCOUT_BASE_HPP
|
||||||
|
#define SCOUT_BASE_HPP
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <cstdint>
|
||||||
|
#include <thread>
|
||||||
|
#include <mutex>
|
||||||
|
#include <functional>
|
||||||
|
|
||||||
|
#include "stopwatch/stopwatch.h"
|
||||||
|
#include "async_io/async_can.hpp"
|
||||||
|
|
||||||
|
#include "scout/scout_state.hpp"
|
||||||
|
#include "scout/scout_command.hpp"
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
class ScoutBase
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
ScoutBase() = default;
|
||||||
|
~ScoutBase();
|
||||||
|
|
||||||
|
// do not allow copy
|
||||||
|
ScoutBase(const ScoutBase &scout) = delete;
|
||||||
|
ScoutBase &operator=(const ScoutBase &scout) = delete;
|
||||||
|
|
||||||
|
public:
|
||||||
|
void ConnectSerialPort(const std::string &port_name = "/dev/ttyUSB0", int32_t baud_rate = 115200);
|
||||||
|
void ConnectCANBus(const std::string &can_if_name = "can1");
|
||||||
|
bool IsConnectionActive() const { return serial_connected_; }
|
||||||
|
|
||||||
|
void StartCmdThread(int32_t period_ms);
|
||||||
|
|
||||||
|
// motion control
|
||||||
|
void SetMotionCommand(double linear_vel, double angular_vel,
|
||||||
|
ScoutMotionCmd::FaultClearFlag fault_clr_flag = ScoutMotionCmd::FaultClearFlag::NO_FAULT);
|
||||||
|
|
||||||
|
// light control
|
||||||
|
void SetLightCommand(ScoutLightCmd cmd);
|
||||||
|
void DisableLightCmdControl();
|
||||||
|
|
||||||
|
// get robot state
|
||||||
|
ScoutState GetScoutState();
|
||||||
|
|
||||||
|
// TODO for testing, will be set private in release
|
||||||
|
void UpdateScoutState(ScoutState &state, can_frame *rx_frame);
|
||||||
|
|
||||||
|
private:
|
||||||
|
bool serial_connected_ = false;
|
||||||
|
|
||||||
|
std::shared_ptr<ASyncCAN> can_if_;
|
||||||
|
|
||||||
|
std::thread cmd_thread_;
|
||||||
|
std::mutex scout_state_mutex_;
|
||||||
|
std::mutex motion_cmd_mutex_;
|
||||||
|
std::mutex light_cmd_mutex_;
|
||||||
|
|
||||||
|
ScoutState scout_state_;
|
||||||
|
ScoutMotionCmd current_motion_cmd_;
|
||||||
|
ScoutLightCmd current_light_cmd_;
|
||||||
|
|
||||||
|
bool light_ctrl_enabled_ = false;
|
||||||
|
bool light_ctrl_requested_ = false;
|
||||||
|
|
||||||
|
void ControlLoop(int32_t period_ms);
|
||||||
|
void ParseCANFrame(can_frame *rx_frame);
|
||||||
|
};
|
||||||
|
} // namespace wescore
|
||||||
|
|
||||||
|
#endif /* SCOUT_BASE_HPP */
|
||||||
@@ -0,0 +1,356 @@
|
|||||||
|
/*
|
||||||
|
* scout_can_protocol.h
|
||||||
|
*
|
||||||
|
* Created on: Jun 10, 2019 23:23
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SCOUT_CAN_PROTOCOL_H
|
||||||
|
#define SCOUT_CAN_PROTOCOL_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "stdint.h"
|
||||||
|
|
||||||
|
enum ScoutCANMsgIDs
|
||||||
|
{
|
||||||
|
MSG_MOTION_CONTROL_ID = 0x130,
|
||||||
|
MSG_MOTION_CONTROL_FEEDBACK_ID = 0x131,
|
||||||
|
MSG_LIGHT_CONTROL_ID = 0x140,
|
||||||
|
MSG_LIGHT_CONTROL_FEEDBACK_ID = 0x141,
|
||||||
|
MSG_SYSTEM_STATUS_FEEDBACK_ID = 0x151,
|
||||||
|
MSG_MOTOR1_DRIVER_FEEDBACK_ID = 0x200,
|
||||||
|
MSG_MOTOR2_DRIVER_FEEDBACK_ID = 0x201,
|
||||||
|
MSG_MOTOR3_DRIVER_FEEDBACK_ID = 0x202,
|
||||||
|
MSG_MOTOR4_DRIVER_FEEDBACK_ID = 0x203,
|
||||||
|
MSG_LAST_ID
|
||||||
|
};
|
||||||
|
|
||||||
|
static uint8_t Agilex_CANMsgChecksum(uint16_t id, uint8_t *data, uint8_t dlc)
|
||||||
|
{
|
||||||
|
uint8_t checksum = 0x00;
|
||||||
|
checksum = (uint8_t)(id & 0x00ff) + (uint8_t)(id >> 8) + dlc;
|
||||||
|
for (int i = 0; i < (dlc - 1); ++i)
|
||||||
|
checksum += data[i];
|
||||||
|
return checksum;
|
||||||
|
};
|
||||||
|
|
||||||
|
/*------------------------- Motion Control Message -------------------------*/
|
||||||
|
|
||||||
|
enum ControlMode
|
||||||
|
{
|
||||||
|
REMOTE_MODE = 0x00,
|
||||||
|
CMD_MODE = 0x01
|
||||||
|
};
|
||||||
|
|
||||||
|
enum FaultClearFlag
|
||||||
|
{
|
||||||
|
NO_FAULT = 0x00,
|
||||||
|
BAT_UNDER_VOL = 0x01,
|
||||||
|
BAT_OVER_VOL = 0x02,
|
||||||
|
MOTOR1_COMM = 0x03,
|
||||||
|
MOTOR2_COMM = 0x04,
|
||||||
|
MOTOR3_COMM = 0x05,
|
||||||
|
MOTOR4_COMM = 0x06,
|
||||||
|
MOTOR_DRV_OVERHEAT = 0x07,
|
||||||
|
MOTOR_OVERCURRENT = 0x08
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_MOTION_CONTROL_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct CmdDef
|
||||||
|
{
|
||||||
|
uint8_t control_mode;
|
||||||
|
uint8_t fault_clear_flag;
|
||||||
|
int8_t linear_velocity_cmd;
|
||||||
|
int8_t angular_velocity_cmd;
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t reserved1;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} cmd;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} MotionControlMessage;
|
||||||
|
|
||||||
|
/*-------------------------- Light Control Message -------------------------*/
|
||||||
|
|
||||||
|
enum LightControlFlag
|
||||||
|
{
|
||||||
|
DISABLE_LIGHT_CTRL = 0x00,
|
||||||
|
ENABLE_LIGHT_CTRL = 0x01
|
||||||
|
};
|
||||||
|
|
||||||
|
enum LightMode
|
||||||
|
{
|
||||||
|
CONST_OFF = 0x00,
|
||||||
|
CONST_ON = 0x01,
|
||||||
|
BREATH = 0x02,
|
||||||
|
CUSTOM = 0x03
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_LIGHT_CONTROL_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct CmdDef
|
||||||
|
{
|
||||||
|
uint8_t light_ctrl_enable;
|
||||||
|
uint8_t front_light_mode;
|
||||||
|
uint8_t front_light_custom;
|
||||||
|
uint8_t rear_light_mode;
|
||||||
|
uint8_t rear_light_custom;
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} cmd;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} LightControlMessage;
|
||||||
|
|
||||||
|
/*--------------------- Motion Control Feedback Message --------------------*/
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_MOTION_CONTROL_FEEDBACK_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct StatusDef
|
||||||
|
{
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
int16_t value;
|
||||||
|
} linear_velocity;
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
int16_t value;
|
||||||
|
} angular_velocity;
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t reserved1;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} status;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} MotionStatusMessage;
|
||||||
|
|
||||||
|
/*---------------------- Light Control Feedback Message --------------------*/
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_LIGHT_CONTROL_FEEDBACK_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct StatusDef
|
||||||
|
{
|
||||||
|
uint8_t light_ctrl_enable;
|
||||||
|
uint8_t front_light_mode;
|
||||||
|
uint8_t front_light_custom;
|
||||||
|
uint8_t rear_light_mode;
|
||||||
|
uint8_t rear_light_custom;
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} status;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} LightStatusMessage;
|
||||||
|
|
||||||
|
/*---------------------- System Status Feedback Message --------------------*/
|
||||||
|
|
||||||
|
enum BaseState
|
||||||
|
{
|
||||||
|
BASE_NORMAL,
|
||||||
|
BASE_ESTOP,
|
||||||
|
BASE_EXCEPTION
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_SYSTEM_STATUS_FEEDBACK_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct StatusDef
|
||||||
|
{
|
||||||
|
uint8_t base_state;
|
||||||
|
uint8_t control_mode;
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
uint16_t value;
|
||||||
|
} battery_voltage;
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
uint16_t value;
|
||||||
|
} fault_code;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} status;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} SystemStatusMessage;
|
||||||
|
|
||||||
|
/*--------------------- Motor 1 Driver Feedback Message --------------------*/
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_MOTOR1_DRIVER_FEEDBACK_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct StatusDef
|
||||||
|
{
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
uint16_t value;
|
||||||
|
} current;
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
int16_t value;
|
||||||
|
} rpm;
|
||||||
|
int8_t temperature;
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} status;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} Motor1DriverStatusMessage;
|
||||||
|
|
||||||
|
/*--------------------- Motor 2 Driver Feedback Message --------------------*/
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_MOTOR2_DRIVER_FEEDBACK_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct StatusDef
|
||||||
|
{
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
uint16_t value;
|
||||||
|
} current;
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
int16_t value;
|
||||||
|
} rpm;
|
||||||
|
int8_t temperature;
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} status;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} Motor2DriverStatusMessage;
|
||||||
|
|
||||||
|
/*--------------------- Motor 3 Driver Feedback Message --------------------*/
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_MOTOR3_DRIVER_FEEDBACK_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct StatusDef
|
||||||
|
{
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
uint16_t value;
|
||||||
|
} current;
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
int16_t value;
|
||||||
|
} rpm;
|
||||||
|
int8_t temperature;
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} status;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} Motor3DriverStatusMessage;
|
||||||
|
|
||||||
|
/*--------------------- Motor 4 Driver Feedback Message --------------------*/
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint16_t id = MSG_MOTOR4_DRIVER_FEEDBACK_ID;
|
||||||
|
const uint8_t dlc = 0x08;
|
||||||
|
union {
|
||||||
|
struct StatusDef
|
||||||
|
{
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
uint16_t value;
|
||||||
|
} current;
|
||||||
|
union {
|
||||||
|
struct
|
||||||
|
{
|
||||||
|
uint8_t high_byte;
|
||||||
|
uint8_t low_byte;
|
||||||
|
};
|
||||||
|
int16_t value;
|
||||||
|
} rpm;
|
||||||
|
int8_t temperature;
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t count;
|
||||||
|
uint8_t checksum;
|
||||||
|
} status;
|
||||||
|
uint8_t raw[8];
|
||||||
|
} data;
|
||||||
|
} Motor4DriverStatusMessage;
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* SCOUT_CAN_PROTOCOL_H */
|
||||||
@@ -0,0 +1,68 @@
|
|||||||
|
/*
|
||||||
|
* scout_command.hpp
|
||||||
|
*
|
||||||
|
* Created on: Jun 11, 2019 10:33
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SCOUT_COMMAND_HPP
|
||||||
|
#define SCOUT_COMMAND_HPP
|
||||||
|
|
||||||
|
#include <cstdint>
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
struct ScoutMotionCmd
|
||||||
|
{
|
||||||
|
enum class FaultClearFlag
|
||||||
|
{
|
||||||
|
NO_FAULT = 0x00,
|
||||||
|
BAT_UNDER_VOL = 0x01,
|
||||||
|
BAT_OVER_VOL = 0x02,
|
||||||
|
MOTOR1_COMM = 0x03,
|
||||||
|
MOTOR2_COMM = 0x04,
|
||||||
|
MOTOR3_COMM = 0x05,
|
||||||
|
MOTOR4_COMM = 0x06,
|
||||||
|
MOTOR_DRV_OVERHEAT = 0x07,
|
||||||
|
MOTOR_OVERCURRENT = 0x08
|
||||||
|
};
|
||||||
|
|
||||||
|
ScoutMotionCmd(int8_t linear = 0, int8_t angular = 0,
|
||||||
|
FaultClearFlag fault_clr_flag = FaultClearFlag::NO_FAULT)
|
||||||
|
: linear_velocity(linear), angular_velocity(angular),
|
||||||
|
fault_clear_flag(fault_clr_flag) {}
|
||||||
|
|
||||||
|
int8_t linear_velocity;
|
||||||
|
int8_t angular_velocity;
|
||||||
|
FaultClearFlag fault_clear_flag;
|
||||||
|
|
||||||
|
static constexpr double max_linear_velocity = 1.5; // 1.5m/s
|
||||||
|
static constexpr double min_linear_velocity = -1.5; // -1.5m/s
|
||||||
|
static constexpr double max_angular_velocity = 0.7853; // 0.7853rad/s
|
||||||
|
static constexpr double min_angular_velocity = -0.7853; // -0.7853rad/s
|
||||||
|
};
|
||||||
|
|
||||||
|
struct ScoutLightCmd
|
||||||
|
{
|
||||||
|
enum class LightMode
|
||||||
|
{
|
||||||
|
CONST_OFF = 0x00,
|
||||||
|
CONST_ON = 0x01,
|
||||||
|
BREATH = 0x02,
|
||||||
|
CUSTOM = 0x03
|
||||||
|
};
|
||||||
|
|
||||||
|
ScoutLightCmd() = default;
|
||||||
|
ScoutLightCmd(LightMode f_mode, uint8_t f_value, LightMode r_mode, uint8_t r_value) : front_mode(f_mode), front_custom_value(f_value),
|
||||||
|
rear_mode(r_mode), rear_custom_value(r_value) {}
|
||||||
|
|
||||||
|
LightMode front_mode;
|
||||||
|
uint8_t front_custom_value;
|
||||||
|
LightMode rear_mode;
|
||||||
|
uint8_t rear_custom_value;
|
||||||
|
};
|
||||||
|
} // namespace wescore
|
||||||
|
|
||||||
|
#endif /* SCOUT_COMMAND_HPP */
|
||||||
@@ -0,0 +1,21 @@
|
|||||||
|
/*
|
||||||
|
* scout_io.hpp
|
||||||
|
*
|
||||||
|
* Created on: May 04, 2019 22:04
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SCOUT_IO_HPP
|
||||||
|
#define SCOUT_IO_HPP
|
||||||
|
|
||||||
|
namespace scout
|
||||||
|
{
|
||||||
|
class ScoutIO
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
};
|
||||||
|
} // namespace scout
|
||||||
|
|
||||||
|
#endif /* SCOUT_IO_HPP */
|
||||||
@@ -1,9 +1,20 @@
|
|||||||
#ifndef TRANSPORT_H
|
/*
|
||||||
#define TRANSPORT_H
|
* scout_serial.h
|
||||||
|
*
|
||||||
|
* Created on: May 05, 2019 11:35
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
namespace scout_transport
|
#ifndef SCOUT_SERIAL_H
|
||||||
|
#define SCOUT_SERIAL_H
|
||||||
|
|
||||||
|
#include "scout_io/scout_io.h"
|
||||||
|
|
||||||
|
namespace scout
|
||||||
{
|
{
|
||||||
typedef struct
|
struct Frame_t
|
||||||
{
|
{
|
||||||
unsigned short Header;
|
unsigned short Header;
|
||||||
unsigned char Len;
|
unsigned char Len;
|
||||||
@@ -13,14 +24,14 @@ typedef struct
|
|||||||
short Linear;
|
short Linear;
|
||||||
short Angular;
|
short Angular;
|
||||||
unsigned short CheckSum;
|
unsigned short CheckSum;
|
||||||
} Frame_t;
|
};
|
||||||
|
|
||||||
typedef struct
|
struct Cmd_t
|
||||||
{
|
{
|
||||||
unsigned short Linear;
|
unsigned short Linear;
|
||||||
unsigned short Angular;
|
unsigned short Angular;
|
||||||
bool IsUpdata;
|
bool IsUpdata;
|
||||||
} Cmd_t;
|
};
|
||||||
|
|
||||||
typedef enum
|
typedef enum
|
||||||
{
|
{
|
||||||
@@ -30,6 +41,18 @@ typedef enum
|
|||||||
eChecksum = 2
|
eChecksum = 2
|
||||||
} state_t;
|
} state_t;
|
||||||
|
|
||||||
|
class ScoutSerial : public ScoutIO
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
Cmd_t Get_dataOfTransport();
|
||||||
|
void Set_dataOfTransport(Cmd_t *CMD);
|
||||||
|
void Read_DataOfChassis_Loop(void);
|
||||||
|
void Send_SpeedToChassis(short Angular, short Linear, unsigned char Count);
|
||||||
|
void Send_Speed(short Angular, short Linear, unsigned char Count);
|
||||||
|
unsigned short Checksum(unsigned char *data, unsigned short len);
|
||||||
|
void Find_NextHead();
|
||||||
|
};
|
||||||
|
|
||||||
Cmd_t Get_dataOfTransport();
|
Cmd_t Get_dataOfTransport();
|
||||||
void Set_dataOfTransport(Cmd_t *CMD);
|
void Set_dataOfTransport(Cmd_t *CMD);
|
||||||
void Read_DataOfChassis_Loop(void);
|
void Read_DataOfChassis_Loop(void);
|
||||||
@@ -38,6 +61,6 @@ void Send_Speed(short Angular, short Linear, unsigned char Count);
|
|||||||
unsigned short Checksum(unsigned char *data, unsigned short len);
|
unsigned short Checksum(unsigned char *data, unsigned short len);
|
||||||
void Find_NextHead();
|
void Find_NextHead();
|
||||||
void Send_SpeedToChassis(short Angular, short Linear, unsigned char Count);
|
void Send_SpeedToChassis(short Angular, short Linear, unsigned char Count);
|
||||||
} // namespace scout_transport
|
} // namespace scout
|
||||||
|
|
||||||
#endif /* TRANSPORT_H */
|
#endif /* SCOUT_SERIAL_H */
|
||||||
@@ -0,0 +1,36 @@
|
|||||||
|
/*
|
||||||
|
* scout_serial_protocol.hpp
|
||||||
|
*
|
||||||
|
* Created on: Jun 05, 2019 02:34
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SCOUT_SERIAL_PROTOCOL_HPP
|
||||||
|
#define SCOUT_SERIAL_PROTOCOL_HPP
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
struct ScoutSerialProtocol
|
||||||
|
{
|
||||||
|
struct Frame
|
||||||
|
{
|
||||||
|
unsigned short Header;
|
||||||
|
unsigned char Len;
|
||||||
|
unsigned char Typedef;
|
||||||
|
unsigned char Count;
|
||||||
|
unsigned char Time_Out;
|
||||||
|
short Linear;
|
||||||
|
short Angular;
|
||||||
|
unsigned short CheckSum;
|
||||||
|
};
|
||||||
|
};
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* SCOUT_SERIAL_PROTOCOL_HPP */
|
||||||
@@ -0,0 +1,61 @@
|
|||||||
|
/*
|
||||||
|
* scout_state.hpp
|
||||||
|
*
|
||||||
|
* Created on: Jun 11, 2019 08:48
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ruixiang Du (rdu)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SCOUT_STATE_HPP
|
||||||
|
#define SCOUT_STATE_HPP
|
||||||
|
|
||||||
|
#include <cstdint>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
struct ScoutState
|
||||||
|
{
|
||||||
|
enum MotorID
|
||||||
|
{
|
||||||
|
FRONT_RIGHT = 0,
|
||||||
|
FRONT_LEFT = 1,
|
||||||
|
REAR_LEFT = 2,
|
||||||
|
REAR_RIGHT = 3
|
||||||
|
};
|
||||||
|
|
||||||
|
struct MotorState
|
||||||
|
{
|
||||||
|
double current = 0; // in A
|
||||||
|
double rpm = 0;
|
||||||
|
double temperature = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct LightState
|
||||||
|
{
|
||||||
|
uint8_t mode = 0;
|
||||||
|
uint8_t custom_value = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
// base state
|
||||||
|
uint8_t base_state = 0;
|
||||||
|
uint8_t control_mode = 0;
|
||||||
|
uint16_t fault_code = 0;
|
||||||
|
double battery_voltage = 0.0;
|
||||||
|
|
||||||
|
// motor state
|
||||||
|
MotorState motor_states[4];
|
||||||
|
|
||||||
|
// light state
|
||||||
|
bool light_control_enabled = false;
|
||||||
|
LightState front_light_state;
|
||||||
|
LightState rear_light_state;
|
||||||
|
|
||||||
|
// motion state
|
||||||
|
double linear_velocity;
|
||||||
|
double angular_velocity;
|
||||||
|
};
|
||||||
|
} // namespace wescore
|
||||||
|
|
||||||
|
#endif /* SCOUT_STATE_HPP */
|
||||||
247
scout_base/src/scout_sdk/src/scout/src/scout_base.cpp
Normal file
247
scout_base/src/scout_sdk/src/scout/src/scout_base.cpp
Normal file
@@ -0,0 +1,247 @@
|
|||||||
|
#include "scout/scout_base.hpp"
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <cstring>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "scout/scout_can_protocol.h"
|
||||||
|
|
||||||
|
namespace wescore
|
||||||
|
{
|
||||||
|
ScoutBase::~ScoutBase()
|
||||||
|
{
|
||||||
|
if (cmd_thread_.joinable())
|
||||||
|
cmd_thread_.join();
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::ConnectSerialPort(const std::string &port_name, int32_t baud_rate)
|
||||||
|
{
|
||||||
|
// serial_connected_ = (scout_serial::Open_Serial(port_name, baud_rate) > 0) ? true : false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::ConnectCANBus(const std::string &can_if_name)
|
||||||
|
{
|
||||||
|
can_if_ = std::make_shared<ASyncCAN>(can_if_name);
|
||||||
|
|
||||||
|
can_if_->set_receive_callback(std::bind(&ScoutBase::ParseCANFrame, this, std::placeholders::_1));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::StartCmdThread(int32_t period_ms)
|
||||||
|
{
|
||||||
|
cmd_thread_ = std::thread(std::bind(&ScoutBase::ControlLoop, this, period_ms));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::ControlLoop(int32_t period_ms)
|
||||||
|
{
|
||||||
|
stopwatch::StopWatch ctrl_sw;
|
||||||
|
uint8_t cmd_count = 0;
|
||||||
|
uint8_t light_cmd_count = 0;
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
ctrl_sw.tic();
|
||||||
|
|
||||||
|
// motion control message
|
||||||
|
{
|
||||||
|
MotionControlMessage m_msg;
|
||||||
|
|
||||||
|
m_msg.data.cmd.control_mode = CMD_MODE;
|
||||||
|
|
||||||
|
motion_cmd_mutex_.lock();
|
||||||
|
m_msg.data.cmd.fault_clear_flag = static_cast<uint8_t>(current_motion_cmd_.fault_clear_flag);
|
||||||
|
m_msg.data.cmd.linear_velocity_cmd = current_motion_cmd_.linear_velocity;
|
||||||
|
m_msg.data.cmd.angular_velocity_cmd = current_motion_cmd_.angular_velocity;
|
||||||
|
motion_cmd_mutex_.unlock();
|
||||||
|
|
||||||
|
m_msg.data.cmd.reserved0 = 0;
|
||||||
|
m_msg.data.cmd.reserved1 = 0;
|
||||||
|
m_msg.data.cmd.count = cmd_count++;
|
||||||
|
m_msg.data.cmd.checksum = Agilex_CANMsgChecksum(m_msg.id, m_msg.data.raw, m_msg.dlc);
|
||||||
|
|
||||||
|
// send to can bus
|
||||||
|
can_frame m_frame;
|
||||||
|
m_frame.can_id = m_msg.id;
|
||||||
|
m_frame.can_dlc = m_msg.dlc;
|
||||||
|
std::memcpy(m_frame.data, m_msg.data.raw, m_msg.dlc * sizeof(uint8_t));
|
||||||
|
can_if_->send_frame(m_frame);
|
||||||
|
}
|
||||||
|
|
||||||
|
// check if there is request for light control
|
||||||
|
if (light_ctrl_requested_)
|
||||||
|
{
|
||||||
|
LightControlMessage l_msg;
|
||||||
|
|
||||||
|
light_cmd_mutex_.lock();
|
||||||
|
if(light_ctrl_enabled_)
|
||||||
|
{
|
||||||
|
l_msg.data.cmd.light_ctrl_enable = ENABLE_LIGHT_CTRL;
|
||||||
|
|
||||||
|
l_msg.data.cmd.front_light_mode = static_cast<uint8_t>(current_light_cmd_.front_mode);
|
||||||
|
l_msg.data.cmd.front_light_custom = current_light_cmd_.front_custom_value;
|
||||||
|
l_msg.data.cmd.rear_light_mode = static_cast<uint8_t>(current_light_cmd_.rear_mode);
|
||||||
|
l_msg.data.cmd.rear_light_custom = current_light_cmd_.rear_custom_value;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
l_msg.data.cmd.light_ctrl_enable = DISABLE_LIGHT_CTRL;
|
||||||
|
|
||||||
|
l_msg.data.cmd.front_light_mode = CONST_OFF;
|
||||||
|
l_msg.data.cmd.front_light_custom = 0;
|
||||||
|
l_msg.data.cmd.rear_light_mode = CONST_OFF;
|
||||||
|
l_msg.data.cmd.rear_light_custom = 0;
|
||||||
|
}
|
||||||
|
light_ctrl_requested_ = false;
|
||||||
|
light_cmd_mutex_.unlock();
|
||||||
|
|
||||||
|
l_msg.data.cmd.reserved0 = 0;
|
||||||
|
l_msg.data.cmd.count = light_cmd_count++;
|
||||||
|
l_msg.data.cmd.checksum = Agilex_CANMsgChecksum(l_msg.id, l_msg.data.raw, l_msg.dlc);
|
||||||
|
|
||||||
|
can_frame l_frame;
|
||||||
|
l_frame.can_id = l_msg.id;
|
||||||
|
l_frame.can_dlc = l_msg.dlc;
|
||||||
|
std::memcpy(l_frame.data, l_msg.data.raw, l_msg.dlc * sizeof(uint8_t));
|
||||||
|
can_if_->send_frame(l_frame);
|
||||||
|
}
|
||||||
|
|
||||||
|
ctrl_sw.sleep_until_ms(period_ms);
|
||||||
|
// std::cout << "control loop update frequency: " << 1.0 / ctrl_sw.toc() << std::endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ScoutState ScoutBase::GetScoutState()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> guard(scout_state_mutex_);
|
||||||
|
return scout_state_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::SetMotionCommand(double linear_vel, double angular_vel, ScoutMotionCmd::FaultClearFlag fault_clr_flag)
|
||||||
|
{
|
||||||
|
if (linear_vel < ScoutMotionCmd::min_linear_velocity)
|
||||||
|
linear_vel = ScoutMotionCmd::min_linear_velocity;
|
||||||
|
if (linear_vel > ScoutMotionCmd::max_linear_velocity)
|
||||||
|
linear_vel = ScoutMotionCmd::max_linear_velocity;
|
||||||
|
if (angular_vel < ScoutMotionCmd::min_angular_velocity)
|
||||||
|
angular_vel = ScoutMotionCmd::min_angular_velocity;
|
||||||
|
if (angular_vel > ScoutMotionCmd::max_angular_velocity)
|
||||||
|
angular_vel = ScoutMotionCmd::max_angular_velocity;
|
||||||
|
|
||||||
|
std::lock_guard<std::mutex> guard(motion_cmd_mutex_);
|
||||||
|
current_motion_cmd_.linear_velocity = static_cast<uint8_t>(linear_vel / ScoutMotionCmd::max_linear_velocity * 100.0);
|
||||||
|
current_motion_cmd_.angular_velocity = static_cast<uint8_t>(angular_vel / ScoutMotionCmd::max_angular_velocity * 100.0);
|
||||||
|
current_motion_cmd_.fault_clear_flag = fault_clr_flag;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::SetLightCommand(ScoutLightCmd cmd)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> guard(light_cmd_mutex_);
|
||||||
|
current_light_cmd_ = cmd;
|
||||||
|
light_ctrl_enabled_ = true;
|
||||||
|
light_ctrl_requested_ = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::DisableLightCmdControl()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> guard(light_cmd_mutex_);
|
||||||
|
light_ctrl_enabled_ = false;
|
||||||
|
light_ctrl_requested_ = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::ParseCANFrame(can_frame *rx_frame)
|
||||||
|
{
|
||||||
|
// validate checksum, discard frame if fails
|
||||||
|
if (!rx_frame->data[7] == Agilex_CANMsgChecksum(rx_frame->can_id, rx_frame->data, rx_frame->can_dlc))
|
||||||
|
{
|
||||||
|
std::cerr << "ERROR: checksum mismatch, discard frame with id " << rx_frame->can_id << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// otherwise, update robot state with new frame
|
||||||
|
std::lock_guard<std::mutex> guard(scout_state_mutex_);
|
||||||
|
UpdateScoutState(scout_state_, rx_frame);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutBase::UpdateScoutState(ScoutState &state, can_frame *rx_frame)
|
||||||
|
{
|
||||||
|
switch (rx_frame->can_id)
|
||||||
|
{
|
||||||
|
case MSG_MOTION_CONTROL_FEEDBACK_ID:
|
||||||
|
{
|
||||||
|
// std::cout << "motion control feedback received" << std::endl;
|
||||||
|
MotionStatusMessage msg;
|
||||||
|
std::memcpy(msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t));
|
||||||
|
state.linear_velocity = static_cast<int16_t>(static_cast<uint16_t>(msg.data.status.linear_velocity.low_byte) | static_cast<uint16_t>(msg.data.status.linear_velocity.high_byte) << 8) / 1000.0;
|
||||||
|
state.angular_velocity = static_cast<int16_t>(static_cast<uint16_t>(msg.data.status.angular_velocity.low_byte) | static_cast<uint16_t>(msg.data.status.angular_velocity.high_byte) << 8) / 1000.0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case MSG_LIGHT_CONTROL_FEEDBACK_ID:
|
||||||
|
{
|
||||||
|
// std::cout << "light control feedback received" << std::endl;
|
||||||
|
LightStatusMessage msg;
|
||||||
|
std::memcpy(msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t));
|
||||||
|
if (msg.data.status.light_ctrl_enable == DISABLE_LIGHT_CTRL)
|
||||||
|
state.light_control_enabled = false;
|
||||||
|
else
|
||||||
|
state.light_control_enabled = true;
|
||||||
|
state.front_light_state.mode = msg.data.status.front_light_mode;
|
||||||
|
state.front_light_state.custom_value = msg.data.status.front_light_custom;
|
||||||
|
state.rear_light_state.mode = msg.data.status.rear_light_mode;
|
||||||
|
state.rear_light_state.custom_value = msg.data.status.rear_light_custom;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case MSG_SYSTEM_STATUS_FEEDBACK_ID:
|
||||||
|
{
|
||||||
|
// std::cout << "system status feedback received" << std::endl;
|
||||||
|
SystemStatusMessage msg;
|
||||||
|
std::memcpy(msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t));
|
||||||
|
state.control_mode = msg.data.status.control_mode;
|
||||||
|
state.base_state = msg.data.status.base_state;
|
||||||
|
state.battery_voltage = (static_cast<uint16_t>(msg.data.status.battery_voltage.low_byte) | static_cast<uint16_t>(msg.data.status.battery_voltage.high_byte) << 8) / 10.0;
|
||||||
|
state.fault_code = (static_cast<uint16_t>(msg.data.status.fault_code.low_byte) | static_cast<uint16_t>(msg.data.status.fault_code.high_byte) << 8);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case MSG_MOTOR1_DRIVER_FEEDBACK_ID:
|
||||||
|
{
|
||||||
|
// std::cout << "motor 1 driver feedback received" << std::endl;
|
||||||
|
Motor1DriverStatusMessage msg;
|
||||||
|
std::memcpy(msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t));
|
||||||
|
state.motor_states[0].current = (static_cast<uint16_t>(msg.data.status.current.low_byte) | static_cast<uint16_t>(msg.data.status.current.high_byte) << 8) / 10.0;
|
||||||
|
state.motor_states[0].rpm = static_cast<int16_t>(static_cast<uint16_t>(msg.data.status.rpm.low_byte) | static_cast<uint16_t>(msg.data.status.rpm.high_byte) << 8);
|
||||||
|
;
|
||||||
|
state.motor_states[0].temperature = msg.data.status.temperature;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case MSG_MOTOR2_DRIVER_FEEDBACK_ID:
|
||||||
|
{
|
||||||
|
// std::cout << "motor 2 driver feedback received" << std::endl;
|
||||||
|
Motor2DriverStatusMessage msg;
|
||||||
|
std::memcpy(msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t));
|
||||||
|
state.motor_states[1].current = (static_cast<uint16_t>(msg.data.status.current.low_byte) | static_cast<uint16_t>(msg.data.status.current.high_byte) << 8) / 10.0;
|
||||||
|
state.motor_states[1].rpm = static_cast<int16_t>(static_cast<uint16_t>(msg.data.status.rpm.low_byte) | static_cast<uint16_t>(msg.data.status.rpm.high_byte) << 8);
|
||||||
|
;
|
||||||
|
state.motor_states[1].temperature = msg.data.status.temperature;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case MSG_MOTOR3_DRIVER_FEEDBACK_ID:
|
||||||
|
{
|
||||||
|
// std::cout << "motor 3 driver feedback received" << std::endl;
|
||||||
|
Motor3DriverStatusMessage msg;
|
||||||
|
std::memcpy(msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t));
|
||||||
|
state.motor_states[2].current = (static_cast<uint16_t>(msg.data.status.current.low_byte) | static_cast<uint16_t>(msg.data.status.current.high_byte) << 8) / 10.0;
|
||||||
|
state.motor_states[2].rpm = static_cast<int16_t>(static_cast<uint16_t>(msg.data.status.rpm.low_byte) | static_cast<uint16_t>(msg.data.status.rpm.high_byte) << 8);
|
||||||
|
;
|
||||||
|
state.motor_states[2].temperature = msg.data.status.temperature;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case MSG_MOTOR4_DRIVER_FEEDBACK_ID:
|
||||||
|
{
|
||||||
|
// std::cout << "motor 4 driver feedback received" << std::endl;
|
||||||
|
Motor4DriverStatusMessage msg;
|
||||||
|
std::memcpy(msg.data.raw, rx_frame->data, rx_frame->can_dlc * sizeof(uint8_t));
|
||||||
|
state.motor_states[3].current = (static_cast<uint16_t>(msg.data.status.current.low_byte) | static_cast<uint16_t>(msg.data.status.current.high_byte) << 8) / 10.0;
|
||||||
|
state.motor_states[3].rpm = static_cast<int16_t>(static_cast<uint16_t>(msg.data.status.rpm.low_byte) | static_cast<uint16_t>(msg.data.status.rpm.high_byte) << 8);
|
||||||
|
state.motor_states[3].temperature = msg.data.status.temperature;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} // namespace wescore
|
||||||
12
scout_base/src/scout_sdk/src/scout/tests/CMakeLists.txt
Normal file
12
scout_base/src/scout_sdk/src/scout/tests/CMakeLists.txt
Normal file
@@ -0,0 +1,12 @@
|
|||||||
|
# Dependency libraries
|
||||||
|
#find_package(LIBRARY_NAME REQUIRED)
|
||||||
|
|
||||||
|
# tests
|
||||||
|
# add_executable(test_scout_cpp test_scout_cpp.cpp)
|
||||||
|
# target_link_libraries(test_scout_cpp scout stopwatch)
|
||||||
|
|
||||||
|
add_executable(test_scout_base test_scout_base.cpp)
|
||||||
|
target_link_libraries(test_scout_base scout_base)
|
||||||
|
|
||||||
|
add_executable(test_can_msg test_can_msg.cpp)
|
||||||
|
target_link_libraries(test_can_msg scout_base)
|
||||||
37
scout_base/src/scout_sdk/src/scout/tests/test_can_msg.cpp
Normal file
37
scout_base/src/scout_sdk/src/scout/tests/test_can_msg.cpp
Normal file
@@ -0,0 +1,37 @@
|
|||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "scout/scout_can_protocol.h"
|
||||||
|
|
||||||
|
void print_msg(uint8_t data[8])
|
||||||
|
{
|
||||||
|
for (int i = 0; i < 8; ++i)
|
||||||
|
std::cout << std::hex << static_cast<int>(data[i]) << " ";
|
||||||
|
std::cout << std::dec << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
int main()
|
||||||
|
{
|
||||||
|
MotionControlMessage msg;
|
||||||
|
msg.data.cmd.control_mode = CMD_MODE;
|
||||||
|
msg.data.cmd.fault_clear_flag = NO_FAULT;
|
||||||
|
msg.data.cmd.linear_velocity_cmd = 10;
|
||||||
|
msg.data.cmd.angular_velocity_cmd = 0;
|
||||||
|
msg.data.cmd.reserved0 = 0;
|
||||||
|
msg.data.cmd.reserved1 = 0;
|
||||||
|
msg.data.cmd.count = 0;
|
||||||
|
msg.data.cmd.checksum = Agilex_CANMsgChecksum(msg.id, msg.data.raw, msg.dlc);
|
||||||
|
print_msg(msg.data.raw);
|
||||||
|
|
||||||
|
LightControlMessage msg2;
|
||||||
|
msg2.data.cmd.light_ctrl_enable = DISABLE_LIGHT_CTRL;
|
||||||
|
msg2.data.cmd.front_light_mode = CONST_ON;
|
||||||
|
msg2.data.cmd.front_light_custom = 0;
|
||||||
|
msg2.data.cmd.rear_light_mode = CONST_ON;
|
||||||
|
msg2.data.cmd.rear_light_custom = 0;
|
||||||
|
msg2.data.cmd.reserved0 = 0;
|
||||||
|
msg2.data.cmd.count = 0;
|
||||||
|
msg2.data.cmd.checksum = Agilex_CANMsgChecksum(msg2.id, msg2.data.raw, msg2.dlc);
|
||||||
|
print_msg(msg2.data.raw);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
50
scout_base/src/scout_sdk/src/scout/tests/test_scout_base.cpp
Normal file
50
scout_base/src/scout_sdk/src/scout/tests/test_scout_base.cpp
Normal file
@@ -0,0 +1,50 @@
|
|||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <thread>
|
||||||
|
#include <mutex>
|
||||||
|
#include <functional>
|
||||||
|
#include <string>
|
||||||
|
#include <iostream>
|
||||||
|
#include <chrono>
|
||||||
|
#include <cmath>
|
||||||
|
|
||||||
|
#include "stopwatch/stopwatch.h"
|
||||||
|
|
||||||
|
#include "scout/scout_base.hpp"
|
||||||
|
|
||||||
|
#define TEST_WITHOUT_SERIAL_HARDWARE
|
||||||
|
|
||||||
|
using namespace wescore;
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
ScoutBase scout;
|
||||||
|
scout.ConnectCANBus("can1");
|
||||||
|
scout.StartCmdThread(10);
|
||||||
|
|
||||||
|
scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_ON, 0, ScoutLightCmd::LightMode::CONST_ON, 0});
|
||||||
|
|
||||||
|
int count = 0;
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
scout.SetMotionCommand(0.5, 0.2);
|
||||||
|
|
||||||
|
if(count == 10)
|
||||||
|
{
|
||||||
|
// scout.SetLightCommand({ScoutLightCmd::LightMode::CONST_OFF, 0, ScoutLightCmd::LightMode::CONST_OFF, 0});
|
||||||
|
scout.DisableLightCmdControl();
|
||||||
|
}
|
||||||
|
|
||||||
|
auto state = scout.GetScoutState();
|
||||||
|
std::cout << "-------------------------------" << std::endl;
|
||||||
|
std::cout << "control mode: " << static_cast<int>(state.control_mode) << " , base state: " << static_cast<int>(state.base_state) << std::endl;
|
||||||
|
std::cout << "battery voltage: " << state.battery_voltage << std::endl;
|
||||||
|
std::cout << "velocity (linear, angular): " << state.linear_velocity << ", " << state.angular_velocity << std::endl;
|
||||||
|
std::cout << "-------------------------------" << std::endl;
|
||||||
|
|
||||||
|
sleep(1);
|
||||||
|
++count;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
4
scout_base/src/scout_sdk/src/scout_cpp/tests/test_scout_cpp.cpp → scout_base/src/scout_sdk/src/scout/tests/test_scout_cpp.cpp
Normal file → Executable file
4
scout_base/src/scout_sdk/src/scout_cpp/tests/test_scout_cpp.cpp → scout_base/src/scout_sdk/src/scout/tests/test_scout_cpp.cpp
Normal file → Executable file
@@ -10,7 +10,7 @@
|
|||||||
|
|
||||||
#include "stopwatch/stopwatch.h"
|
#include "stopwatch/stopwatch.h"
|
||||||
|
|
||||||
#include "scout/scout_robot.h"
|
#include "scout/scout_base.hpp"
|
||||||
|
|
||||||
#define TEST_WITHOUT_SERIAL_HARDWARE
|
#define TEST_WITHOUT_SERIAL_HARDWARE
|
||||||
|
|
||||||
@@ -28,7 +28,7 @@ public:
|
|||||||
|
|
||||||
void PublishOdometry()
|
void PublishOdometry()
|
||||||
{
|
{
|
||||||
RobotState data;
|
ScoutState data;
|
||||||
stopwatch::StopWatch swatch;
|
stopwatch::StopWatch swatch;
|
||||||
while (true)
|
while (true)
|
||||||
{
|
{
|
||||||
@@ -1,43 +0,0 @@
|
|||||||
#ifndef SCOUT_ROBOT_H
|
|
||||||
#define SCOUT_ROBOT_H
|
|
||||||
|
|
||||||
#include <string>
|
|
||||||
#include <cstdint>
|
|
||||||
|
|
||||||
namespace scout
|
|
||||||
{
|
|
||||||
struct RobotState
|
|
||||||
{
|
|
||||||
RobotState() : linear(0), angular(0) {}
|
|
||||||
RobotState(short _linear, short _angular) : linear(_linear), angular(_angular) {}
|
|
||||||
|
|
||||||
short linear;
|
|
||||||
short angular;
|
|
||||||
};
|
|
||||||
|
|
||||||
struct RobotCmd
|
|
||||||
{
|
|
||||||
RobotCmd() : linear(0), angular(0) {}
|
|
||||||
RobotCmd(double _linear, double _angular, uint32_t cnt)
|
|
||||||
: linear(_linear), angular(_angular), count(0) {}
|
|
||||||
|
|
||||||
double linear;
|
|
||||||
double angular;
|
|
||||||
uint32_t count;
|
|
||||||
};
|
|
||||||
|
|
||||||
class ScoutRobot
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
void ConnectSerialPort(const std::string &port_name = "/dev/ttyUSB0", int32_t baud_rate = 115200);
|
|
||||||
bool IsConnectionActive() const { return serial_connected_; }
|
|
||||||
|
|
||||||
void SendCommand(const RobotCmd& cmd);
|
|
||||||
bool QueryRobotState(RobotState *data);
|
|
||||||
|
|
||||||
private:
|
|
||||||
bool serial_connected_ = false;
|
|
||||||
};
|
|
||||||
} // namespace scout
|
|
||||||
|
|
||||||
#endif /* SCOUT_ROBOT_H */
|
|
||||||
@@ -1,54 +0,0 @@
|
|||||||
#include "scout/scout_robot.h"
|
|
||||||
|
|
||||||
#include <string>
|
|
||||||
#include <iostream>
|
|
||||||
|
|
||||||
#include "scout_io/serialport.h"
|
|
||||||
#include "scout_io/transport.h"
|
|
||||||
|
|
||||||
namespace scout
|
|
||||||
{
|
|
||||||
void ScoutRobot::ConnectSerialPort(const std::string &port_name, int32_t baud_rate)
|
|
||||||
{
|
|
||||||
serial_connected_ = (scout_serial::Open_Serial(port_name, baud_rate) > 0) ? true : false;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool ScoutRobot::QueryRobotState(RobotState *data)
|
|
||||||
{
|
|
||||||
scout_transport::Cmd_t cmd;
|
|
||||||
scout_transport::Read_DataOfChassis_Loop();
|
|
||||||
cmd = scout_transport::Get_dataOfTransport();
|
|
||||||
|
|
||||||
if (cmd.IsUpdata == true)
|
|
||||||
{
|
|
||||||
cmd.IsUpdata = false;
|
|
||||||
data->linear = cmd.Linear;
|
|
||||||
data->angular = cmd.Angular;
|
|
||||||
scout_transport::Set_dataOfTransport(&cmd);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ScoutRobot::SendCommand(const RobotCmd& cmd)
|
|
||||||
{
|
|
||||||
double cent_speed = cmd.linear;
|
|
||||||
double cmd_twist_rotation = cmd.angular;
|
|
||||||
|
|
||||||
cent_speed = cent_speed * 10000;
|
|
||||||
cmd_twist_rotation = cmd_twist_rotation * 10000;
|
|
||||||
if (cent_speed > 20000)
|
|
||||||
cent_speed = 20000;
|
|
||||||
if (cent_speed < -20000)
|
|
||||||
cent_speed = -20000;
|
|
||||||
if (cmd_twist_rotation > 20000)
|
|
||||||
cmd_twist_rotation = 20000;
|
|
||||||
if (cmd_twist_rotation < -20000)
|
|
||||||
cmd_twist_rotation = -20000;
|
|
||||||
|
|
||||||
scout_transport::Send_Speed(static_cast<short>(cmd_twist_rotation), static_cast<short>(cent_speed), cmd.count);
|
|
||||||
std::cout << "send -> linear: " << cent_speed << "; angular: " << cmd_twist_rotation << std::endl;
|
|
||||||
}
|
|
||||||
} // namespace scout
|
|
||||||
@@ -1,6 +0,0 @@
|
|||||||
# Dependency libraries
|
|
||||||
#find_package(LIBRARY_NAME REQUIRED)
|
|
||||||
|
|
||||||
# tests
|
|
||||||
add_executable(test_scout_cpp test_scout_cpp.cpp)
|
|
||||||
target_link_libraries(test_scout_cpp scoutcpp stopwatch)
|
|
||||||
@@ -1,34 +0,0 @@
|
|||||||
cmake_minimum_required(VERSION 3.0.0)
|
|
||||||
project(scout_io)
|
|
||||||
|
|
||||||
## Put all binary files into /bin and libraries into /lib
|
|
||||||
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
|
||||||
set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib)
|
|
||||||
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
|
||||||
|
|
||||||
## Set compiler to use c++ 11 features
|
|
||||||
include(CheckCXXCompilerFlag)
|
|
||||||
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
|
|
||||||
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
|
|
||||||
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
|
|
||||||
if(COMPILER_SUPPORTS_CXX14)
|
|
||||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
|
|
||||||
elseif(COMPILER_SUPPORTS_CXX11)
|
|
||||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
|
|
||||||
elseif(COMPILER_SUPPORTS_CXX0X)
|
|
||||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
|
|
||||||
else()
|
|
||||||
message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++14 or C++11 support. Please use a different C++ compiler.")
|
|
||||||
endif()
|
|
||||||
|
|
||||||
## Add libraries
|
|
||||||
set(SCOUT_IO_SRC
|
|
||||||
src/serialport.cpp
|
|
||||||
src/transport.cpp
|
|
||||||
)
|
|
||||||
add_library(scoutio STATIC ${SCOUT_IO_SRC})
|
|
||||||
target_link_libraries(scoutio serial)
|
|
||||||
target_include_directories(scoutio PUBLIC
|
|
||||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
|
||||||
$<INSTALL_INTERFACE:include>
|
|
||||||
PRIVATE src)
|
|
||||||
@@ -1,14 +0,0 @@
|
|||||||
#ifndef SERIALPORT_H
|
|
||||||
#define SERIALPORT_H
|
|
||||||
|
|
||||||
#include <string>
|
|
||||||
|
|
||||||
namespace scout_serial
|
|
||||||
{
|
|
||||||
int Open_Serial(std::string port_name, int baud_rate);
|
|
||||||
unsigned int Write(unsigned char *data, unsigned short len);
|
|
||||||
unsigned int Read(unsigned char *data, unsigned short len);
|
|
||||||
unsigned int GetDataCount(void);
|
|
||||||
} // namespace scout_serial
|
|
||||||
|
|
||||||
#endif /* SERIALPORT_H */
|
|
||||||
@@ -1,58 +0,0 @@
|
|||||||
#include <iostream>
|
|
||||||
|
|
||||||
#include <serial/serial.h>
|
|
||||||
|
|
||||||
#include "scout_io/serialport.h"
|
|
||||||
|
|
||||||
namespace
|
|
||||||
{
|
|
||||||
serial::Serial ser;
|
|
||||||
}
|
|
||||||
|
|
||||||
namespace scout_serial
|
|
||||||
{
|
|
||||||
int Open_Serial(std::string port_name, int baud_rate)
|
|
||||||
{
|
|
||||||
try
|
|
||||||
{
|
|
||||||
// 设置串口属性,并打开串口 Configure and open serial port
|
|
||||||
ser.setPort(port_name);
|
|
||||||
ser.setBaudrate(baud_rate);
|
|
||||||
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
|
|
||||||
ser.setTimeout(to);
|
|
||||||
ser.open();
|
|
||||||
}
|
|
||||||
catch (serial::IOException &e)
|
|
||||||
{
|
|
||||||
std::cerr << "Unable to open port " << std::endl;
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (ser.isOpen())
|
|
||||||
{
|
|
||||||
std::cerr << "Serial Port initialized" << std::endl;
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
unsigned int Write(unsigned char *data, unsigned short len)
|
|
||||||
{
|
|
||||||
unsigned int Len = ser.write(data, len);
|
|
||||||
return Len;
|
|
||||||
}
|
|
||||||
|
|
||||||
unsigned int Read(unsigned char *data, unsigned short len)
|
|
||||||
{
|
|
||||||
unsigned int Len = ser.read(data, len);
|
|
||||||
return Len;
|
|
||||||
}
|
|
||||||
|
|
||||||
unsigned int GetDataCount(void)
|
|
||||||
{
|
|
||||||
return ser.available();
|
|
||||||
}
|
|
||||||
} // namespace scout_serial
|
|
||||||
@@ -1,193 +0,0 @@
|
|||||||
#include <iostream>
|
|
||||||
#include <thread>
|
|
||||||
#include <mutex>
|
|
||||||
#include <cstring>
|
|
||||||
|
|
||||||
#include "scout_io/serialport.h"
|
|
||||||
#include "scout_io/transport.h"
|
|
||||||
|
|
||||||
#define serial_debug 1
|
|
||||||
#define receive_speed_callback_debug 0
|
|
||||||
#define receive_odom_debug 1
|
|
||||||
|
|
||||||
namespace
|
|
||||||
{
|
|
||||||
#define ChassisToRos_Odom 0x56
|
|
||||||
#define RosToChassis_Cmd 0x12
|
|
||||||
|
|
||||||
bool Is_send_speed_callback;
|
|
||||||
|
|
||||||
scout_transport::Frame_t Get_Odom_Frame;
|
|
||||||
scout_transport::Cmd_t cmd;
|
|
||||||
|
|
||||||
std::mutex ack_write;
|
|
||||||
std::mutex cmd_write;
|
|
||||||
} // namespace
|
|
||||||
|
|
||||||
namespace scout_transport
|
|
||||||
{
|
|
||||||
unsigned short Checksum(unsigned char *data, unsigned short len)
|
|
||||||
{
|
|
||||||
unsigned short i = 0;
|
|
||||||
unsigned short sum = 0;
|
|
||||||
for (i = 0; i < len; i++)
|
|
||||||
{
|
|
||||||
sum += data[i];
|
|
||||||
}
|
|
||||||
return sum;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Send_Speed(short Angular, short Linear, unsigned char Count)
|
|
||||||
{
|
|
||||||
Frame_t Cmd_Frame;
|
|
||||||
memset(&Cmd_Frame, 0, sizeof(Cmd_Frame));
|
|
||||||
Cmd_Frame.Header = 0x55aa;
|
|
||||||
Cmd_Frame.Len = sizeof(Cmd_Frame) - 2;
|
|
||||||
Cmd_Frame.Typedef = RosToChassis_Cmd;
|
|
||||||
Cmd_Frame.Count = Count;
|
|
||||||
Cmd_Frame.Angular = Angular;
|
|
||||||
Cmd_Frame.Linear = Linear;
|
|
||||||
Cmd_Frame.CheckSum = Checksum((unsigned char *)&Cmd_Frame, Cmd_Frame.Len);
|
|
||||||
scout_serial::Write((unsigned char *)&Cmd_Frame, sizeof(Cmd_Frame));
|
|
||||||
}
|
|
||||||
|
|
||||||
void Read_DataOfChassis(void)
|
|
||||||
{
|
|
||||||
static int state = 0;
|
|
||||||
static int len_index = 0;
|
|
||||||
static unsigned char len = 0;
|
|
||||||
static unsigned char buff[30] = {0};
|
|
||||||
|
|
||||||
switch (state)
|
|
||||||
{
|
|
||||||
case 0:
|
|
||||||
{
|
|
||||||
scout_serial::Read(&buff[0], 1);
|
|
||||||
if (buff[0] == 0xaa)
|
|
||||||
{
|
|
||||||
len_index = 0;
|
|
||||||
state = 1;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
printf("Head error 1\r\n");
|
|
||||||
state = 0;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case 1:
|
|
||||||
{
|
|
||||||
scout_serial::Read(&buff[1], 1);
|
|
||||||
if (buff[1] == 0x55)
|
|
||||||
{
|
|
||||||
len_index = 0;
|
|
||||||
state = 2;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
printf("Head error 2\r\n");
|
|
||||||
state = 0;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case 2:
|
|
||||||
{
|
|
||||||
scout_serial::Read(&buff[2], 1);
|
|
||||||
len = buff[2];
|
|
||||||
if (len == 10)
|
|
||||||
{
|
|
||||||
state = 3;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
state = 0;
|
|
||||||
printf("Len error 1 : %d \r\n", buff[2]);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case 3:
|
|
||||||
{
|
|
||||||
scout_serial::Read(&buff[3], len - 1);
|
|
||||||
unsigned short CheckSum = buff[len] | buff[len + 1] << 8;
|
|
||||||
if (CheckSum == Checksum(&buff[0], len))
|
|
||||||
{
|
|
||||||
state = 4;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
state = 0;
|
|
||||||
printf("Check sum error \r\n");
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case 4:
|
|
||||||
{
|
|
||||||
unsigned char Typedef = buff[3];
|
|
||||||
if (Typedef == ChassisToRos_Odom)
|
|
||||||
{
|
|
||||||
memcpy(&Get_Odom_Frame, &buff[0], sizeof(Get_Odom_Frame));
|
|
||||||
|
|
||||||
cmd.IsUpdata = true;
|
|
||||||
cmd.Angular = Get_Odom_Frame.Angular;
|
|
||||||
cmd.Linear = Get_Odom_Frame.Linear;
|
|
||||||
|
|
||||||
static int Successful_Connection = 0;
|
|
||||||
|
|
||||||
if (Successful_Connection == 0)
|
|
||||||
{
|
|
||||||
Successful_Connection = 1;
|
|
||||||
printf("The connection was successful and the vehicle was ready!");
|
|
||||||
}
|
|
||||||
|
|
||||||
#if receive_odom_debug
|
|
||||||
printf("Angular = %d Linear = %d count = %d Time_Out = %d \r\n",
|
|
||||||
Get_Odom_Frame.Angular,
|
|
||||||
Get_Odom_Frame.Linear,
|
|
||||||
Get_Odom_Frame.Count,
|
|
||||||
Get_Odom_Frame.Time_Out);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
state = 0;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
default:
|
|
||||||
{
|
|
||||||
state = 0;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
Cmd_t Get_dataOfTransport() { return cmd; }
|
|
||||||
|
|
||||||
void Set_dataOfTransport(Cmd_t *CMD) { cmd = *CMD; }
|
|
||||||
|
|
||||||
void Read_DataOfChassis_Loop(void)
|
|
||||||
{
|
|
||||||
unsigned int len = scout_serial::GetDataCount();
|
|
||||||
if (len >= sizeof(Frame_t))
|
|
||||||
{
|
|
||||||
Read_DataOfChassis();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void Send_SpeedToChassis(short Angular, short Linear, unsigned char Count)
|
|
||||||
{
|
|
||||||
Is_send_speed_callback = false;
|
|
||||||
static int time = 0;
|
|
||||||
time = 0;
|
|
||||||
do
|
|
||||||
{
|
|
||||||
Send_Speed(Angular, Linear, Count);
|
|
||||||
// boost::this_thread::sleep(boost::posix_time::milliseconds(60));
|
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(60));
|
|
||||||
time++;
|
|
||||||
if (time > 20)
|
|
||||||
{
|
|
||||||
// ROS_INFO_STREAM("lost scout! Please check whether the power supply or the serial line of the vehicle is loose.\r\n");
|
|
||||||
std::cout << "Lost Scout! Please check whether the power supply or the serial cable of the vehicle is loose." << std::endl;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
} while (Is_send_speed_callback == false);
|
|
||||||
}
|
|
||||||
} // namespace scout_transport
|
|
||||||
5
scout_base/src/scout_sdk/src/third_party/CMakeLists.txt
vendored
Normal file → Executable file
5
scout_base/src/scout_sdk/src/third_party/CMakeLists.txt
vendored
Normal file → Executable file
@@ -7,5 +7,8 @@ set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib)
|
|||||||
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
|
||||||
## Add sub source directories
|
## Add sub source directories
|
||||||
add_subdirectory(serial)
|
add_subdirectory(asio)
|
||||||
add_subdirectory(stopwatch)
|
add_subdirectory(stopwatch)
|
||||||
|
if(BUILD_TESTS)
|
||||||
|
add_subdirectory(googletest)
|
||||||
|
endif()
|
||||||
9
scout_base/src/scout_sdk/src/third_party/asio/CMakeLists.txt
vendored
Normal file
9
scout_base/src/scout_sdk/src/third_party/asio/CMakeLists.txt
vendored
Normal file
@@ -0,0 +1,9 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.0)
|
||||||
|
project(asio)
|
||||||
|
|
||||||
|
# ascent library
|
||||||
|
add_library(asio INTERFACE)
|
||||||
|
target_compile_definitions(asio INTERFACE "-DASIO_STANDALONE")
|
||||||
|
target_include_directories(asio INTERFACE
|
||||||
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
|
$<INSTALL_INTERFACE:include>)
|
||||||
4
scout_base/src/scout_sdk/src/third_party/asio/COPYING
vendored
Normal file
4
scout_base/src/scout_sdk/src/third_party/asio/COPYING
vendored
Normal file
@@ -0,0 +1,4 @@
|
|||||||
|
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)
|
||||||
5
scout_base/src/scout_sdk/src/third_party/asio/INSTALL
vendored
Normal file
5
scout_base/src/scout_sdk/src/third_party/asio/INSTALL
vendored
Normal file
@@ -0,0 +1,5 @@
|
|||||||
|
See doc/index.html for information on:
|
||||||
|
- External dependencies
|
||||||
|
- Using asio
|
||||||
|
- Supported platforms
|
||||||
|
- How to build the tests and examples
|
||||||
23
scout_base/src/scout_sdk/src/third_party/asio/LICENSE_1_0.txt
vendored
Normal file
23
scout_base/src/scout_sdk/src/third_party/asio/LICENSE_1_0.txt
vendored
Normal file
@@ -0,0 +1,23 @@
|
|||||||
|
Boost Software License - Version 1.0 - August 17th, 2003
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person or organization
|
||||||
|
obtaining a copy of the software and accompanying documentation covered by
|
||||||
|
this license (the "Software") to use, reproduce, display, distribute,
|
||||||
|
execute, and transmit the Software, and to prepare derivative works of the
|
||||||
|
Software, and to permit third-parties to whom the Software is furnished to
|
||||||
|
do so, all subject to the following:
|
||||||
|
|
||||||
|
The copyright notices in the Software and this entire statement, including
|
||||||
|
the above license grant, this restriction and the following disclaimer,
|
||||||
|
must be included in all copies of the Software, in whole or in part, and
|
||||||
|
all derivative works of the Software, unless such copies or derivative
|
||||||
|
works are solely in the form of machine-executable object code generated by
|
||||||
|
a source language processor.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT
|
||||||
|
SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE
|
||||||
|
FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE,
|
||||||
|
ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||||
|
DEALINGS IN THE SOFTWARE.
|
||||||
19
scout_base/src/scout_sdk/src/third_party/asio/Makefile.am
vendored
Normal file
19
scout_base/src/scout_sdk/src/third_party/asio/Makefile.am
vendored
Normal file
@@ -0,0 +1,19 @@
|
|||||||
|
AUTOMAKE_OPTIONS = foreign dist-bzip2 dist-zip
|
||||||
|
|
||||||
|
SUBDIRS = include src
|
||||||
|
|
||||||
|
MAINTAINERCLEANFILES = \
|
||||||
|
$(srcdir)/aclocal.m4 \
|
||||||
|
$(srcdir)/configure \
|
||||||
|
$(srcdir)/config.guess \
|
||||||
|
$(srcdir)/config.sub \
|
||||||
|
$(srcdir)/depcomp \
|
||||||
|
$(srcdir)/install-sh \
|
||||||
|
$(srcdir)/missing \
|
||||||
|
$(srcdir)/mkinstalldirs \
|
||||||
|
$(srcdir)/Makefile.in \
|
||||||
|
asio-*.tar.gz
|
||||||
|
|
||||||
|
EXTRA_DIST = \
|
||||||
|
LICENSE_1_0.txt \
|
||||||
|
doc
|
||||||
778
scout_base/src/scout_sdk/src/third_party/asio/Makefile.in
vendored
Normal file
778
scout_base/src/scout_sdk/src/third_party/asio/Makefile.in
vendored
Normal file
@@ -0,0 +1,778 @@
|
|||||||
|
# Makefile.in generated by automake 1.15.1 from Makefile.am.
|
||||||
|
# @configure_input@
|
||||||
|
|
||||||
|
# Copyright (C) 1994-2017 Free Software Foundation, Inc.
|
||||||
|
|
||||||
|
# This Makefile.in is free software; the Free Software Foundation
|
||||||
|
# gives unlimited permission to copy and/or distribute it,
|
||||||
|
# with or without modifications, as long as this notice is preserved.
|
||||||
|
|
||||||
|
# This program is distributed in the hope that it will be useful,
|
||||||
|
# but WITHOUT ANY WARRANTY, to the extent permitted by law; without
|
||||||
|
# even the implied warranty of MERCHANTABILITY or FITNESS FOR A
|
||||||
|
# PARTICULAR PURPOSE.
|
||||||
|
|
||||||
|
@SET_MAKE@
|
||||||
|
VPATH = @srcdir@
|
||||||
|
am__is_gnu_make = { \
|
||||||
|
if test -z '$(MAKELEVEL)'; then \
|
||||||
|
false; \
|
||||||
|
elif test -n '$(MAKE_HOST)'; then \
|
||||||
|
true; \
|
||||||
|
elif test -n '$(MAKE_VERSION)' && test -n '$(CURDIR)'; then \
|
||||||
|
true; \
|
||||||
|
else \
|
||||||
|
false; \
|
||||||
|
fi; \
|
||||||
|
}
|
||||||
|
am__make_running_with_option = \
|
||||||
|
case $${target_option-} in \
|
||||||
|
?) ;; \
|
||||||
|
*) echo "am__make_running_with_option: internal error: invalid" \
|
||||||
|
"target option '$${target_option-}' specified" >&2; \
|
||||||
|
exit 1;; \
|
||||||
|
esac; \
|
||||||
|
has_opt=no; \
|
||||||
|
sane_makeflags=$$MAKEFLAGS; \
|
||||||
|
if $(am__is_gnu_make); then \
|
||||||
|
sane_makeflags=$$MFLAGS; \
|
||||||
|
else \
|
||||||
|
case $$MAKEFLAGS in \
|
||||||
|
*\\[\ \ ]*) \
|
||||||
|
bs=\\; \
|
||||||
|
sane_makeflags=`printf '%s\n' "$$MAKEFLAGS" \
|
||||||
|
| sed "s/$$bs$$bs[$$bs $$bs ]*//g"`;; \
|
||||||
|
esac; \
|
||||||
|
fi; \
|
||||||
|
skip_next=no; \
|
||||||
|
strip_trailopt () \
|
||||||
|
{ \
|
||||||
|
flg=`printf '%s\n' "$$flg" | sed "s/$$1.*$$//"`; \
|
||||||
|
}; \
|
||||||
|
for flg in $$sane_makeflags; do \
|
||||||
|
test $$skip_next = yes && { skip_next=no; continue; }; \
|
||||||
|
case $$flg in \
|
||||||
|
*=*|--*) continue;; \
|
||||||
|
-*I) strip_trailopt 'I'; skip_next=yes;; \
|
||||||
|
-*I?*) strip_trailopt 'I';; \
|
||||||
|
-*O) strip_trailopt 'O'; skip_next=yes;; \
|
||||||
|
-*O?*) strip_trailopt 'O';; \
|
||||||
|
-*l) strip_trailopt 'l'; skip_next=yes;; \
|
||||||
|
-*l?*) strip_trailopt 'l';; \
|
||||||
|
-[dEDm]) skip_next=yes;; \
|
||||||
|
-[JT]) skip_next=yes;; \
|
||||||
|
esac; \
|
||||||
|
case $$flg in \
|
||||||
|
*$$target_option*) has_opt=yes; break;; \
|
||||||
|
esac; \
|
||||||
|
done; \
|
||||||
|
test $$has_opt = yes
|
||||||
|
am__make_dryrun = (target_option=n; $(am__make_running_with_option))
|
||||||
|
am__make_keepgoing = (target_option=k; $(am__make_running_with_option))
|
||||||
|
pkgdatadir = $(datadir)/@PACKAGE@
|
||||||
|
pkgincludedir = $(includedir)/@PACKAGE@
|
||||||
|
pkglibdir = $(libdir)/@PACKAGE@
|
||||||
|
pkglibexecdir = $(libexecdir)/@PACKAGE@
|
||||||
|
am__cd = CDPATH="$${ZSH_VERSION+.}$(PATH_SEPARATOR)" && cd
|
||||||
|
install_sh_DATA = $(install_sh) -c -m 644
|
||||||
|
install_sh_PROGRAM = $(install_sh) -c
|
||||||
|
install_sh_SCRIPT = $(install_sh) -c
|
||||||
|
INSTALL_HEADER = $(INSTALL_DATA)
|
||||||
|
transform = $(program_transform_name)
|
||||||
|
NORMAL_INSTALL = :
|
||||||
|
PRE_INSTALL = :
|
||||||
|
POST_INSTALL = :
|
||||||
|
NORMAL_UNINSTALL = :
|
||||||
|
PRE_UNINSTALL = :
|
||||||
|
POST_UNINSTALL = :
|
||||||
|
build_triplet = @build@
|
||||||
|
host_triplet = @host@
|
||||||
|
subdir = .
|
||||||
|
ACLOCAL_M4 = $(top_srcdir)/aclocal.m4
|
||||||
|
am__aclocal_m4_deps = $(top_srcdir)/configure.ac
|
||||||
|
am__configure_deps = $(am__aclocal_m4_deps) $(CONFIGURE_DEPENDENCIES) \
|
||||||
|
$(ACLOCAL_M4)
|
||||||
|
DIST_COMMON = $(srcdir)/Makefile.am $(top_srcdir)/configure \
|
||||||
|
$(am__configure_deps) $(am__DIST_COMMON)
|
||||||
|
am__CONFIG_DISTCLEAN_FILES = config.status config.cache config.log \
|
||||||
|
configure.lineno config.status.lineno
|
||||||
|
mkinstalldirs = $(install_sh) -d
|
||||||
|
CONFIG_CLEAN_FILES =
|
||||||
|
CONFIG_CLEAN_VPATH_FILES =
|
||||||
|
AM_V_P = $(am__v_P_@AM_V@)
|
||||||
|
am__v_P_ = $(am__v_P_@AM_DEFAULT_V@)
|
||||||
|
am__v_P_0 = false
|
||||||
|
am__v_P_1 = :
|
||||||
|
AM_V_GEN = $(am__v_GEN_@AM_V@)
|
||||||
|
am__v_GEN_ = $(am__v_GEN_@AM_DEFAULT_V@)
|
||||||
|
am__v_GEN_0 = @echo " GEN " $@;
|
||||||
|
am__v_GEN_1 =
|
||||||
|
AM_V_at = $(am__v_at_@AM_V@)
|
||||||
|
am__v_at_ = $(am__v_at_@AM_DEFAULT_V@)
|
||||||
|
am__v_at_0 = @
|
||||||
|
am__v_at_1 =
|
||||||
|
SOURCES =
|
||||||
|
DIST_SOURCES =
|
||||||
|
RECURSIVE_TARGETS = all-recursive check-recursive cscopelist-recursive \
|
||||||
|
ctags-recursive dvi-recursive html-recursive info-recursive \
|
||||||
|
install-data-recursive install-dvi-recursive \
|
||||||
|
install-exec-recursive install-html-recursive \
|
||||||
|
install-info-recursive install-pdf-recursive \
|
||||||
|
install-ps-recursive install-recursive installcheck-recursive \
|
||||||
|
installdirs-recursive pdf-recursive ps-recursive \
|
||||||
|
tags-recursive uninstall-recursive
|
||||||
|
am__can_run_installinfo = \
|
||||||
|
case $$AM_UPDATE_INFO_DIR in \
|
||||||
|
n|no|NO) false;; \
|
||||||
|
*) (install-info --version) >/dev/null 2>&1;; \
|
||||||
|
esac
|
||||||
|
RECURSIVE_CLEAN_TARGETS = mostlyclean-recursive clean-recursive \
|
||||||
|
distclean-recursive maintainer-clean-recursive
|
||||||
|
am__recursive_targets = \
|
||||||
|
$(RECURSIVE_TARGETS) \
|
||||||
|
$(RECURSIVE_CLEAN_TARGETS) \
|
||||||
|
$(am__extra_recursive_targets)
|
||||||
|
AM_RECURSIVE_TARGETS = $(am__recursive_targets:-recursive=) TAGS CTAGS \
|
||||||
|
cscope distdir dist dist-all distcheck
|
||||||
|
am__tagged_files = $(HEADERS) $(SOURCES) $(TAGS_FILES) $(LISP)
|
||||||
|
# Read a list of newline-separated strings from the standard input,
|
||||||
|
# and print each of them once, without duplicates. Input order is
|
||||||
|
# *not* preserved.
|
||||||
|
am__uniquify_input = $(AWK) '\
|
||||||
|
BEGIN { nonempty = 0; } \
|
||||||
|
{ items[$$0] = 1; nonempty = 1; } \
|
||||||
|
END { if (nonempty) { for (i in items) print i; }; } \
|
||||||
|
'
|
||||||
|
# Make sure the list of sources is unique. This is necessary because,
|
||||||
|
# e.g., the same source file might be shared among _SOURCES variables
|
||||||
|
# for different programs/libraries.
|
||||||
|
am__define_uniq_tagged_files = \
|
||||||
|
list='$(am__tagged_files)'; \
|
||||||
|
unique=`for i in $$list; do \
|
||||||
|
if test -f "$$i"; then echo $$i; else echo $(srcdir)/$$i; fi; \
|
||||||
|
done | $(am__uniquify_input)`
|
||||||
|
ETAGS = etags
|
||||||
|
CTAGS = ctags
|
||||||
|
CSCOPE = cscope
|
||||||
|
DIST_SUBDIRS = $(SUBDIRS)
|
||||||
|
am__DIST_COMMON = $(srcdir)/Makefile.in COPYING INSTALL README compile \
|
||||||
|
config.guess config.sub depcomp install-sh missing
|
||||||
|
DISTFILES = $(DIST_COMMON) $(DIST_SOURCES) $(TEXINFOS) $(EXTRA_DIST)
|
||||||
|
distdir = $(PACKAGE)-$(VERSION)
|
||||||
|
top_distdir = $(distdir)
|
||||||
|
am__remove_distdir = \
|
||||||
|
if test -d "$(distdir)"; then \
|
||||||
|
find "$(distdir)" -type d ! -perm -200 -exec chmod u+w {} ';' \
|
||||||
|
&& rm -rf "$(distdir)" \
|
||||||
|
|| { sleep 5 && rm -rf "$(distdir)"; }; \
|
||||||
|
else :; fi
|
||||||
|
am__post_remove_distdir = $(am__remove_distdir)
|
||||||
|
am__relativize = \
|
||||||
|
dir0=`pwd`; \
|
||||||
|
sed_first='s,^\([^/]*\)/.*$$,\1,'; \
|
||||||
|
sed_rest='s,^[^/]*/*,,'; \
|
||||||
|
sed_last='s,^.*/\([^/]*\)$$,\1,'; \
|
||||||
|
sed_butlast='s,/*[^/]*$$,,'; \
|
||||||
|
while test -n "$$dir1"; do \
|
||||||
|
first=`echo "$$dir1" | sed -e "$$sed_first"`; \
|
||||||
|
if test "$$first" != "."; then \
|
||||||
|
if test "$$first" = ".."; then \
|
||||||
|
dir2=`echo "$$dir0" | sed -e "$$sed_last"`/"$$dir2"; \
|
||||||
|
dir0=`echo "$$dir0" | sed -e "$$sed_butlast"`; \
|
||||||
|
else \
|
||||||
|
first2=`echo "$$dir2" | sed -e "$$sed_first"`; \
|
||||||
|
if test "$$first2" = "$$first"; then \
|
||||||
|
dir2=`echo "$$dir2" | sed -e "$$sed_rest"`; \
|
||||||
|
else \
|
||||||
|
dir2="../$$dir2"; \
|
||||||
|
fi; \
|
||||||
|
dir0="$$dir0"/"$$first"; \
|
||||||
|
fi; \
|
||||||
|
fi; \
|
||||||
|
dir1=`echo "$$dir1" | sed -e "$$sed_rest"`; \
|
||||||
|
done; \
|
||||||
|
reldir="$$dir2"
|
||||||
|
DIST_ARCHIVES = $(distdir).tar.gz $(distdir).tar.bz2 $(distdir).zip
|
||||||
|
GZIP_ENV = --best
|
||||||
|
DIST_TARGETS = dist-bzip2 dist-gzip dist-zip
|
||||||
|
distuninstallcheck_listfiles = find . -type f -print
|
||||||
|
am__distuninstallcheck_listfiles = $(distuninstallcheck_listfiles) \
|
||||||
|
| sed 's|^\./|$(prefix)/|' | grep -v '$(infodir)/dir$$'
|
||||||
|
distcleancheck_listfiles = find . -type f -print
|
||||||
|
ACLOCAL = @ACLOCAL@
|
||||||
|
AMTAR = @AMTAR@
|
||||||
|
AM_DEFAULT_VERBOSITY = @AM_DEFAULT_VERBOSITY@
|
||||||
|
AUTOCONF = @AUTOCONF@
|
||||||
|
AUTOHEADER = @AUTOHEADER@
|
||||||
|
AUTOMAKE = @AUTOMAKE@
|
||||||
|
AWK = @AWK@
|
||||||
|
CC = @CC@
|
||||||
|
CCDEPMODE = @CCDEPMODE@
|
||||||
|
CFLAGS = @CFLAGS@
|
||||||
|
CPPFLAGS = @CPPFLAGS@
|
||||||
|
CXX = @CXX@
|
||||||
|
CXXCPP = @CXXCPP@
|
||||||
|
CXXDEPMODE = @CXXDEPMODE@
|
||||||
|
CXXFLAGS = @CXXFLAGS@
|
||||||
|
CYGPATH_W = @CYGPATH_W@
|
||||||
|
DEFS = @DEFS@
|
||||||
|
DEPDIR = @DEPDIR@
|
||||||
|
ECHO_C = @ECHO_C@
|
||||||
|
ECHO_N = @ECHO_N@
|
||||||
|
ECHO_T = @ECHO_T@
|
||||||
|
EGREP = @EGREP@
|
||||||
|
EXEEXT = @EXEEXT@
|
||||||
|
GREP = @GREP@
|
||||||
|
INSTALL = @INSTALL@
|
||||||
|
INSTALL_DATA = @INSTALL_DATA@
|
||||||
|
INSTALL_PROGRAM = @INSTALL_PROGRAM@
|
||||||
|
INSTALL_SCRIPT = @INSTALL_SCRIPT@
|
||||||
|
INSTALL_STRIP_PROGRAM = @INSTALL_STRIP_PROGRAM@
|
||||||
|
LDFLAGS = @LDFLAGS@
|
||||||
|
LIBOBJS = @LIBOBJS@
|
||||||
|
LIBS = @LIBS@
|
||||||
|
LTLIBOBJS = @LTLIBOBJS@
|
||||||
|
MAINT = @MAINT@
|
||||||
|
MAKEINFO = @MAKEINFO@
|
||||||
|
MKDIR_P = @MKDIR_P@
|
||||||
|
OBJEXT = @OBJEXT@
|
||||||
|
PACKAGE = @PACKAGE@
|
||||||
|
PACKAGE_BUGREPORT = @PACKAGE_BUGREPORT@
|
||||||
|
PACKAGE_NAME = @PACKAGE_NAME@
|
||||||
|
PACKAGE_STRING = @PACKAGE_STRING@
|
||||||
|
PACKAGE_TARNAME = @PACKAGE_TARNAME@
|
||||||
|
PACKAGE_URL = @PACKAGE_URL@
|
||||||
|
PACKAGE_VERSION = @PACKAGE_VERSION@
|
||||||
|
PATH_SEPARATOR = @PATH_SEPARATOR@
|
||||||
|
RANLIB = @RANLIB@
|
||||||
|
SET_MAKE = @SET_MAKE@
|
||||||
|
SHELL = @SHELL@
|
||||||
|
STRIP = @STRIP@
|
||||||
|
VERSION = @VERSION@
|
||||||
|
abs_builddir = @abs_builddir@
|
||||||
|
abs_srcdir = @abs_srcdir@
|
||||||
|
abs_top_builddir = @abs_top_builddir@
|
||||||
|
abs_top_srcdir = @abs_top_srcdir@
|
||||||
|
ac_ct_CC = @ac_ct_CC@
|
||||||
|
ac_ct_CXX = @ac_ct_CXX@
|
||||||
|
am__include = @am__include@
|
||||||
|
am__leading_dot = @am__leading_dot@
|
||||||
|
am__quote = @am__quote@
|
||||||
|
am__tar = @am__tar@
|
||||||
|
am__untar = @am__untar@
|
||||||
|
bindir = @bindir@
|
||||||
|
build = @build@
|
||||||
|
build_alias = @build_alias@
|
||||||
|
build_cpu = @build_cpu@
|
||||||
|
build_os = @build_os@
|
||||||
|
build_vendor = @build_vendor@
|
||||||
|
builddir = @builddir@
|
||||||
|
datadir = @datadir@
|
||||||
|
datarootdir = @datarootdir@
|
||||||
|
docdir = @docdir@
|
||||||
|
dvidir = @dvidir@
|
||||||
|
exec_prefix = @exec_prefix@
|
||||||
|
host = @host@
|
||||||
|
host_alias = @host_alias@
|
||||||
|
host_cpu = @host_cpu@
|
||||||
|
host_os = @host_os@
|
||||||
|
host_vendor = @host_vendor@
|
||||||
|
htmldir = @htmldir@
|
||||||
|
includedir = @includedir@
|
||||||
|
infodir = @infodir@
|
||||||
|
install_sh = @install_sh@
|
||||||
|
libdir = @libdir@
|
||||||
|
libexecdir = @libexecdir@
|
||||||
|
localedir = @localedir@
|
||||||
|
localstatedir = @localstatedir@
|
||||||
|
mandir = @mandir@
|
||||||
|
mkdir_p = @mkdir_p@
|
||||||
|
oldincludedir = @oldincludedir@
|
||||||
|
pdfdir = @pdfdir@
|
||||||
|
prefix = @prefix@
|
||||||
|
program_transform_name = @program_transform_name@
|
||||||
|
psdir = @psdir@
|
||||||
|
runstatedir = @runstatedir@
|
||||||
|
sbindir = @sbindir@
|
||||||
|
sharedstatedir = @sharedstatedir@
|
||||||
|
srcdir = @srcdir@
|
||||||
|
sysconfdir = @sysconfdir@
|
||||||
|
target_alias = @target_alias@
|
||||||
|
top_build_prefix = @top_build_prefix@
|
||||||
|
top_builddir = @top_builddir@
|
||||||
|
top_srcdir = @top_srcdir@
|
||||||
|
AUTOMAKE_OPTIONS = foreign dist-bzip2 dist-zip
|
||||||
|
SUBDIRS = include src
|
||||||
|
MAINTAINERCLEANFILES = \
|
||||||
|
$(srcdir)/aclocal.m4 \
|
||||||
|
$(srcdir)/configure \
|
||||||
|
$(srcdir)/config.guess \
|
||||||
|
$(srcdir)/config.sub \
|
||||||
|
$(srcdir)/depcomp \
|
||||||
|
$(srcdir)/install-sh \
|
||||||
|
$(srcdir)/missing \
|
||||||
|
$(srcdir)/mkinstalldirs \
|
||||||
|
$(srcdir)/Makefile.in \
|
||||||
|
asio-*.tar.gz
|
||||||
|
|
||||||
|
EXTRA_DIST = \
|
||||||
|
LICENSE_1_0.txt \
|
||||||
|
doc
|
||||||
|
|
||||||
|
all: all-recursive
|
||||||
|
|
||||||
|
.SUFFIXES:
|
||||||
|
am--refresh: Makefile
|
||||||
|
@:
|
||||||
|
$(srcdir)/Makefile.in: @MAINTAINER_MODE_TRUE@ $(srcdir)/Makefile.am $(am__configure_deps)
|
||||||
|
@for dep in $?; do \
|
||||||
|
case '$(am__configure_deps)' in \
|
||||||
|
*$$dep*) \
|
||||||
|
echo ' cd $(srcdir) && $(AUTOMAKE) --foreign'; \
|
||||||
|
$(am__cd) $(srcdir) && $(AUTOMAKE) --foreign \
|
||||||
|
&& exit 0; \
|
||||||
|
exit 1;; \
|
||||||
|
esac; \
|
||||||
|
done; \
|
||||||
|
echo ' cd $(top_srcdir) && $(AUTOMAKE) --foreign Makefile'; \
|
||||||
|
$(am__cd) $(top_srcdir) && \
|
||||||
|
$(AUTOMAKE) --foreign Makefile
|
||||||
|
Makefile: $(srcdir)/Makefile.in $(top_builddir)/config.status
|
||||||
|
@case '$?' in \
|
||||||
|
*config.status*) \
|
||||||
|
echo ' $(SHELL) ./config.status'; \
|
||||||
|
$(SHELL) ./config.status;; \
|
||||||
|
*) \
|
||||||
|
echo ' cd $(top_builddir) && $(SHELL) ./config.status $@ $(am__depfiles_maybe)'; \
|
||||||
|
cd $(top_builddir) && $(SHELL) ./config.status $@ $(am__depfiles_maybe);; \
|
||||||
|
esac;
|
||||||
|
|
||||||
|
$(top_builddir)/config.status: $(top_srcdir)/configure $(CONFIG_STATUS_DEPENDENCIES)
|
||||||
|
$(SHELL) ./config.status --recheck
|
||||||
|
|
||||||
|
$(top_srcdir)/configure: @MAINTAINER_MODE_TRUE@ $(am__configure_deps)
|
||||||
|
$(am__cd) $(srcdir) && $(AUTOCONF)
|
||||||
|
$(ACLOCAL_M4): @MAINTAINER_MODE_TRUE@ $(am__aclocal_m4_deps)
|
||||||
|
$(am__cd) $(srcdir) && $(ACLOCAL) $(ACLOCAL_AMFLAGS)
|
||||||
|
$(am__aclocal_m4_deps):
|
||||||
|
|
||||||
|
# This directory's subdirectories are mostly independent; you can cd
|
||||||
|
# into them and run 'make' without going through this Makefile.
|
||||||
|
# To change the values of 'make' variables: instead of editing Makefiles,
|
||||||
|
# (1) if the variable is set in 'config.status', edit 'config.status'
|
||||||
|
# (which will cause the Makefiles to be regenerated when you run 'make');
|
||||||
|
# (2) otherwise, pass the desired values on the 'make' command line.
|
||||||
|
$(am__recursive_targets):
|
||||||
|
@fail=; \
|
||||||
|
if $(am__make_keepgoing); then \
|
||||||
|
failcom='fail=yes'; \
|
||||||
|
else \
|
||||||
|
failcom='exit 1'; \
|
||||||
|
fi; \
|
||||||
|
dot_seen=no; \
|
||||||
|
target=`echo $@ | sed s/-recursive//`; \
|
||||||
|
case "$@" in \
|
||||||
|
distclean-* | maintainer-clean-*) list='$(DIST_SUBDIRS)' ;; \
|
||||||
|
*) list='$(SUBDIRS)' ;; \
|
||||||
|
esac; \
|
||||||
|
for subdir in $$list; do \
|
||||||
|
echo "Making $$target in $$subdir"; \
|
||||||
|
if test "$$subdir" = "."; then \
|
||||||
|
dot_seen=yes; \
|
||||||
|
local_target="$$target-am"; \
|
||||||
|
else \
|
||||||
|
local_target="$$target"; \
|
||||||
|
fi; \
|
||||||
|
($(am__cd) $$subdir && $(MAKE) $(AM_MAKEFLAGS) $$local_target) \
|
||||||
|
|| eval $$failcom; \
|
||||||
|
done; \
|
||||||
|
if test "$$dot_seen" = "no"; then \
|
||||||
|
$(MAKE) $(AM_MAKEFLAGS) "$$target-am" || exit 1; \
|
||||||
|
fi; test -z "$$fail"
|
||||||
|
|
||||||
|
ID: $(am__tagged_files)
|
||||||
|
$(am__define_uniq_tagged_files); mkid -fID $$unique
|
||||||
|
tags: tags-recursive
|
||||||
|
TAGS: tags
|
||||||
|
|
||||||
|
tags-am: $(TAGS_DEPENDENCIES) $(am__tagged_files)
|
||||||
|
set x; \
|
||||||
|
here=`pwd`; \
|
||||||
|
if ($(ETAGS) --etags-include --version) >/dev/null 2>&1; then \
|
||||||
|
include_option=--etags-include; \
|
||||||
|
empty_fix=.; \
|
||||||
|
else \
|
||||||
|
include_option=--include; \
|
||||||
|
empty_fix=; \
|
||||||
|
fi; \
|
||||||
|
list='$(SUBDIRS)'; for subdir in $$list; do \
|
||||||
|
if test "$$subdir" = .; then :; else \
|
||||||
|
test ! -f $$subdir/TAGS || \
|
||||||
|
set "$$@" "$$include_option=$$here/$$subdir/TAGS"; \
|
||||||
|
fi; \
|
||||||
|
done; \
|
||||||
|
$(am__define_uniq_tagged_files); \
|
||||||
|
shift; \
|
||||||
|
if test -z "$(ETAGS_ARGS)$$*$$unique"; then :; else \
|
||||||
|
test -n "$$unique" || unique=$$empty_fix; \
|
||||||
|
if test $$# -gt 0; then \
|
||||||
|
$(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \
|
||||||
|
"$$@" $$unique; \
|
||||||
|
else \
|
||||||
|
$(ETAGS) $(ETAGSFLAGS) $(AM_ETAGSFLAGS) $(ETAGS_ARGS) \
|
||||||
|
$$unique; \
|
||||||
|
fi; \
|
||||||
|
fi
|
||||||
|
ctags: ctags-recursive
|
||||||
|
|
||||||
|
CTAGS: ctags
|
||||||
|
ctags-am: $(TAGS_DEPENDENCIES) $(am__tagged_files)
|
||||||
|
$(am__define_uniq_tagged_files); \
|
||||||
|
test -z "$(CTAGS_ARGS)$$unique" \
|
||||||
|
|| $(CTAGS) $(CTAGSFLAGS) $(AM_CTAGSFLAGS) $(CTAGS_ARGS) \
|
||||||
|
$$unique
|
||||||
|
|
||||||
|
GTAGS:
|
||||||
|
here=`$(am__cd) $(top_builddir) && pwd` \
|
||||||
|
&& $(am__cd) $(top_srcdir) \
|
||||||
|
&& gtags -i $(GTAGS_ARGS) "$$here"
|
||||||
|
cscope: cscope.files
|
||||||
|
test ! -s cscope.files \
|
||||||
|
|| $(CSCOPE) -b -q $(AM_CSCOPEFLAGS) $(CSCOPEFLAGS) -i cscope.files $(CSCOPE_ARGS)
|
||||||
|
clean-cscope:
|
||||||
|
-rm -f cscope.files
|
||||||
|
cscope.files: clean-cscope cscopelist
|
||||||
|
cscopelist: cscopelist-recursive
|
||||||
|
|
||||||
|
cscopelist-am: $(am__tagged_files)
|
||||||
|
list='$(am__tagged_files)'; \
|
||||||
|
case "$(srcdir)" in \
|
||||||
|
[\\/]* | ?:[\\/]*) sdir="$(srcdir)" ;; \
|
||||||
|
*) sdir=$(subdir)/$(srcdir) ;; \
|
||||||
|
esac; \
|
||||||
|
for i in $$list; do \
|
||||||
|
if test -f "$$i"; then \
|
||||||
|
echo "$(subdir)/$$i"; \
|
||||||
|
else \
|
||||||
|
echo "$$sdir/$$i"; \
|
||||||
|
fi; \
|
||||||
|
done >> $(top_builddir)/cscope.files
|
||||||
|
|
||||||
|
distclean-tags:
|
||||||
|
-rm -f TAGS ID GTAGS GRTAGS GSYMS GPATH tags
|
||||||
|
-rm -f cscope.out cscope.in.out cscope.po.out cscope.files
|
||||||
|
|
||||||
|
distdir: $(DISTFILES)
|
||||||
|
$(am__remove_distdir)
|
||||||
|
test -d "$(distdir)" || mkdir "$(distdir)"
|
||||||
|
@srcdirstrip=`echo "$(srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \
|
||||||
|
topsrcdirstrip=`echo "$(top_srcdir)" | sed 's/[].[^$$\\*]/\\\\&/g'`; \
|
||||||
|
list='$(DISTFILES)'; \
|
||||||
|
dist_files=`for file in $$list; do echo $$file; done | \
|
||||||
|
sed -e "s|^$$srcdirstrip/||;t" \
|
||||||
|
-e "s|^$$topsrcdirstrip/|$(top_builddir)/|;t"`; \
|
||||||
|
case $$dist_files in \
|
||||||
|
*/*) $(MKDIR_P) `echo "$$dist_files" | \
|
||||||
|
sed '/\//!d;s|^|$(distdir)/|;s,/[^/]*$$,,' | \
|
||||||
|
sort -u` ;; \
|
||||||
|
esac; \
|
||||||
|
for file in $$dist_files; do \
|
||||||
|
if test -f $$file || test -d $$file; then d=.; else d=$(srcdir); fi; \
|
||||||
|
if test -d $$d/$$file; then \
|
||||||
|
dir=`echo "/$$file" | sed -e 's,/[^/]*$$,,'`; \
|
||||||
|
if test -d "$(distdir)/$$file"; then \
|
||||||
|
find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \
|
||||||
|
fi; \
|
||||||
|
if test -d $(srcdir)/$$file && test $$d != $(srcdir); then \
|
||||||
|
cp -fpR $(srcdir)/$$file "$(distdir)$$dir" || exit 1; \
|
||||||
|
find "$(distdir)/$$file" -type d ! -perm -700 -exec chmod u+rwx {} \;; \
|
||||||
|
fi; \
|
||||||
|
cp -fpR $$d/$$file "$(distdir)$$dir" || exit 1; \
|
||||||
|
else \
|
||||||
|
test -f "$(distdir)/$$file" \
|
||||||
|
|| cp -p $$d/$$file "$(distdir)/$$file" \
|
||||||
|
|| exit 1; \
|
||||||
|
fi; \
|
||||||
|
done
|
||||||
|
@list='$(DIST_SUBDIRS)'; for subdir in $$list; do \
|
||||||
|
if test "$$subdir" = .; then :; else \
|
||||||
|
$(am__make_dryrun) \
|
||||||
|
|| test -d "$(distdir)/$$subdir" \
|
||||||
|
|| $(MKDIR_P) "$(distdir)/$$subdir" \
|
||||||
|
|| exit 1; \
|
||||||
|
dir1=$$subdir; dir2="$(distdir)/$$subdir"; \
|
||||||
|
$(am__relativize); \
|
||||||
|
new_distdir=$$reldir; \
|
||||||
|
dir1=$$subdir; dir2="$(top_distdir)"; \
|
||||||
|
$(am__relativize); \
|
||||||
|
new_top_distdir=$$reldir; \
|
||||||
|
echo " (cd $$subdir && $(MAKE) $(AM_MAKEFLAGS) top_distdir="$$new_top_distdir" distdir="$$new_distdir" \\"; \
|
||||||
|
echo " am__remove_distdir=: am__skip_length_check=: am__skip_mode_fix=: distdir)"; \
|
||||||
|
($(am__cd) $$subdir && \
|
||||||
|
$(MAKE) $(AM_MAKEFLAGS) \
|
||||||
|
top_distdir="$$new_top_distdir" \
|
||||||
|
distdir="$$new_distdir" \
|
||||||
|
am__remove_distdir=: \
|
||||||
|
am__skip_length_check=: \
|
||||||
|
am__skip_mode_fix=: \
|
||||||
|
distdir) \
|
||||||
|
|| exit 1; \
|
||||||
|
fi; \
|
||||||
|
done
|
||||||
|
-test -n "$(am__skip_mode_fix)" \
|
||||||
|
|| find "$(distdir)" -type d ! -perm -755 \
|
||||||
|
-exec chmod u+rwx,go+rx {} \; -o \
|
||||||
|
! -type d ! -perm -444 -links 1 -exec chmod a+r {} \; -o \
|
||||||
|
! -type d ! -perm -400 -exec chmod a+r {} \; -o \
|
||||||
|
! -type d ! -perm -444 -exec $(install_sh) -c -m a+r {} {} \; \
|
||||||
|
|| chmod -R a+r "$(distdir)"
|
||||||
|
dist-gzip: distdir
|
||||||
|
tardir=$(distdir) && $(am__tar) | eval GZIP= gzip $(GZIP_ENV) -c >$(distdir).tar.gz
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
dist-bzip2: distdir
|
||||||
|
tardir=$(distdir) && $(am__tar) | BZIP2=$${BZIP2--9} bzip2 -c >$(distdir).tar.bz2
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
|
||||||
|
dist-lzip: distdir
|
||||||
|
tardir=$(distdir) && $(am__tar) | lzip -c $${LZIP_OPT--9} >$(distdir).tar.lz
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
|
||||||
|
dist-xz: distdir
|
||||||
|
tardir=$(distdir) && $(am__tar) | XZ_OPT=$${XZ_OPT--e} xz -c >$(distdir).tar.xz
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
|
||||||
|
dist-tarZ: distdir
|
||||||
|
@echo WARNING: "Support for distribution archives compressed with" \
|
||||||
|
"legacy program 'compress' is deprecated." >&2
|
||||||
|
@echo WARNING: "It will be removed altogether in Automake 2.0" >&2
|
||||||
|
tardir=$(distdir) && $(am__tar) | compress -c >$(distdir).tar.Z
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
|
||||||
|
dist-shar: distdir
|
||||||
|
@echo WARNING: "Support for shar distribution archives is" \
|
||||||
|
"deprecated." >&2
|
||||||
|
@echo WARNING: "It will be removed altogether in Automake 2.0" >&2
|
||||||
|
shar $(distdir) | eval GZIP= gzip $(GZIP_ENV) -c >$(distdir).shar.gz
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
dist-zip: distdir
|
||||||
|
-rm -f $(distdir).zip
|
||||||
|
zip -rq $(distdir).zip $(distdir)
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
|
||||||
|
dist dist-all:
|
||||||
|
$(MAKE) $(AM_MAKEFLAGS) $(DIST_TARGETS) am__post_remove_distdir='@:'
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
|
||||||
|
# This target untars the dist file and tries a VPATH configuration. Then
|
||||||
|
# it guarantees that the distribution is self-contained by making another
|
||||||
|
# tarfile.
|
||||||
|
distcheck: dist
|
||||||
|
case '$(DIST_ARCHIVES)' in \
|
||||||
|
*.tar.gz*) \
|
||||||
|
eval GZIP= gzip $(GZIP_ENV) -dc $(distdir).tar.gz | $(am__untar) ;;\
|
||||||
|
*.tar.bz2*) \
|
||||||
|
bzip2 -dc $(distdir).tar.bz2 | $(am__untar) ;;\
|
||||||
|
*.tar.lz*) \
|
||||||
|
lzip -dc $(distdir).tar.lz | $(am__untar) ;;\
|
||||||
|
*.tar.xz*) \
|
||||||
|
xz -dc $(distdir).tar.xz | $(am__untar) ;;\
|
||||||
|
*.tar.Z*) \
|
||||||
|
uncompress -c $(distdir).tar.Z | $(am__untar) ;;\
|
||||||
|
*.shar.gz*) \
|
||||||
|
eval GZIP= gzip $(GZIP_ENV) -dc $(distdir).shar.gz | unshar ;;\
|
||||||
|
*.zip*) \
|
||||||
|
unzip $(distdir).zip ;;\
|
||||||
|
esac
|
||||||
|
chmod -R a-w $(distdir)
|
||||||
|
chmod u+w $(distdir)
|
||||||
|
mkdir $(distdir)/_build $(distdir)/_build/sub $(distdir)/_inst
|
||||||
|
chmod a-w $(distdir)
|
||||||
|
test -d $(distdir)/_build || exit 0; \
|
||||||
|
dc_install_base=`$(am__cd) $(distdir)/_inst && pwd | sed -e 's,^[^:\\/]:[\\/],/,'` \
|
||||||
|
&& dc_destdir="$${TMPDIR-/tmp}/am-dc-$$$$/" \
|
||||||
|
&& am__cwd=`pwd` \
|
||||||
|
&& $(am__cd) $(distdir)/_build/sub \
|
||||||
|
&& ../../configure \
|
||||||
|
$(AM_DISTCHECK_CONFIGURE_FLAGS) \
|
||||||
|
$(DISTCHECK_CONFIGURE_FLAGS) \
|
||||||
|
--srcdir=../.. --prefix="$$dc_install_base" \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) dvi \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) check \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) install \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) installcheck \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) uninstall \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) distuninstallcheck_dir="$$dc_install_base" \
|
||||||
|
distuninstallcheck \
|
||||||
|
&& chmod -R a-w "$$dc_install_base" \
|
||||||
|
&& ({ \
|
||||||
|
(cd ../.. && umask 077 && mkdir "$$dc_destdir") \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) DESTDIR="$$dc_destdir" install \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) DESTDIR="$$dc_destdir" uninstall \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) DESTDIR="$$dc_destdir" \
|
||||||
|
distuninstallcheck_dir="$$dc_destdir" distuninstallcheck; \
|
||||||
|
} || { rm -rf "$$dc_destdir"; exit 1; }) \
|
||||||
|
&& rm -rf "$$dc_destdir" \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) dist \
|
||||||
|
&& rm -rf $(DIST_ARCHIVES) \
|
||||||
|
&& $(MAKE) $(AM_MAKEFLAGS) distcleancheck \
|
||||||
|
&& cd "$$am__cwd" \
|
||||||
|
|| exit 1
|
||||||
|
$(am__post_remove_distdir)
|
||||||
|
@(echo "$(distdir) archives ready for distribution: "; \
|
||||||
|
list='$(DIST_ARCHIVES)'; for i in $$list; do echo $$i; done) | \
|
||||||
|
sed -e 1h -e 1s/./=/g -e 1p -e 1x -e '$$p' -e '$$x'
|
||||||
|
distuninstallcheck:
|
||||||
|
@test -n '$(distuninstallcheck_dir)' || { \
|
||||||
|
echo 'ERROR: trying to run $@ with an empty' \
|
||||||
|
'$$(distuninstallcheck_dir)' >&2; \
|
||||||
|
exit 1; \
|
||||||
|
}; \
|
||||||
|
$(am__cd) '$(distuninstallcheck_dir)' || { \
|
||||||
|
echo 'ERROR: cannot chdir into $(distuninstallcheck_dir)' >&2; \
|
||||||
|
exit 1; \
|
||||||
|
}; \
|
||||||
|
test `$(am__distuninstallcheck_listfiles) | wc -l` -eq 0 \
|
||||||
|
|| { echo "ERROR: files left after uninstall:" ; \
|
||||||
|
if test -n "$(DESTDIR)"; then \
|
||||||
|
echo " (check DESTDIR support)"; \
|
||||||
|
fi ; \
|
||||||
|
$(distuninstallcheck_listfiles) ; \
|
||||||
|
exit 1; } >&2
|
||||||
|
distcleancheck: distclean
|
||||||
|
@if test '$(srcdir)' = . ; then \
|
||||||
|
echo "ERROR: distcleancheck can only run from a VPATH build" ; \
|
||||||
|
exit 1 ; \
|
||||||
|
fi
|
||||||
|
@test `$(distcleancheck_listfiles) | wc -l` -eq 0 \
|
||||||
|
|| { echo "ERROR: files left in build directory after distclean:" ; \
|
||||||
|
$(distcleancheck_listfiles) ; \
|
||||||
|
exit 1; } >&2
|
||||||
|
check-am: all-am
|
||||||
|
check: check-recursive
|
||||||
|
all-am: Makefile
|
||||||
|
installdirs: installdirs-recursive
|
||||||
|
installdirs-am:
|
||||||
|
install: install-recursive
|
||||||
|
install-exec: install-exec-recursive
|
||||||
|
install-data: install-data-recursive
|
||||||
|
uninstall: uninstall-recursive
|
||||||
|
|
||||||
|
install-am: all-am
|
||||||
|
@$(MAKE) $(AM_MAKEFLAGS) install-exec-am install-data-am
|
||||||
|
|
||||||
|
installcheck: installcheck-recursive
|
||||||
|
install-strip:
|
||||||
|
if test -z '$(STRIP)'; then \
|
||||||
|
$(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \
|
||||||
|
install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \
|
||||||
|
install; \
|
||||||
|
else \
|
||||||
|
$(MAKE) $(AM_MAKEFLAGS) INSTALL_PROGRAM="$(INSTALL_STRIP_PROGRAM)" \
|
||||||
|
install_sh_PROGRAM="$(INSTALL_STRIP_PROGRAM)" INSTALL_STRIP_FLAG=-s \
|
||||||
|
"INSTALL_PROGRAM_ENV=STRIPPROG='$(STRIP)'" install; \
|
||||||
|
fi
|
||||||
|
mostlyclean-generic:
|
||||||
|
|
||||||
|
clean-generic:
|
||||||
|
|
||||||
|
distclean-generic:
|
||||||
|
-test -z "$(CONFIG_CLEAN_FILES)" || rm -f $(CONFIG_CLEAN_FILES)
|
||||||
|
-test . = "$(srcdir)" || test -z "$(CONFIG_CLEAN_VPATH_FILES)" || rm -f $(CONFIG_CLEAN_VPATH_FILES)
|
||||||
|
|
||||||
|
maintainer-clean-generic:
|
||||||
|
@echo "This command is intended for maintainers to use"
|
||||||
|
@echo "it deletes files that may require special tools to rebuild."
|
||||||
|
-test -z "$(MAINTAINERCLEANFILES)" || rm -f $(MAINTAINERCLEANFILES)
|
||||||
|
clean: clean-recursive
|
||||||
|
|
||||||
|
clean-am: clean-generic mostlyclean-am
|
||||||
|
|
||||||
|
distclean: distclean-recursive
|
||||||
|
-rm -f $(am__CONFIG_DISTCLEAN_FILES)
|
||||||
|
-rm -f Makefile
|
||||||
|
distclean-am: clean-am distclean-generic distclean-tags
|
||||||
|
|
||||||
|
dvi: dvi-recursive
|
||||||
|
|
||||||
|
dvi-am:
|
||||||
|
|
||||||
|
html: html-recursive
|
||||||
|
|
||||||
|
html-am:
|
||||||
|
|
||||||
|
info: info-recursive
|
||||||
|
|
||||||
|
info-am:
|
||||||
|
|
||||||
|
install-data-am:
|
||||||
|
|
||||||
|
install-dvi: install-dvi-recursive
|
||||||
|
|
||||||
|
install-dvi-am:
|
||||||
|
|
||||||
|
install-exec-am:
|
||||||
|
|
||||||
|
install-html: install-html-recursive
|
||||||
|
|
||||||
|
install-html-am:
|
||||||
|
|
||||||
|
install-info: install-info-recursive
|
||||||
|
|
||||||
|
install-info-am:
|
||||||
|
|
||||||
|
install-man:
|
||||||
|
|
||||||
|
install-pdf: install-pdf-recursive
|
||||||
|
|
||||||
|
install-pdf-am:
|
||||||
|
|
||||||
|
install-ps: install-ps-recursive
|
||||||
|
|
||||||
|
install-ps-am:
|
||||||
|
|
||||||
|
installcheck-am:
|
||||||
|
|
||||||
|
maintainer-clean: maintainer-clean-recursive
|
||||||
|
-rm -f $(am__CONFIG_DISTCLEAN_FILES)
|
||||||
|
-rm -rf $(top_srcdir)/autom4te.cache
|
||||||
|
-rm -f Makefile
|
||||||
|
maintainer-clean-am: distclean-am maintainer-clean-generic
|
||||||
|
|
||||||
|
mostlyclean: mostlyclean-recursive
|
||||||
|
|
||||||
|
mostlyclean-am: mostlyclean-generic
|
||||||
|
|
||||||
|
pdf: pdf-recursive
|
||||||
|
|
||||||
|
pdf-am:
|
||||||
|
|
||||||
|
ps: ps-recursive
|
||||||
|
|
||||||
|
ps-am:
|
||||||
|
|
||||||
|
uninstall-am:
|
||||||
|
|
||||||
|
.MAKE: $(am__recursive_targets) install-am install-strip
|
||||||
|
|
||||||
|
.PHONY: $(am__recursive_targets) CTAGS GTAGS TAGS all all-am \
|
||||||
|
am--refresh check check-am clean clean-cscope clean-generic \
|
||||||
|
cscope cscopelist-am ctags ctags-am dist dist-all dist-bzip2 \
|
||||||
|
dist-gzip dist-lzip dist-shar dist-tarZ dist-xz dist-zip \
|
||||||
|
distcheck distclean distclean-generic distclean-tags \
|
||||||
|
distcleancheck distdir distuninstallcheck dvi dvi-am html \
|
||||||
|
html-am info info-am install install-am install-data \
|
||||||
|
install-data-am install-dvi install-dvi-am install-exec \
|
||||||
|
install-exec-am install-html install-html-am install-info \
|
||||||
|
install-info-am install-man install-pdf install-pdf-am \
|
||||||
|
install-ps install-ps-am install-strip installcheck \
|
||||||
|
installcheck-am installdirs installdirs-am maintainer-clean \
|
||||||
|
maintainer-clean-generic mostlyclean mostlyclean-generic pdf \
|
||||||
|
pdf-am ps ps-am tags tags-am uninstall uninstall-am
|
||||||
|
|
||||||
|
.PRECIOUS: Makefile
|
||||||
|
|
||||||
|
|
||||||
|
# Tell versions [3.59,3.63) of GNU make to not export all variables.
|
||||||
|
# Otherwise a system limit (for SysV at least) may be exceeded.
|
||||||
|
.NOEXPORT:
|
||||||
4
scout_base/src/scout_sdk/src/third_party/asio/README
vendored
Normal file
4
scout_base/src/scout_sdk/src/third_party/asio/README
vendored
Normal file
@@ -0,0 +1,4 @@
|
|||||||
|
asio version 1.12.1
|
||||||
|
Released Sunday, 15 April 2018.
|
||||||
|
|
||||||
|
See doc/index.html for API documentation and a tutorial.
|
||||||
1188
scout_base/src/scout_sdk/src/third_party/asio/aclocal.m4
vendored
Normal file
1188
scout_base/src/scout_sdk/src/third_party/asio/aclocal.m4
vendored
Normal file
File diff suppressed because it is too large
Load Diff
343
scout_base/src/scout_sdk/src/third_party/asio/compile
vendored
Executable file
343
scout_base/src/scout_sdk/src/third_party/asio/compile
vendored
Executable file
@@ -0,0 +1,343 @@
|
|||||||
|
#! /bin/sh
|
||||||
|
# Wrapper for compilers which do not understand '-c -o'.
|
||||||
|
|
||||||
|
scriptversion=2012-03-05.13; # UTC
|
||||||
|
|
||||||
|
# Copyright (C) 1999, 2000, 2003, 2004, 2005, 2009, 2010, 2012 Free
|
||||||
|
# Software Foundation, Inc.
|
||||||
|
# Written by Tom Tromey <tromey@cygnus.com>.
|
||||||
|
#
|
||||||
|
# This program is free software; you can redistribute it and/or modify
|
||||||
|
# it under the terms of the GNU General Public License as published by
|
||||||
|
# the Free Software Foundation; either version 2, or (at your option)
|
||||||
|
# any later version.
|
||||||
|
#
|
||||||
|
# This program is distributed in the hope that it will be useful,
|
||||||
|
# but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
# GNU General Public License for more details.
|
||||||
|
#
|
||||||
|
# You should have received a copy of the GNU General Public License
|
||||||
|
# along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
# As a special exception to the GNU General Public License, if you
|
||||||
|
# distribute this file as part of a program that contains a
|
||||||
|
# configuration script generated by Autoconf, you may include it under
|
||||||
|
# the same distribution terms that you use for the rest of that program.
|
||||||
|
|
||||||
|
# This file is maintained in Automake, please report
|
||||||
|
# bugs to <bug-automake@gnu.org> or send patches to
|
||||||
|
# <automake-patches@gnu.org>.
|
||||||
|
|
||||||
|
nl='
|
||||||
|
'
|
||||||
|
|
||||||
|
# We need space, tab and new line, in precisely that order. Quoting is
|
||||||
|
# there to prevent tools from complaining about whitespace usage.
|
||||||
|
IFS=" "" $nl"
|
||||||
|
|
||||||
|
file_conv=
|
||||||
|
|
||||||
|
# func_file_conv build_file lazy
|
||||||
|
# Convert a $build file to $host form and store it in $file
|
||||||
|
# Currently only supports Windows hosts. If the determined conversion
|
||||||
|
# type is listed in (the comma separated) LAZY, no conversion will
|
||||||
|
# take place.
|
||||||
|
func_file_conv ()
|
||||||
|
{
|
||||||
|
file=$1
|
||||||
|
case $file in
|
||||||
|
/ | /[!/]*) # absolute file, and not a UNC file
|
||||||
|
if test -z "$file_conv"; then
|
||||||
|
# lazily determine how to convert abs files
|
||||||
|
case `uname -s` in
|
||||||
|
MINGW*)
|
||||||
|
file_conv=mingw
|
||||||
|
;;
|
||||||
|
CYGWIN*)
|
||||||
|
file_conv=cygwin
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
file_conv=wine
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
fi
|
||||||
|
case $file_conv/,$2, in
|
||||||
|
*,$file_conv,*)
|
||||||
|
;;
|
||||||
|
mingw/*)
|
||||||
|
file=`cmd //C echo "$file " | sed -e 's/"\(.*\) " *$/\1/'`
|
||||||
|
;;
|
||||||
|
cygwin/*)
|
||||||
|
file=`cygpath -m "$file" || echo "$file"`
|
||||||
|
;;
|
||||||
|
wine/*)
|
||||||
|
file=`winepath -w "$file" || echo "$file"`
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
}
|
||||||
|
|
||||||
|
# func_cl_dashL linkdir
|
||||||
|
# Make cl look for libraries in LINKDIR
|
||||||
|
func_cl_dashL ()
|
||||||
|
{
|
||||||
|
func_file_conv "$1"
|
||||||
|
if test -z "$lib_path"; then
|
||||||
|
lib_path=$file
|
||||||
|
else
|
||||||
|
lib_path="$lib_path;$file"
|
||||||
|
fi
|
||||||
|
linker_opts="$linker_opts -LIBPATH:$file"
|
||||||
|
}
|
||||||
|
|
||||||
|
# func_cl_dashl library
|
||||||
|
# Do a library search-path lookup for cl
|
||||||
|
func_cl_dashl ()
|
||||||
|
{
|
||||||
|
lib=$1
|
||||||
|
found=no
|
||||||
|
save_IFS=$IFS
|
||||||
|
IFS=';'
|
||||||
|
for dir in $lib_path $LIB
|
||||||
|
do
|
||||||
|
IFS=$save_IFS
|
||||||
|
if $shared && test -f "$dir/$lib.dll.lib"; then
|
||||||
|
found=yes
|
||||||
|
lib=$dir/$lib.dll.lib
|
||||||
|
break
|
||||||
|
fi
|
||||||
|
if test -f "$dir/$lib.lib"; then
|
||||||
|
found=yes
|
||||||
|
lib=$dir/$lib.lib
|
||||||
|
break
|
||||||
|
fi
|
||||||
|
done
|
||||||
|
IFS=$save_IFS
|
||||||
|
|
||||||
|
if test "$found" != yes; then
|
||||||
|
lib=$lib.lib
|
||||||
|
fi
|
||||||
|
}
|
||||||
|
|
||||||
|
# func_cl_wrapper cl arg...
|
||||||
|
# Adjust compile command to suit cl
|
||||||
|
func_cl_wrapper ()
|
||||||
|
{
|
||||||
|
# Assume a capable shell
|
||||||
|
lib_path=
|
||||||
|
shared=:
|
||||||
|
linker_opts=
|
||||||
|
for arg
|
||||||
|
do
|
||||||
|
if test -n "$eat"; then
|
||||||
|
eat=
|
||||||
|
else
|
||||||
|
case $1 in
|
||||||
|
-o)
|
||||||
|
# configure might choose to run compile as 'compile cc -o foo foo.c'.
|
||||||
|
eat=1
|
||||||
|
case $2 in
|
||||||
|
*.o | *.[oO][bB][jJ])
|
||||||
|
func_file_conv "$2"
|
||||||
|
set x "$@" -Fo"$file"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
func_file_conv "$2"
|
||||||
|
set x "$@" -Fe"$file"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
;;
|
||||||
|
-I)
|
||||||
|
eat=1
|
||||||
|
func_file_conv "$2" mingw
|
||||||
|
set x "$@" -I"$file"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
-I*)
|
||||||
|
func_file_conv "${1#-I}" mingw
|
||||||
|
set x "$@" -I"$file"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
-l)
|
||||||
|
eat=1
|
||||||
|
func_cl_dashl "$2"
|
||||||
|
set x "$@" "$lib"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
-l*)
|
||||||
|
func_cl_dashl "${1#-l}"
|
||||||
|
set x "$@" "$lib"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
-L)
|
||||||
|
eat=1
|
||||||
|
func_cl_dashL "$2"
|
||||||
|
;;
|
||||||
|
-L*)
|
||||||
|
func_cl_dashL "${1#-L}"
|
||||||
|
;;
|
||||||
|
-static)
|
||||||
|
shared=false
|
||||||
|
;;
|
||||||
|
-Wl,*)
|
||||||
|
arg=${1#-Wl,}
|
||||||
|
save_ifs="$IFS"; IFS=','
|
||||||
|
for flag in $arg; do
|
||||||
|
IFS="$save_ifs"
|
||||||
|
linker_opts="$linker_opts $flag"
|
||||||
|
done
|
||||||
|
IFS="$save_ifs"
|
||||||
|
;;
|
||||||
|
-Xlinker)
|
||||||
|
eat=1
|
||||||
|
linker_opts="$linker_opts $2"
|
||||||
|
;;
|
||||||
|
-*)
|
||||||
|
set x "$@" "$1"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
*.cc | *.CC | *.cxx | *.CXX | *.[cC]++)
|
||||||
|
func_file_conv "$1"
|
||||||
|
set x "$@" -Tp"$file"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
*.c | *.cpp | *.CPP | *.lib | *.LIB | *.Lib | *.OBJ | *.obj | *.[oO])
|
||||||
|
func_file_conv "$1" mingw
|
||||||
|
set x "$@" "$file"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
set x "$@" "$1"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
fi
|
||||||
|
shift
|
||||||
|
done
|
||||||
|
if test -n "$linker_opts"; then
|
||||||
|
linker_opts="-link$linker_opts"
|
||||||
|
fi
|
||||||
|
exec "$@" $linker_opts
|
||||||
|
exit 1
|
||||||
|
}
|
||||||
|
|
||||||
|
eat=
|
||||||
|
|
||||||
|
case $1 in
|
||||||
|
'')
|
||||||
|
echo "$0: No command. Try '$0 --help' for more information." 1>&2
|
||||||
|
exit 1;
|
||||||
|
;;
|
||||||
|
-h | --h*)
|
||||||
|
cat <<\EOF
|
||||||
|
Usage: compile [--help] [--version] PROGRAM [ARGS]
|
||||||
|
|
||||||
|
Wrapper for compilers which do not understand '-c -o'.
|
||||||
|
Remove '-o dest.o' from ARGS, run PROGRAM with the remaining
|
||||||
|
arguments, and rename the output as expected.
|
||||||
|
|
||||||
|
If you are trying to build a whole package this is not the
|
||||||
|
right script to run: please start by reading the file 'INSTALL'.
|
||||||
|
|
||||||
|
Report bugs to <bug-automake@gnu.org>.
|
||||||
|
EOF
|
||||||
|
exit $?
|
||||||
|
;;
|
||||||
|
-v | --v*)
|
||||||
|
echo "compile $scriptversion"
|
||||||
|
exit $?
|
||||||
|
;;
|
||||||
|
cl | *[/\\]cl | cl.exe | *[/\\]cl.exe )
|
||||||
|
func_cl_wrapper "$@" # Doesn't return...
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
|
||||||
|
ofile=
|
||||||
|
cfile=
|
||||||
|
|
||||||
|
for arg
|
||||||
|
do
|
||||||
|
if test -n "$eat"; then
|
||||||
|
eat=
|
||||||
|
else
|
||||||
|
case $1 in
|
||||||
|
-o)
|
||||||
|
# configure might choose to run compile as 'compile cc -o foo foo.c'.
|
||||||
|
# So we strip '-o arg' only if arg is an object.
|
||||||
|
eat=1
|
||||||
|
case $2 in
|
||||||
|
*.o | *.obj)
|
||||||
|
ofile=$2
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
set x "$@" -o "$2"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
;;
|
||||||
|
*.c)
|
||||||
|
cfile=$1
|
||||||
|
set x "$@" "$1"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
set x "$@" "$1"
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
fi
|
||||||
|
shift
|
||||||
|
done
|
||||||
|
|
||||||
|
if test -z "$ofile" || test -z "$cfile"; then
|
||||||
|
# If no '-o' option was seen then we might have been invoked from a
|
||||||
|
# pattern rule where we don't need one. That is ok -- this is a
|
||||||
|
# normal compilation that the losing compiler can handle. If no
|
||||||
|
# '.c' file was seen then we are probably linking. That is also
|
||||||
|
# ok.
|
||||||
|
exec "$@"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# Name of file we expect compiler to create.
|
||||||
|
cofile=`echo "$cfile" | sed 's|^.*[\\/]||; s|^[a-zA-Z]:||; s/\.c$/.o/'`
|
||||||
|
|
||||||
|
# Create the lock directory.
|
||||||
|
# Note: use '[/\\:.-]' here to ensure that we don't use the same name
|
||||||
|
# that we are using for the .o file. Also, base the name on the expected
|
||||||
|
# object file name, since that is what matters with a parallel build.
|
||||||
|
lockdir=`echo "$cofile" | sed -e 's|[/\\:.-]|_|g'`.d
|
||||||
|
while true; do
|
||||||
|
if mkdir "$lockdir" >/dev/null 2>&1; then
|
||||||
|
break
|
||||||
|
fi
|
||||||
|
sleep 1
|
||||||
|
done
|
||||||
|
# FIXME: race condition here if user kills between mkdir and trap.
|
||||||
|
trap "rmdir '$lockdir'; exit 1" 1 2 15
|
||||||
|
|
||||||
|
# Run the compile.
|
||||||
|
"$@"
|
||||||
|
ret=$?
|
||||||
|
|
||||||
|
if test -f "$cofile"; then
|
||||||
|
test "$cofile" = "$ofile" || mv "$cofile" "$ofile"
|
||||||
|
elif test -f "${cofile}bj"; then
|
||||||
|
test "${cofile}bj" = "$ofile" || mv "${cofile}bj" "$ofile"
|
||||||
|
fi
|
||||||
|
|
||||||
|
rmdir "$lockdir"
|
||||||
|
exit $ret
|
||||||
|
|
||||||
|
# Local Variables:
|
||||||
|
# mode: shell-script
|
||||||
|
# sh-indentation: 2
|
||||||
|
# eval: (add-hook 'write-file-hooks 'time-stamp)
|
||||||
|
# time-stamp-start: "scriptversion="
|
||||||
|
# time-stamp-format: "%:y-%02m-%02d.%02H"
|
||||||
|
# time-stamp-time-zone: "UTC"
|
||||||
|
# time-stamp-end: "; # UTC"
|
||||||
|
# End:
|
||||||
1530
scout_base/src/scout_sdk/src/third_party/asio/config.guess
vendored
Executable file
1530
scout_base/src/scout_sdk/src/third_party/asio/config.guess
vendored
Executable file
File diff suppressed because it is too large
Load Diff
1782
scout_base/src/scout_sdk/src/third_party/asio/config.sub
vendored
Executable file
1782
scout_base/src/scout_sdk/src/third_party/asio/config.sub
vendored
Executable file
File diff suppressed because it is too large
Load Diff
6485
scout_base/src/scout_sdk/src/third_party/asio/configure
vendored
Executable file
6485
scout_base/src/scout_sdk/src/third_party/asio/configure
vendored
Executable file
File diff suppressed because it is too large
Load Diff
186
scout_base/src/scout_sdk/src/third_party/asio/configure.ac
vendored
Normal file
186
scout_base/src/scout_sdk/src/third_party/asio/configure.ac
vendored
Normal file
@@ -0,0 +1,186 @@
|
|||||||
|
AC_INIT(asio, [1.12.1])
|
||||||
|
AC_CONFIG_SRCDIR(include/asio.hpp)
|
||||||
|
AM_MAINTAINER_MODE
|
||||||
|
AM_INIT_AUTOMAKE([tar-ustar])
|
||||||
|
|
||||||
|
AC_CANONICAL_HOST
|
||||||
|
AM_PROG_CC_C_O
|
||||||
|
AC_PROG_CXX
|
||||||
|
AC_LANG(C++)
|
||||||
|
AC_PROG_RANLIB
|
||||||
|
|
||||||
|
AC_DEFINE(_REENTRANT, [1], [Define this])
|
||||||
|
|
||||||
|
AC_ARG_WITH(boost,
|
||||||
|
AC_HELP_STRING([--with-boost=DIR],[location of boost distribution]),
|
||||||
|
[
|
||||||
|
if test "${withval}" = no; then
|
||||||
|
STANDALONE="yes"
|
||||||
|
else
|
||||||
|
CPPFLAGS="$CPPFLAGS -I${withval} -DBOOST_CHRONO_HEADER_ONLY -DBOOST_CHRONO_DONT_PROVIDE_HYBRID_ERROR_HANDLING"
|
||||||
|
LIBS="$LIBS -L${withval}/stage/lib"
|
||||||
|
fi
|
||||||
|
],
|
||||||
|
[
|
||||||
|
BOOSTDIR=`ls -1d ../boost_*_*_*/ 2>/dev/null | sort -t "_" -k 2nr -k 3nr -k 4nr | head -n 1 | sed -e 's/\/$//'`
|
||||||
|
if test "${BOOSTDIR}" != ""; then
|
||||||
|
BOOSTDIR="`pwd`/${BOOSTDIR}"
|
||||||
|
if test -d "${BOOSTDIR}"; then
|
||||||
|
echo "using automatically detected boost from ${BOOSTDIR}"
|
||||||
|
CPPFLAGS="$CPPFLAGS -I${BOOSTDIR} -DBOOST_CHRONO_HEADER_ONLY -DBOOST_CHRONO_DONT_PROVIDE_HYBRID_ERROR_HANDLING"
|
||||||
|
LIBS="$LIBS -L${BOOSTDIR}/stage/lib"
|
||||||
|
fi
|
||||||
|
fi
|
||||||
|
])
|
||||||
|
|
||||||
|
AC_ARG_ENABLE(separate-compilation,
|
||||||
|
[ --enable-separate-compilation separate compilation of asio source],
|
||||||
|
[
|
||||||
|
SEPARATE_COMPILATION=yes
|
||||||
|
])
|
||||||
|
|
||||||
|
AC_ARG_ENABLE(boost-coroutine,
|
||||||
|
[ --enable-boost-coroutine use Boost.Coroutine to implement stackful coroutines],
|
||||||
|
[
|
||||||
|
HAVE_BOOST_COROUTINE=yes
|
||||||
|
])
|
||||||
|
|
||||||
|
if test "$STANDALONE" != yes; then
|
||||||
|
AC_CHECK_HEADER([boost/noncopyable.hpp],,
|
||||||
|
[
|
||||||
|
echo "Can't find boost headers. Please check the location of the boost"
|
||||||
|
echo "distribution and rerun configure using the --with-boost=DIR option."
|
||||||
|
echo "Alternatively, run with --without-boost to enable standalone build."
|
||||||
|
exit 1
|
||||||
|
],[])
|
||||||
|
fi
|
||||||
|
|
||||||
|
AC_ARG_WITH(openssl,
|
||||||
|
AC_HELP_STRING([--with-openssl=DIR],[location of openssl]),
|
||||||
|
[
|
||||||
|
CPPFLAGS="$CPPFLAGS -I${withval}/include"
|
||||||
|
LIBS="$LIBS -L${withval}/lib"
|
||||||
|
],[])
|
||||||
|
|
||||||
|
AC_CHECK_HEADER([openssl/ssl.h],,
|
||||||
|
[
|
||||||
|
OPENSSL_FOUND=no
|
||||||
|
],[])
|
||||||
|
|
||||||
|
if test x$OPENSSL_FOUND != xno; then
|
||||||
|
LIBS="$LIBS -lssl -lcrypto"
|
||||||
|
fi
|
||||||
|
|
||||||
|
AM_CONDITIONAL(HAVE_OPENSSL,test x$OPENSSL_FOUND != xno)
|
||||||
|
|
||||||
|
WINDOWS=no
|
||||||
|
case $host in
|
||||||
|
*-*-linux*)
|
||||||
|
CXXFLAGS="$CXXFLAGS -pthread"
|
||||||
|
LDFLAGS="$LDFLAGS -pthread"
|
||||||
|
LIBS="$LIBS -lrt"
|
||||||
|
;;
|
||||||
|
*-*-solaris*)
|
||||||
|
if test "$GXX" = yes; then
|
||||||
|
CXXFLAGS="$CXXFLAGS -D_PTHREADS"
|
||||||
|
else
|
||||||
|
# We'll assume Sun's CC.
|
||||||
|
CXXFLAGS="$CXXFLAGS -mt"
|
||||||
|
fi
|
||||||
|
LIBS="$LIBS -lsocket -lnsl -lpthread"
|
||||||
|
;;
|
||||||
|
*-*-mingw32*)
|
||||||
|
CXXFLAGS="$CXXFLAGS -mthreads"
|
||||||
|
LDFLAGS="$LDFLAGS -mthreads"
|
||||||
|
LIBS="$LIBS -lws2_32 -lmswsock"
|
||||||
|
WINDOWS=yes
|
||||||
|
;;
|
||||||
|
*-*-mingw64*)
|
||||||
|
CXXFLAGS="$CXXFLAGS -mthreads"
|
||||||
|
LDFLAGS="$LDFLAGS -mthreads"
|
||||||
|
LIBS="$LIBS -lws2_32 -lmswsock"
|
||||||
|
WINDOWS=yes
|
||||||
|
;;
|
||||||
|
*-pc-cygwin*)
|
||||||
|
CXXFLAGS="$CXXFLAGS -D__USE_W32_SOCKETS -D_WIN32_WINNT=0x0501"
|
||||||
|
LIBS="$LIBS -lws2_32 -lmswsock"
|
||||||
|
WINDOWS=yes
|
||||||
|
;;
|
||||||
|
*-apple-darwin*)
|
||||||
|
CXXFLAGS="$CXXFLAGS"
|
||||||
|
LDFLAGS="$LDFLAGS"
|
||||||
|
;;
|
||||||
|
*-*-freebsd*)
|
||||||
|
CXXFLAGS="$CXXFLAGS -pthread"
|
||||||
|
LDFLAGS="$LDFLAGS -pthread"
|
||||||
|
;;
|
||||||
|
*-*-netbsd*)
|
||||||
|
CXXFLAGS="$CXXFLAGS -pthread"
|
||||||
|
LDFLAGS="$LDFLAGS -pthread"
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
|
||||||
|
if test "$GXX" = yes; then
|
||||||
|
CXXFLAGS="$CXXFLAGS -ftemplate-depth-256"
|
||||||
|
fi
|
||||||
|
|
||||||
|
if test "$STANDALONE" = yes; then
|
||||||
|
CPPFLAGS="$CPPFLAGS -DASIO_STANDALONE"
|
||||||
|
fi
|
||||||
|
|
||||||
|
if test "$SEPARATE_COMPILATION" = yes; then
|
||||||
|
CPPFLAGS="$CPPFLAGS -DASIO_SEPARATE_COMPILATION"
|
||||||
|
fi
|
||||||
|
|
||||||
|
AC_MSG_CHECKING([whether C++11 is enabled])
|
||||||
|
AC_COMPILE_IFELSE(
|
||||||
|
[AC_LANG_PROGRAM(
|
||||||
|
[[#if __cplusplus < 201103L]]
|
||||||
|
[[#error C++11 not available]]
|
||||||
|
[[#endif]])],
|
||||||
|
[AC_MSG_RESULT([yes])
|
||||||
|
HAVE_CXX11=yes;],
|
||||||
|
[AC_MSG_RESULT([no])
|
||||||
|
HAVE_CXX11=no;])
|
||||||
|
|
||||||
|
AC_MSG_CHECKING([whether C++14 is enabled])
|
||||||
|
AC_COMPILE_IFELSE(
|
||||||
|
[AC_LANG_PROGRAM(
|
||||||
|
[[#if __cplusplus < 201402L]]
|
||||||
|
[[#error C++14 not available]]
|
||||||
|
[[#endif]])],
|
||||||
|
[AC_MSG_RESULT([yes])
|
||||||
|
HAVE_CXX14=yes;],
|
||||||
|
[AC_MSG_RESULT([no])
|
||||||
|
HAVE_CXX14=no;])
|
||||||
|
|
||||||
|
if test "$GXX" = yes; then
|
||||||
|
if test "$STANDALONE" = yes; then
|
||||||
|
if test "$HAVE_CXX11" = no; then
|
||||||
|
HAVE_CXX11=yes
|
||||||
|
CPPFLAGS="-std=c++0x $CPPFLAGS"
|
||||||
|
fi
|
||||||
|
fi
|
||||||
|
fi
|
||||||
|
|
||||||
|
AM_CONDITIONAL(STANDALONE,test x$STANDALONE = xyes)
|
||||||
|
|
||||||
|
AM_CONDITIONAL(SEPARATE_COMPILATION,test x$SEPARATE_COMPILATION = xyes)
|
||||||
|
|
||||||
|
AM_CONDITIONAL(HAVE_BOOST_COROUTINE,test x$HAVE_BOOST_COROUTINE = xyes)
|
||||||
|
|
||||||
|
AM_CONDITIONAL(WINDOWS_TARGET,test x$WINDOWS != xno)
|
||||||
|
|
||||||
|
AM_CONDITIONAL(HAVE_CXX11,test x$HAVE_CXX11 = xyes)
|
||||||
|
|
||||||
|
AM_CONDITIONAL(HAVE_CXX14,test x$HAVE_CXX14 = xyes)
|
||||||
|
|
||||||
|
AC_OUTPUT([
|
||||||
|
Makefile
|
||||||
|
include/Makefile
|
||||||
|
src/Makefile
|
||||||
|
src/tests/Makefile
|
||||||
|
src/examples/cpp03/Makefile
|
||||||
|
src/examples/cpp11/Makefile
|
||||||
|
src/examples/cpp14/Makefile
|
||||||
|
src/examples/cpp17/Makefile])
|
||||||
708
scout_base/src/scout_sdk/src/third_party/asio/depcomp
vendored
Executable file
708
scout_base/src/scout_sdk/src/third_party/asio/depcomp
vendored
Executable file
@@ -0,0 +1,708 @@
|
|||||||
|
#! /bin/sh
|
||||||
|
# depcomp - compile a program generating dependencies as side-effects
|
||||||
|
|
||||||
|
scriptversion=2012-03-27.16; # UTC
|
||||||
|
|
||||||
|
# Copyright (C) 1999, 2000, 2003, 2004, 2005, 2006, 2007, 2009, 2010,
|
||||||
|
# 2011, 2012 Free Software Foundation, Inc.
|
||||||
|
|
||||||
|
# This program is free software; you can redistribute it and/or modify
|
||||||
|
# it under the terms of the GNU General Public License as published by
|
||||||
|
# the Free Software Foundation; either version 2, or (at your option)
|
||||||
|
# any later version.
|
||||||
|
|
||||||
|
# This program is distributed in the hope that it will be useful,
|
||||||
|
# but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
# GNU General Public License for more details.
|
||||||
|
|
||||||
|
# You should have received a copy of the GNU General Public License
|
||||||
|
# along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
|
# As a special exception to the GNU General Public License, if you
|
||||||
|
# distribute this file as part of a program that contains a
|
||||||
|
# configuration script generated by Autoconf, you may include it under
|
||||||
|
# the same distribution terms that you use for the rest of that program.
|
||||||
|
|
||||||
|
# Originally written by Alexandre Oliva <oliva@dcc.unicamp.br>.
|
||||||
|
|
||||||
|
case $1 in
|
||||||
|
'')
|
||||||
|
echo "$0: No command. Try '$0 --help' for more information." 1>&2
|
||||||
|
exit 1;
|
||||||
|
;;
|
||||||
|
-h | --h*)
|
||||||
|
cat <<\EOF
|
||||||
|
Usage: depcomp [--help] [--version] PROGRAM [ARGS]
|
||||||
|
|
||||||
|
Run PROGRAMS ARGS to compile a file, generating dependencies
|
||||||
|
as side-effects.
|
||||||
|
|
||||||
|
Environment variables:
|
||||||
|
depmode Dependency tracking mode.
|
||||||
|
source Source file read by 'PROGRAMS ARGS'.
|
||||||
|
object Object file output by 'PROGRAMS ARGS'.
|
||||||
|
DEPDIR directory where to store dependencies.
|
||||||
|
depfile Dependency file to output.
|
||||||
|
tmpdepfile Temporary file to use when outputting dependencies.
|
||||||
|
libtool Whether libtool is used (yes/no).
|
||||||
|
|
||||||
|
Report bugs to <bug-automake@gnu.org>.
|
||||||
|
EOF
|
||||||
|
exit $?
|
||||||
|
;;
|
||||||
|
-v | --v*)
|
||||||
|
echo "depcomp $scriptversion"
|
||||||
|
exit $?
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
|
||||||
|
# A tabulation character.
|
||||||
|
tab=' '
|
||||||
|
# A newline character.
|
||||||
|
nl='
|
||||||
|
'
|
||||||
|
|
||||||
|
if test -z "$depmode" || test -z "$source" || test -z "$object"; then
|
||||||
|
echo "depcomp: Variables source, object and depmode must be set" 1>&2
|
||||||
|
exit 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
# Dependencies for sub/bar.o or sub/bar.obj go into sub/.deps/bar.Po.
|
||||||
|
depfile=${depfile-`echo "$object" |
|
||||||
|
sed 's|[^\\/]*$|'${DEPDIR-.deps}'/&|;s|\.\([^.]*\)$|.P\1|;s|Pobj$|Po|'`}
|
||||||
|
tmpdepfile=${tmpdepfile-`echo "$depfile" | sed 's/\.\([^.]*\)$/.T\1/'`}
|
||||||
|
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
|
||||||
|
# Some modes work just like other modes, but use different flags. We
|
||||||
|
# parameterize here, but still list the modes in the big case below,
|
||||||
|
# to make depend.m4 easier to write. Note that we *cannot* use a case
|
||||||
|
# here, because this file can only contain one case statement.
|
||||||
|
if test "$depmode" = hp; then
|
||||||
|
# HP compiler uses -M and no extra arg.
|
||||||
|
gccflag=-M
|
||||||
|
depmode=gcc
|
||||||
|
fi
|
||||||
|
|
||||||
|
if test "$depmode" = dashXmstdout; then
|
||||||
|
# This is just like dashmstdout with a different argument.
|
||||||
|
dashmflag=-xM
|
||||||
|
depmode=dashmstdout
|
||||||
|
fi
|
||||||
|
|
||||||
|
cygpath_u="cygpath -u -f -"
|
||||||
|
if test "$depmode" = msvcmsys; then
|
||||||
|
# This is just like msvisualcpp but w/o cygpath translation.
|
||||||
|
# Just convert the backslash-escaped backslashes to single forward
|
||||||
|
# slashes to satisfy depend.m4
|
||||||
|
cygpath_u='sed s,\\\\,/,g'
|
||||||
|
depmode=msvisualcpp
|
||||||
|
fi
|
||||||
|
|
||||||
|
if test "$depmode" = msvc7msys; then
|
||||||
|
# This is just like msvc7 but w/o cygpath translation.
|
||||||
|
# Just convert the backslash-escaped backslashes to single forward
|
||||||
|
# slashes to satisfy depend.m4
|
||||||
|
cygpath_u='sed s,\\\\,/,g'
|
||||||
|
depmode=msvc7
|
||||||
|
fi
|
||||||
|
|
||||||
|
if test "$depmode" = xlc; then
|
||||||
|
# IBM C/C++ Compilers xlc/xlC can output gcc-like dependency informations.
|
||||||
|
gccflag=-qmakedep=gcc,-MF
|
||||||
|
depmode=gcc
|
||||||
|
fi
|
||||||
|
|
||||||
|
case "$depmode" in
|
||||||
|
gcc3)
|
||||||
|
## gcc 3 implements dependency tracking that does exactly what
|
||||||
|
## we want. Yay! Note: for some reason libtool 1.4 doesn't like
|
||||||
|
## it if -MD -MP comes after the -MF stuff. Hmm.
|
||||||
|
## Unfortunately, FreeBSD c89 acceptance of flags depends upon
|
||||||
|
## the command line argument order; so add the flags where they
|
||||||
|
## appear in depend2.am. Note that the slowdown incurred here
|
||||||
|
## affects only configure: in makefiles, %FASTDEP% shortcuts this.
|
||||||
|
for arg
|
||||||
|
do
|
||||||
|
case $arg in
|
||||||
|
-c) set fnord "$@" -MT "$object" -MD -MP -MF "$tmpdepfile" "$arg" ;;
|
||||||
|
*) set fnord "$@" "$arg" ;;
|
||||||
|
esac
|
||||||
|
shift # fnord
|
||||||
|
shift # $arg
|
||||||
|
done
|
||||||
|
"$@"
|
||||||
|
stat=$?
|
||||||
|
if test $stat -eq 0; then :
|
||||||
|
else
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
exit $stat
|
||||||
|
fi
|
||||||
|
mv "$tmpdepfile" "$depfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
gcc)
|
||||||
|
## There are various ways to get dependency output from gcc. Here's
|
||||||
|
## why we pick this rather obscure method:
|
||||||
|
## - Don't want to use -MD because we'd like the dependencies to end
|
||||||
|
## up in a subdir. Having to rename by hand is ugly.
|
||||||
|
## (We might end up doing this anyway to support other compilers.)
|
||||||
|
## - The DEPENDENCIES_OUTPUT environment variable makes gcc act like
|
||||||
|
## -MM, not -M (despite what the docs say).
|
||||||
|
## - Using -M directly means running the compiler twice (even worse
|
||||||
|
## than renaming).
|
||||||
|
if test -z "$gccflag"; then
|
||||||
|
gccflag=-MD,
|
||||||
|
fi
|
||||||
|
"$@" -Wp,"$gccflag$tmpdepfile"
|
||||||
|
stat=$?
|
||||||
|
if test $stat -eq 0; then :
|
||||||
|
else
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
exit $stat
|
||||||
|
fi
|
||||||
|
rm -f "$depfile"
|
||||||
|
echo "$object : \\" > "$depfile"
|
||||||
|
alpha=ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz
|
||||||
|
## The second -e expression handles DOS-style file names with drive letters.
|
||||||
|
sed -e 's/^[^:]*: / /' \
|
||||||
|
-e 's/^['$alpha']:\/[^:]*: / /' < "$tmpdepfile" >> "$depfile"
|
||||||
|
## This next piece of magic avoids the "deleted header file" problem.
|
||||||
|
## The problem is that when a header file which appears in a .P file
|
||||||
|
## is deleted, the dependency causes make to die (because there is
|
||||||
|
## typically no way to rebuild the header). We avoid this by adding
|
||||||
|
## dummy dependencies for each header file. Too bad gcc doesn't do
|
||||||
|
## this for us directly.
|
||||||
|
tr ' ' "$nl" < "$tmpdepfile" |
|
||||||
|
## Some versions of gcc put a space before the ':'. On the theory
|
||||||
|
## that the space means something, we add a space to the output as
|
||||||
|
## well. hp depmode also adds that space, but also prefixes the VPATH
|
||||||
|
## to the object. Take care to not repeat it in the output.
|
||||||
|
## Some versions of the HPUX 10.20 sed can't process this invocation
|
||||||
|
## correctly. Breaking it into two sed invocations is a workaround.
|
||||||
|
sed -e 's/^\\$//' -e '/^$/d' -e "s|.*$object$||" -e '/:$/d' \
|
||||||
|
| sed -e 's/$/ :/' >> "$depfile"
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
hp)
|
||||||
|
# This case exists only to let depend.m4 do its work. It works by
|
||||||
|
# looking at the text of this script. This case will never be run,
|
||||||
|
# since it is checked for above.
|
||||||
|
exit 1
|
||||||
|
;;
|
||||||
|
|
||||||
|
sgi)
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
"$@" "-Wp,-MDupdate,$tmpdepfile"
|
||||||
|
else
|
||||||
|
"$@" -MDupdate "$tmpdepfile"
|
||||||
|
fi
|
||||||
|
stat=$?
|
||||||
|
if test $stat -eq 0; then :
|
||||||
|
else
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
exit $stat
|
||||||
|
fi
|
||||||
|
rm -f "$depfile"
|
||||||
|
|
||||||
|
if test -f "$tmpdepfile"; then # yes, the sourcefile depend on other files
|
||||||
|
echo "$object : \\" > "$depfile"
|
||||||
|
|
||||||
|
# Clip off the initial element (the dependent). Don't try to be
|
||||||
|
# clever and replace this with sed code, as IRIX sed won't handle
|
||||||
|
# lines with more than a fixed number of characters (4096 in
|
||||||
|
# IRIX 6.2 sed, 8192 in IRIX 6.5). We also remove comment lines;
|
||||||
|
# the IRIX cc adds comments like '#:fec' to the end of the
|
||||||
|
# dependency line.
|
||||||
|
tr ' ' "$nl" < "$tmpdepfile" \
|
||||||
|
| sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' | \
|
||||||
|
tr "$nl" ' ' >> "$depfile"
|
||||||
|
echo >> "$depfile"
|
||||||
|
|
||||||
|
# The second pass generates a dummy entry for each header file.
|
||||||
|
tr ' ' "$nl" < "$tmpdepfile" \
|
||||||
|
| sed -e 's/^.*\.o://' -e 's/#.*$//' -e '/^$/ d' -e 's/$/:/' \
|
||||||
|
>> "$depfile"
|
||||||
|
else
|
||||||
|
# The sourcefile does not contain any dependencies, so just
|
||||||
|
# store a dummy comment line, to avoid errors with the Makefile
|
||||||
|
# "include basename.Plo" scheme.
|
||||||
|
echo "#dummy" > "$depfile"
|
||||||
|
fi
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
xlc)
|
||||||
|
# This case exists only to let depend.m4 do its work. It works by
|
||||||
|
# looking at the text of this script. This case will never be run,
|
||||||
|
# since it is checked for above.
|
||||||
|
exit 1
|
||||||
|
;;
|
||||||
|
|
||||||
|
aix)
|
||||||
|
# The C for AIX Compiler uses -M and outputs the dependencies
|
||||||
|
# in a .u file. In older versions, this file always lives in the
|
||||||
|
# current directory. Also, the AIX compiler puts '$object:' at the
|
||||||
|
# start of each line; $object doesn't have directory information.
|
||||||
|
# Version 6 uses the directory in both cases.
|
||||||
|
dir=`echo "$object" | sed -e 's|/[^/]*$|/|'`
|
||||||
|
test "x$dir" = "x$object" && dir=
|
||||||
|
base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'`
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
tmpdepfile1=$dir$base.u
|
||||||
|
tmpdepfile2=$base.u
|
||||||
|
tmpdepfile3=$dir.libs/$base.u
|
||||||
|
"$@" -Wc,-M
|
||||||
|
else
|
||||||
|
tmpdepfile1=$dir$base.u
|
||||||
|
tmpdepfile2=$dir$base.u
|
||||||
|
tmpdepfile3=$dir$base.u
|
||||||
|
"$@" -M
|
||||||
|
fi
|
||||||
|
stat=$?
|
||||||
|
|
||||||
|
if test $stat -eq 0; then :
|
||||||
|
else
|
||||||
|
rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3"
|
||||||
|
exit $stat
|
||||||
|
fi
|
||||||
|
|
||||||
|
for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3"
|
||||||
|
do
|
||||||
|
test -f "$tmpdepfile" && break
|
||||||
|
done
|
||||||
|
if test -f "$tmpdepfile"; then
|
||||||
|
# Each line is of the form 'foo.o: dependent.h'.
|
||||||
|
# Do two passes, one to just change these to
|
||||||
|
# '$object: dependent.h' and one to simply 'dependent.h:'.
|
||||||
|
sed -e "s,^.*\.[a-z]*:,$object:," < "$tmpdepfile" > "$depfile"
|
||||||
|
sed -e 's,^.*\.[a-z]*:['"$tab"' ]*,,' -e 's,$,:,' < "$tmpdepfile" >> "$depfile"
|
||||||
|
else
|
||||||
|
# The sourcefile does not contain any dependencies, so just
|
||||||
|
# store a dummy comment line, to avoid errors with the Makefile
|
||||||
|
# "include basename.Plo" scheme.
|
||||||
|
echo "#dummy" > "$depfile"
|
||||||
|
fi
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
icc)
|
||||||
|
# Intel's C compiler anf tcc (Tiny C Compiler) understand '-MD -MF file'.
|
||||||
|
# However on
|
||||||
|
# $CC -MD -MF foo.d -c -o sub/foo.o sub/foo.c
|
||||||
|
# ICC 7.0 will fill foo.d with something like
|
||||||
|
# foo.o: sub/foo.c
|
||||||
|
# foo.o: sub/foo.h
|
||||||
|
# which is wrong. We want
|
||||||
|
# sub/foo.o: sub/foo.c
|
||||||
|
# sub/foo.o: sub/foo.h
|
||||||
|
# sub/foo.c:
|
||||||
|
# sub/foo.h:
|
||||||
|
# ICC 7.1 will output
|
||||||
|
# foo.o: sub/foo.c sub/foo.h
|
||||||
|
# and will wrap long lines using '\':
|
||||||
|
# foo.o: sub/foo.c ... \
|
||||||
|
# sub/foo.h ... \
|
||||||
|
# ...
|
||||||
|
# tcc 0.9.26 (FIXME still under development at the moment of writing)
|
||||||
|
# will emit a similar output, but also prepend the continuation lines
|
||||||
|
# with horizontal tabulation characters.
|
||||||
|
"$@" -MD -MF "$tmpdepfile"
|
||||||
|
stat=$?
|
||||||
|
if test $stat -eq 0; then :
|
||||||
|
else
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
exit $stat
|
||||||
|
fi
|
||||||
|
rm -f "$depfile"
|
||||||
|
# Each line is of the form 'foo.o: dependent.h',
|
||||||
|
# or 'foo.o: dep1.h dep2.h \', or ' dep3.h dep4.h \'.
|
||||||
|
# Do two passes, one to just change these to
|
||||||
|
# '$object: dependent.h' and one to simply 'dependent.h:'.
|
||||||
|
sed -e "s/^[ $tab][ $tab]*/ /" -e "s,^[^:]*:,$object :," \
|
||||||
|
< "$tmpdepfile" > "$depfile"
|
||||||
|
sed '
|
||||||
|
s/[ '"$tab"'][ '"$tab"']*/ /g
|
||||||
|
s/^ *//
|
||||||
|
s/ *\\*$//
|
||||||
|
s/^[^:]*: *//
|
||||||
|
/^$/d
|
||||||
|
/:$/d
|
||||||
|
s/$/ :/
|
||||||
|
' < "$tmpdepfile" >> "$depfile"
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
hp2)
|
||||||
|
# The "hp" stanza above does not work with aCC (C++) and HP's ia64
|
||||||
|
# compilers, which have integrated preprocessors. The correct option
|
||||||
|
# to use with these is +Maked; it writes dependencies to a file named
|
||||||
|
# 'foo.d', which lands next to the object file, wherever that
|
||||||
|
# happens to be.
|
||||||
|
# Much of this is similar to the tru64 case; see comments there.
|
||||||
|
dir=`echo "$object" | sed -e 's|/[^/]*$|/|'`
|
||||||
|
test "x$dir" = "x$object" && dir=
|
||||||
|
base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'`
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
tmpdepfile1=$dir$base.d
|
||||||
|
tmpdepfile2=$dir.libs/$base.d
|
||||||
|
"$@" -Wc,+Maked
|
||||||
|
else
|
||||||
|
tmpdepfile1=$dir$base.d
|
||||||
|
tmpdepfile2=$dir$base.d
|
||||||
|
"$@" +Maked
|
||||||
|
fi
|
||||||
|
stat=$?
|
||||||
|
if test $stat -eq 0; then :
|
||||||
|
else
|
||||||
|
rm -f "$tmpdepfile1" "$tmpdepfile2"
|
||||||
|
exit $stat
|
||||||
|
fi
|
||||||
|
|
||||||
|
for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2"
|
||||||
|
do
|
||||||
|
test -f "$tmpdepfile" && break
|
||||||
|
done
|
||||||
|
if test -f "$tmpdepfile"; then
|
||||||
|
sed -e "s,^.*\.[a-z]*:,$object:," "$tmpdepfile" > "$depfile"
|
||||||
|
# Add 'dependent.h:' lines.
|
||||||
|
sed -ne '2,${
|
||||||
|
s/^ *//
|
||||||
|
s/ \\*$//
|
||||||
|
s/$/:/
|
||||||
|
p
|
||||||
|
}' "$tmpdepfile" >> "$depfile"
|
||||||
|
else
|
||||||
|
echo "#dummy" > "$depfile"
|
||||||
|
fi
|
||||||
|
rm -f "$tmpdepfile" "$tmpdepfile2"
|
||||||
|
;;
|
||||||
|
|
||||||
|
tru64)
|
||||||
|
# The Tru64 compiler uses -MD to generate dependencies as a side
|
||||||
|
# effect. 'cc -MD -o foo.o ...' puts the dependencies into 'foo.o.d'.
|
||||||
|
# At least on Alpha/Redhat 6.1, Compaq CCC V6.2-504 seems to put
|
||||||
|
# dependencies in 'foo.d' instead, so we check for that too.
|
||||||
|
# Subdirectories are respected.
|
||||||
|
dir=`echo "$object" | sed -e 's|/[^/]*$|/|'`
|
||||||
|
test "x$dir" = "x$object" && dir=
|
||||||
|
base=`echo "$object" | sed -e 's|^.*/||' -e 's/\.o$//' -e 's/\.lo$//'`
|
||||||
|
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
# With Tru64 cc, shared objects can also be used to make a
|
||||||
|
# static library. This mechanism is used in libtool 1.4 series to
|
||||||
|
# handle both shared and static libraries in a single compilation.
|
||||||
|
# With libtool 1.4, dependencies were output in $dir.libs/$base.lo.d.
|
||||||
|
#
|
||||||
|
# With libtool 1.5 this exception was removed, and libtool now
|
||||||
|
# generates 2 separate objects for the 2 libraries. These two
|
||||||
|
# compilations output dependencies in $dir.libs/$base.o.d and
|
||||||
|
# in $dir$base.o.d. We have to check for both files, because
|
||||||
|
# one of the two compilations can be disabled. We should prefer
|
||||||
|
# $dir$base.o.d over $dir.libs/$base.o.d because the latter is
|
||||||
|
# automatically cleaned when .libs/ is deleted, while ignoring
|
||||||
|
# the former would cause a distcleancheck panic.
|
||||||
|
tmpdepfile1=$dir.libs/$base.lo.d # libtool 1.4
|
||||||
|
tmpdepfile2=$dir$base.o.d # libtool 1.5
|
||||||
|
tmpdepfile3=$dir.libs/$base.o.d # libtool 1.5
|
||||||
|
tmpdepfile4=$dir.libs/$base.d # Compaq CCC V6.2-504
|
||||||
|
"$@" -Wc,-MD
|
||||||
|
else
|
||||||
|
tmpdepfile1=$dir$base.o.d
|
||||||
|
tmpdepfile2=$dir$base.d
|
||||||
|
tmpdepfile3=$dir$base.d
|
||||||
|
tmpdepfile4=$dir$base.d
|
||||||
|
"$@" -MD
|
||||||
|
fi
|
||||||
|
|
||||||
|
stat=$?
|
||||||
|
if test $stat -eq 0; then :
|
||||||
|
else
|
||||||
|
rm -f "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" "$tmpdepfile4"
|
||||||
|
exit $stat
|
||||||
|
fi
|
||||||
|
|
||||||
|
for tmpdepfile in "$tmpdepfile1" "$tmpdepfile2" "$tmpdepfile3" "$tmpdepfile4"
|
||||||
|
do
|
||||||
|
test -f "$tmpdepfile" && break
|
||||||
|
done
|
||||||
|
if test -f "$tmpdepfile"; then
|
||||||
|
sed -e "s,^.*\.[a-z]*:,$object:," < "$tmpdepfile" > "$depfile"
|
||||||
|
sed -e 's,^.*\.[a-z]*:['"$tab"' ]*,,' -e 's,$,:,' < "$tmpdepfile" >> "$depfile"
|
||||||
|
else
|
||||||
|
echo "#dummy" > "$depfile"
|
||||||
|
fi
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
msvc7)
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
showIncludes=-Wc,-showIncludes
|
||||||
|
else
|
||||||
|
showIncludes=-showIncludes
|
||||||
|
fi
|
||||||
|
"$@" $showIncludes > "$tmpdepfile"
|
||||||
|
stat=$?
|
||||||
|
grep -v '^Note: including file: ' "$tmpdepfile"
|
||||||
|
if test "$stat" = 0; then :
|
||||||
|
else
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
exit $stat
|
||||||
|
fi
|
||||||
|
rm -f "$depfile"
|
||||||
|
echo "$object : \\" > "$depfile"
|
||||||
|
# The first sed program below extracts the file names and escapes
|
||||||
|
# backslashes for cygpath. The second sed program outputs the file
|
||||||
|
# name when reading, but also accumulates all include files in the
|
||||||
|
# hold buffer in order to output them again at the end. This only
|
||||||
|
# works with sed implementations that can handle large buffers.
|
||||||
|
sed < "$tmpdepfile" -n '
|
||||||
|
/^Note: including file: *\(.*\)/ {
|
||||||
|
s//\1/
|
||||||
|
s/\\/\\\\/g
|
||||||
|
p
|
||||||
|
}' | $cygpath_u | sort -u | sed -n '
|
||||||
|
s/ /\\ /g
|
||||||
|
s/\(.*\)/'"$tab"'\1 \\/p
|
||||||
|
s/.\(.*\) \\/\1:/
|
||||||
|
H
|
||||||
|
$ {
|
||||||
|
s/.*/'"$tab"'/
|
||||||
|
G
|
||||||
|
p
|
||||||
|
}' >> "$depfile"
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
msvc7msys)
|
||||||
|
# This case exists only to let depend.m4 do its work. It works by
|
||||||
|
# looking at the text of this script. This case will never be run,
|
||||||
|
# since it is checked for above.
|
||||||
|
exit 1
|
||||||
|
;;
|
||||||
|
|
||||||
|
#nosideeffect)
|
||||||
|
# This comment above is used by automake to tell side-effect
|
||||||
|
# dependency tracking mechanisms from slower ones.
|
||||||
|
|
||||||
|
dashmstdout)
|
||||||
|
# Important note: in order to support this mode, a compiler *must*
|
||||||
|
# always write the preprocessed file to stdout, regardless of -o.
|
||||||
|
"$@" || exit $?
|
||||||
|
|
||||||
|
# Remove the call to Libtool.
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
while test "X$1" != 'X--mode=compile'; do
|
||||||
|
shift
|
||||||
|
done
|
||||||
|
shift
|
||||||
|
fi
|
||||||
|
|
||||||
|
# Remove '-o $object'.
|
||||||
|
IFS=" "
|
||||||
|
for arg
|
||||||
|
do
|
||||||
|
case $arg in
|
||||||
|
-o)
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
$object)
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
set fnord "$@" "$arg"
|
||||||
|
shift # fnord
|
||||||
|
shift # $arg
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
done
|
||||||
|
|
||||||
|
test -z "$dashmflag" && dashmflag=-M
|
||||||
|
# Require at least two characters before searching for ':'
|
||||||
|
# in the target name. This is to cope with DOS-style filenames:
|
||||||
|
# a dependency such as 'c:/foo/bar' could be seen as target 'c' otherwise.
|
||||||
|
"$@" $dashmflag |
|
||||||
|
sed 's:^['"$tab"' ]*[^:'"$tab"' ][^:][^:]*\:['"$tab"' ]*:'"$object"'\: :' > "$tmpdepfile"
|
||||||
|
rm -f "$depfile"
|
||||||
|
cat < "$tmpdepfile" > "$depfile"
|
||||||
|
tr ' ' "$nl" < "$tmpdepfile" | \
|
||||||
|
## Some versions of the HPUX 10.20 sed can't process this invocation
|
||||||
|
## correctly. Breaking it into two sed invocations is a workaround.
|
||||||
|
sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' | sed -e 's/$/ :/' >> "$depfile"
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
dashXmstdout)
|
||||||
|
# This case only exists to satisfy depend.m4. It is never actually
|
||||||
|
# run, as this mode is specially recognized in the preamble.
|
||||||
|
exit 1
|
||||||
|
;;
|
||||||
|
|
||||||
|
makedepend)
|
||||||
|
"$@" || exit $?
|
||||||
|
# Remove any Libtool call
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
while test "X$1" != 'X--mode=compile'; do
|
||||||
|
shift
|
||||||
|
done
|
||||||
|
shift
|
||||||
|
fi
|
||||||
|
# X makedepend
|
||||||
|
shift
|
||||||
|
cleared=no eat=no
|
||||||
|
for arg
|
||||||
|
do
|
||||||
|
case $cleared in
|
||||||
|
no)
|
||||||
|
set ""; shift
|
||||||
|
cleared=yes ;;
|
||||||
|
esac
|
||||||
|
if test $eat = yes; then
|
||||||
|
eat=no
|
||||||
|
continue
|
||||||
|
fi
|
||||||
|
case "$arg" in
|
||||||
|
-D*|-I*)
|
||||||
|
set fnord "$@" "$arg"; shift ;;
|
||||||
|
# Strip any option that makedepend may not understand. Remove
|
||||||
|
# the object too, otherwise makedepend will parse it as a source file.
|
||||||
|
-arch)
|
||||||
|
eat=yes ;;
|
||||||
|
-*|$object)
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
set fnord "$@" "$arg"; shift ;;
|
||||||
|
esac
|
||||||
|
done
|
||||||
|
obj_suffix=`echo "$object" | sed 's/^.*\././'`
|
||||||
|
touch "$tmpdepfile"
|
||||||
|
${MAKEDEPEND-makedepend} -o"$obj_suffix" -f"$tmpdepfile" "$@"
|
||||||
|
rm -f "$depfile"
|
||||||
|
# makedepend may prepend the VPATH from the source file name to the object.
|
||||||
|
# No need to regex-escape $object, excess matching of '.' is harmless.
|
||||||
|
sed "s|^.*\($object *:\)|\1|" "$tmpdepfile" > "$depfile"
|
||||||
|
sed '1,2d' "$tmpdepfile" | tr ' ' "$nl" | \
|
||||||
|
## Some versions of the HPUX 10.20 sed can't process this invocation
|
||||||
|
## correctly. Breaking it into two sed invocations is a workaround.
|
||||||
|
sed -e 's/^\\$//' -e '/^$/d' -e '/:$/d' | sed -e 's/$/ :/' >> "$depfile"
|
||||||
|
rm -f "$tmpdepfile" "$tmpdepfile".bak
|
||||||
|
;;
|
||||||
|
|
||||||
|
cpp)
|
||||||
|
# Important note: in order to support this mode, a compiler *must*
|
||||||
|
# always write the preprocessed file to stdout.
|
||||||
|
"$@" || exit $?
|
||||||
|
|
||||||
|
# Remove the call to Libtool.
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
while test "X$1" != 'X--mode=compile'; do
|
||||||
|
shift
|
||||||
|
done
|
||||||
|
shift
|
||||||
|
fi
|
||||||
|
|
||||||
|
# Remove '-o $object'.
|
||||||
|
IFS=" "
|
||||||
|
for arg
|
||||||
|
do
|
||||||
|
case $arg in
|
||||||
|
-o)
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
$object)
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
set fnord "$@" "$arg"
|
||||||
|
shift # fnord
|
||||||
|
shift # $arg
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
done
|
||||||
|
|
||||||
|
"$@" -E |
|
||||||
|
sed -n -e '/^# [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' \
|
||||||
|
-e '/^#line [0-9][0-9]* "\([^"]*\)".*/ s:: \1 \\:p' |
|
||||||
|
sed '$ s: \\$::' > "$tmpdepfile"
|
||||||
|
rm -f "$depfile"
|
||||||
|
echo "$object : \\" > "$depfile"
|
||||||
|
cat < "$tmpdepfile" >> "$depfile"
|
||||||
|
sed < "$tmpdepfile" '/^$/d;s/^ //;s/ \\$//;s/$/ :/' >> "$depfile"
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
msvisualcpp)
|
||||||
|
# Important note: in order to support this mode, a compiler *must*
|
||||||
|
# always write the preprocessed file to stdout.
|
||||||
|
"$@" || exit $?
|
||||||
|
|
||||||
|
# Remove the call to Libtool.
|
||||||
|
if test "$libtool" = yes; then
|
||||||
|
while test "X$1" != 'X--mode=compile'; do
|
||||||
|
shift
|
||||||
|
done
|
||||||
|
shift
|
||||||
|
fi
|
||||||
|
|
||||||
|
IFS=" "
|
||||||
|
for arg
|
||||||
|
do
|
||||||
|
case "$arg" in
|
||||||
|
-o)
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
$object)
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
"-Gm"|"/Gm"|"-Gi"|"/Gi"|"-ZI"|"/ZI")
|
||||||
|
set fnord "$@"
|
||||||
|
shift
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
*)
|
||||||
|
set fnord "$@" "$arg"
|
||||||
|
shift
|
||||||
|
shift
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
done
|
||||||
|
"$@" -E 2>/dev/null |
|
||||||
|
sed -n '/^#line [0-9][0-9]* "\([^"]*\)"/ s::\1:p' | $cygpath_u | sort -u > "$tmpdepfile"
|
||||||
|
rm -f "$depfile"
|
||||||
|
echo "$object : \\" > "$depfile"
|
||||||
|
sed < "$tmpdepfile" -n -e 's% %\\ %g' -e '/^\(.*\)$/ s::'"$tab"'\1 \\:p' >> "$depfile"
|
||||||
|
echo "$tab" >> "$depfile"
|
||||||
|
sed < "$tmpdepfile" -n -e 's% %\\ %g' -e '/^\(.*\)$/ s::\1\::p' >> "$depfile"
|
||||||
|
rm -f "$tmpdepfile"
|
||||||
|
;;
|
||||||
|
|
||||||
|
msvcmsys)
|
||||||
|
# This case exists only to let depend.m4 do its work. It works by
|
||||||
|
# looking at the text of this script. This case will never be run,
|
||||||
|
# since it is checked for above.
|
||||||
|
exit 1
|
||||||
|
;;
|
||||||
|
|
||||||
|
none)
|
||||||
|
exec "$@"
|
||||||
|
;;
|
||||||
|
|
||||||
|
*)
|
||||||
|
echo "Unknown depmode $depmode" 1>&2
|
||||||
|
exit 1
|
||||||
|
;;
|
||||||
|
esac
|
||||||
|
|
||||||
|
exit 0
|
||||||
|
|
||||||
|
# Local Variables:
|
||||||
|
# mode: shell-script
|
||||||
|
# sh-indentation: 2
|
||||||
|
# eval: (add-hook 'write-file-hooks 'time-stamp)
|
||||||
|
# time-stamp-start: "scriptversion="
|
||||||
|
# time-stamp-format: "%:y-%02m-%02d.%02H"
|
||||||
|
# time-stamp-time-zone: "UTC"
|
||||||
|
# time-stamp-end: "; # UTC"
|
||||||
|
# End:
|
||||||
BIN
scout_base/src/scout_sdk/src/third_party/asio/doc/asio.png
vendored
Normal file
BIN
scout_base/src/scout_sdk/src/third_party/asio/doc/asio.png
vendored
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 3.1 KiB |
54
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/examples.html
vendored
Normal file
54
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/examples.html
vendored
Normal file
@@ -0,0 +1,54 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Examples</title>
|
||||||
|
<link rel="stylesheet" href="../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../index.html" title="Asio">
|
||||||
|
<link rel="prev" href="tutorial/boost_bind.html" title="boost::bind">
|
||||||
|
<link rel="next" href="examples/cpp03_examples.html" title="C++03 Examples">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="tutorial/boost_bind.html"><img src="../prev.png" alt="Prev"></a><a accesskey="u" href="../index.html"><img src="../up.png" alt="Up"></a><a accesskey="h" href="../index.html"><img src="../home.png" alt="Home"></a><a accesskey="n" href="examples/cpp03_examples.html"><img src="../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h2 class="title" style="clear: both">
|
||||||
|
<a name="asio.examples"></a><a class="link" href="examples.html" title="Examples">Examples</a>
|
||||||
|
</h2></div></div></div>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="examples/cpp03_examples.html" title="C++03 Examples">C++03 Examples</a>: Illustrates
|
||||||
|
the use of Asio using only C++03 language and library features. Where necessary,
|
||||||
|
the examples make use of selected Boost C++ libraries.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="examples/cpp11_examples.html" title="C++11 Examples">C++11 Examples</a>: Contains
|
||||||
|
a limited set of the C++03 Asio examples, updated to use only C++11 library
|
||||||
|
and language facilities. These examples do not make direct use of Boost
|
||||||
|
C++ libraries. To show the changes between C++03 and C++11, these examples
|
||||||
|
include a diff between the C++03 and C++11 versions.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="examples/cpp17_examples.html" title="C++17 Examples">C++17 Examples</a>: Selected
|
||||||
|
examples illustrating C++17 usage in conjunction with Technical Specifications.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="tutorial/boost_bind.html"><img src="../prev.png" alt="Prev"></a><a accesskey="u" href="../index.html"><img src="../up.png" alt="Up"></a><a accesskey="h" href="../index.html"><img src="../home.png" alt="Home"></a><a accesskey="n" href="examples/cpp03_examples.html"><img src="../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
635
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/examples/cpp03_examples.html
vendored
Normal file
635
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/examples/cpp03_examples.html
vendored
Normal file
@@ -0,0 +1,635 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>C++03 Examples</title>
|
||||||
|
<link rel="stylesheet" href="../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../examples.html" title="Examples">
|
||||||
|
<link rel="prev" href="../examples.html" title="Examples">
|
||||||
|
<link rel="next" href="cpp11_examples.html" title="C++11 Examples">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="../examples.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../examples.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="cpp11_examples.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h3 class="title">
|
||||||
|
<a name="asio.examples.cpp03_examples"></a><a class="link" href="cpp03_examples.html" title="C++03 Examples">C++03 Examples</a>
|
||||||
|
</h3></div></div></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h0"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.allocation"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.allocation">Allocation</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example shows how to customise the allocation of memory associated with
|
||||||
|
asynchronous operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/allocation/server.cpp" target="_top">../src/examples/cpp03/allocation/server.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h1"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.buffers"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.buffers">Buffers</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example demonstrates how to create reference counted buffers that can
|
||||||
|
be used with socket read and write operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/buffers/reference_counted.cpp" target="_top">../src/examples/cpp03/buffers/reference_counted.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h2"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.chat"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.chat">Chat</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example implements a chat server and client. The programs use a custom
|
||||||
|
protocol with a fixed length message header and variable length message body.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/chat/chat_message.hpp" target="_top">../src/examples/cpp03/chat/chat_message.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/chat/chat_client.cpp" target="_top">../src/examples/cpp03/chat/chat_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/chat/chat_server.cpp" target="_top">../src/examples/cpp03/chat/chat_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
The following POSIX-specific chat client demonstrates how to use the <a class="link" href="../reference/posix__stream_descriptor.html" title="posix::stream_descriptor">posix::stream_descriptor</a>
|
||||||
|
class to perform console input and output.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/chat/posix_chat_client.cpp" target="_top">../src/examples/cpp03/chat/posix_chat_client.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h3"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.echo"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.echo">Echo</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
A collection of simple clients and servers, showing the use of both synchronous
|
||||||
|
and asynchronous operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/echo/async_tcp_echo_server.cpp" target="_top">../src/examples/cpp03/echo/async_tcp_echo_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/echo/async_udp_echo_server.cpp" target="_top">../src/examples/cpp03/echo/async_udp_echo_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/echo/blocking_tcp_echo_client.cpp" target="_top">../src/examples/cpp03/echo/blocking_tcp_echo_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/echo/blocking_tcp_echo_server.cpp" target="_top">../src/examples/cpp03/echo/blocking_tcp_echo_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/echo/blocking_udp_echo_client.cpp" target="_top">../src/examples/cpp03/echo/blocking_udp_echo_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/echo/blocking_udp_echo_server.cpp" target="_top">../src/examples/cpp03/echo/blocking_udp_echo_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h4"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.fork"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.fork">Fork</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
These POSIX-specific examples show how to use Asio in conjunction with the
|
||||||
|
<code class="computeroutput">fork()</code> system call. The first example illustrates the steps
|
||||||
|
required to start a daemon process:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/fork/daemon.cpp" target="_top">../src/examples/cpp03/fork/daemon.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<p>
|
||||||
|
The second example demonstrates how it is possible to fork a process from
|
||||||
|
within a completion handler.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/fork/process_per_connection.cpp" target="_top">../src/examples/cpp03/fork/process_per_connection.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h5"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.http_client"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.http_client">HTTP
|
||||||
|
Client</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example programs implementing simple HTTP 1.0 clients. These examples show
|
||||||
|
how to use the <a class="link" href="../reference/read_until.html" title="read_until">read_until</a>
|
||||||
|
and <a class="link" href="../reference/async_read_until.html" title="async_read_until">async_read_until</a>
|
||||||
|
functions.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/client/sync_client.cpp" target="_top">../src/examples/cpp03/http/client/sync_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/client/async_client.cpp" target="_top">../src/examples/cpp03/http/client/async_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h6"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.http_server"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.http_server">HTTP
|
||||||
|
Server</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example illustrates the use of asio in a simple single-threaded server
|
||||||
|
implementation of HTTP 1.0. It demonstrates how to perform a clean shutdown
|
||||||
|
by cancelling all outstanding asynchronous operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/connection.cpp" target="_top">../src/examples/cpp03/http/server/connection.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/connection.hpp" target="_top">../src/examples/cpp03/http/server/connection.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/connection_manager.cpp" target="_top">../src/examples/cpp03/http/server/connection_manager.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/connection_manager.hpp" target="_top">../src/examples/cpp03/http/server/connection_manager.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/header.hpp" target="_top">../src/examples/cpp03/http/server/header.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/main.cpp" target="_top">../src/examples/cpp03/http/server/main.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/mime_types.cpp" target="_top">../src/examples/cpp03/http/server/mime_types.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/mime_types.hpp" target="_top">../src/examples/cpp03/http/server/mime_types.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/reply.cpp" target="_top">../src/examples/cpp03/http/server/reply.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/reply.hpp" target="_top">../src/examples/cpp03/http/server/reply.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/request.hpp" target="_top">../src/examples/cpp03/http/server/request.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/request_handler.cpp" target="_top">../src/examples/cpp03/http/server/request_handler.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/request_handler.hpp" target="_top">../src/examples/cpp03/http/server/request_handler.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/request_parser.cpp" target="_top">../src/examples/cpp03/http/server/request_parser.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/request_parser.hpp" target="_top">../src/examples/cpp03/http/server/request_parser.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/server.cpp" target="_top">../src/examples/cpp03/http/server/server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server/server.hpp" target="_top">../src/examples/cpp03/http/server/server.hpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h7"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.http_server_2"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.http_server_2">HTTP
|
||||||
|
Server 2</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
An HTTP server using an io_context-per-CPU design.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/connection.cpp" target="_top">../src/examples/cpp03/http/server2/connection.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/connection.hpp" target="_top">../src/examples/cpp03/http/server2/connection.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/header.hpp" target="_top">../src/examples/cpp03/http/server2/header.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/io_context_pool.cpp" target="_top">../src/examples/cpp03/http/server2/io_context_pool.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/io_context_pool.hpp" target="_top">../src/examples/cpp03/http/server2/io_context_pool.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/main.cpp" target="_top">../src/examples/cpp03/http/server2/main.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/mime_types.cpp" target="_top">../src/examples/cpp03/http/server2/mime_types.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/mime_types.hpp" target="_top">../src/examples/cpp03/http/server2/mime_types.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/reply.cpp" target="_top">../src/examples/cpp03/http/server2/reply.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/reply.hpp" target="_top">../src/examples/cpp03/http/server2/reply.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/request.hpp" target="_top">../src/examples/cpp03/http/server2/request.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/request_handler.cpp" target="_top">../src/examples/cpp03/http/server2/request_handler.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/request_handler.hpp" target="_top">../src/examples/cpp03/http/server2/request_handler.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/request_parser.cpp" target="_top">../src/examples/cpp03/http/server2/request_parser.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/request_parser.hpp" target="_top">../src/examples/cpp03/http/server2/request_parser.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/server.cpp" target="_top">../src/examples/cpp03/http/server2/server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server2/server.hpp" target="_top">../src/examples/cpp03/http/server2/server.hpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h8"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.http_server_3"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.http_server_3">HTTP
|
||||||
|
Server 3</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
An HTTP server using a single io_context and a thread pool calling <code class="computeroutput">io_context::run()</code>.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/connection.cpp" target="_top">../src/examples/cpp03/http/server3/connection.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/connection.hpp" target="_top">../src/examples/cpp03/http/server3/connection.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/header.hpp" target="_top">../src/examples/cpp03/http/server3/header.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/main.cpp" target="_top">../src/examples/cpp03/http/server3/main.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/mime_types.cpp" target="_top">../src/examples/cpp03/http/server3/mime_types.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/mime_types.hpp" target="_top">../src/examples/cpp03/http/server3/mime_types.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/reply.cpp" target="_top">../src/examples/cpp03/http/server3/reply.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/reply.hpp" target="_top">../src/examples/cpp03/http/server3/reply.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/request.hpp" target="_top">../src/examples/cpp03/http/server3/request.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/request_handler.cpp" target="_top">../src/examples/cpp03/http/server3/request_handler.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/request_handler.hpp" target="_top">../src/examples/cpp03/http/server3/request_handler.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/request_parser.cpp" target="_top">../src/examples/cpp03/http/server3/request_parser.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/request_parser.hpp" target="_top">../src/examples/cpp03/http/server3/request_parser.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/server.cpp" target="_top">../src/examples/cpp03/http/server3/server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server3/server.hpp" target="_top">../src/examples/cpp03/http/server3/server.hpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h9"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.http_server_4"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.http_server_4">HTTP
|
||||||
|
Server 4</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
A single-threaded HTTP server implemented using stackless coroutines.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/file_handler.cpp" target="_top">../src/examples/cpp03/http/server4/file_handler.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/file_handler.hpp" target="_top">../src/examples/cpp03/http/server4/file_handler.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/header.hpp" target="_top">../src/examples/cpp03/http/server4/header.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/main.cpp" target="_top">../src/examples/cpp03/http/server4/main.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/mime_types.cpp" target="_top">../src/examples/cpp03/http/server4/mime_types.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/mime_types.hpp" target="_top">../src/examples/cpp03/http/server4/mime_types.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/reply.cpp" target="_top">../src/examples/cpp03/http/server4/reply.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/reply.hpp" target="_top">../src/examples/cpp03/http/server4/reply.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/request.hpp" target="_top">../src/examples/cpp03/http/server4/request.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/request_parser.cpp" target="_top">../src/examples/cpp03/http/server4/request_parser.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/request_parser.hpp" target="_top">../src/examples/cpp03/http/server4/request_parser.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/server.cpp" target="_top">../src/examples/cpp03/http/server4/server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/http/server4/server.hpp" target="_top">../src/examples/cpp03/http/server4/server.hpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h10"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.icmp"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.icmp">ICMP</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example shows how to use raw sockets with ICMP to ping a remote host.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/icmp/ping.cpp" target="_top">../src/examples/cpp03/icmp/ping.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/icmp/ipv4_header.hpp" target="_top">../src/examples/cpp03/icmp/ipv4_header.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/icmp/icmp_header.hpp" target="_top">../src/examples/cpp03/icmp/icmp_header.hpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h11"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.invocation"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.invocation">Invocation</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example shows how to customise handler invocation. Completion handlers
|
||||||
|
are added to a priority queue rather than executed immediately.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/invocation/prioritised_handlers.cpp" target="_top">../src/examples/cpp03/invocation/prioritised_handlers.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h12"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.iostreams"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.iostreams">Iostreams</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Two examples showing how to use <a class="link" href="../reference/ip__tcp/iostream.html" title="ip::tcp::iostream">ip::tcp::iostream</a>.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/iostreams/daytime_client.cpp" target="_top">../src/examples/cpp03/iostreams/daytime_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/iostreams/daytime_server.cpp" target="_top">../src/examples/cpp03/iostreams/daytime_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/iostreams/http_client.cpp" target="_top">../src/examples/cpp03/iostreams/http_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h13"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.multicast"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.multicast">Multicast</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
An example showing the use of multicast to transmit packets to a group of
|
||||||
|
subscribers.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/multicast/receiver.cpp" target="_top">../src/examples/cpp03/multicast/receiver.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/multicast/sender.cpp" target="_top">../src/examples/cpp03/multicast/sender.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h14"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.serialization"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.serialization">Serialization</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example shows how Boost.Serialization can be used with asio to encode
|
||||||
|
and decode structures for transmission over a socket.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/serialization/client.cpp" target="_top">../src/examples/cpp03/serialization/client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/serialization/connection.hpp" target="_top">../src/examples/cpp03/serialization/connection.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/serialization/server.cpp" target="_top">../src/examples/cpp03/serialization/server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/serialization/stock.hpp" target="_top">../src/examples/cpp03/serialization/stock.hpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h15"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.services"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.services">Services</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example demonstrates how to integrate custom functionality (in this
|
||||||
|
case, for logging) into asio's <a class="link" href="../reference/io_context.html" title="io_context">io_context</a>,
|
||||||
|
and how to use a custom service with <a class="link" href="../reference/basic_stream_socket.html" title="basic_stream_socket">basic_stream_socket<></a>.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/services/basic_logger.hpp" target="_top">../src/examples/cpp03/services/basic_logger.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/services/daytime_client.cpp" target="_top">../src/examples/cpp03/services/daytime_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/services/logger.hpp" target="_top">../src/examples/cpp03/services/logger.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/services/logger_service.cpp" target="_top">../src/examples/cpp03/services/logger_service.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/services/logger_service.hpp" target="_top">../src/examples/cpp03/services/logger_service.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/services/stream_socket_service.hpp" target="_top">../src/examples/cpp03/services/stream_socket_service.hpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h16"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.socks_4"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.socks_4">SOCKS
|
||||||
|
4</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example client program implementing the SOCKS 4 protocol for communication
|
||||||
|
via a proxy.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/socks4/sync_client.cpp" target="_top">../src/examples/cpp03/socks4/sync_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/socks4/socks4.hpp" target="_top">../src/examples/cpp03/socks4/socks4.hpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h17"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.ssl"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.ssl">SSL</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example client and server programs showing the use of the <a class="link" href="../reference/ssl__stream.html" title="ssl::stream">ssl::stream<></a>
|
||||||
|
template with asynchronous operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/ssl/client.cpp" target="_top">../src/examples/cpp03/ssl/client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/ssl/server.cpp" target="_top">../src/examples/cpp03/ssl/server.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h18"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.timeouts"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.timeouts">Timeouts</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
A collection of examples showing how to cancel long running asynchronous
|
||||||
|
operations after a period of time.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/timeouts/async_tcp_client.cpp" target="_top">../src/examples/cpp03/timeouts/async_tcp_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/timeouts/blocking_tcp_client.cpp" target="_top">../src/examples/cpp03/timeouts/blocking_tcp_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/timeouts/blocking_token_tcp_client.cpp" target="_top">../src/examples/cpp03/timeouts/blocking_token_tcp_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/timeouts/blocking_udp_client.cpp" target="_top">../src/examples/cpp03/timeouts/blocking_udp_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/timeouts/server.cpp" target="_top">../src/examples/cpp03/timeouts/server.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h19"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.timers"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.timers">Timers</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example showing how to customise basic_waitable_timer using a different clock
|
||||||
|
type.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/timers/time_t_timer.cpp" target="_top">../src/examples/cpp03/timers/time_t_timer.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h20"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.porthopper"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.porthopper">Porthopper</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example illustrating mixed synchronous and asynchronous operations, and how
|
||||||
|
to use Boost.Lambda with Asio.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/porthopper/protocol.hpp" target="_top">../src/examples/cpp03/porthopper/protocol.hpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/porthopper/client.cpp" target="_top">../src/examples/cpp03/porthopper/client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/porthopper/server.cpp" target="_top">../src/examples/cpp03/porthopper/server.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h21"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.nonblocking"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.nonblocking">Nonblocking</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example demonstrating reactor-style operations for integrating a third-party
|
||||||
|
library that wants to perform the I/O operations itself.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/nonblocking/third_party_lib.cpp" target="_top">../src/examples/cpp03/nonblocking/third_party_lib.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h22"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.spawn"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.spawn">Spawn</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example of using the asio::spawn() function, a wrapper around the <a href="http://www.boost.org/doc/libs/release/libs/coroutine/index.html" target="_top">Boost.Coroutine</a>
|
||||||
|
library, to implement a chain of asynchronous operations using stackful coroutines.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/spawn/echo_server.cpp" target="_top">../src/examples/cpp03/spawn/echo_server.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h23"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.unix_domain_sockets"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.unix_domain_sockets">UNIX
|
||||||
|
Domain Sockets</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Examples showing how to use UNIX domain (local) sockets.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/local/connect_pair.cpp" target="_top">../src/examples/cpp03/local/connect_pair.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/local/iostream_client.cpp" target="_top">../src/examples/cpp03/local/iostream_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/local/stream_server.cpp" target="_top">../src/examples/cpp03/local/stream_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/local/stream_client.cpp" target="_top">../src/examples/cpp03/local/stream_client.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp03_examples.h24"></a>
|
||||||
|
<span><a name="asio.examples.cpp03_examples.windows"></a></span><a class="link" href="cpp03_examples.html#asio.examples.cpp03_examples.windows">Windows</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
An example showing how to use the Windows-specific function <code class="computeroutput">TransmitFile</code>
|
||||||
|
with Asio.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp03/windows/transmit_file.cpp" target="_top">../src/examples/cpp03/windows/transmit_file.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="../examples.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../examples.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="cpp11_examples.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
326
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/examples/cpp11_examples.html
vendored
Normal file
326
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/examples/cpp11_examples.html
vendored
Normal file
@@ -0,0 +1,326 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>C++11 Examples</title>
|
||||||
|
<link rel="stylesheet" href="../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../examples.html" title="Examples">
|
||||||
|
<link rel="prev" href="cpp03_examples.html" title="C++03 Examples">
|
||||||
|
<link rel="next" href="cpp17_examples.html" title="C++17 Examples">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="cpp03_examples.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../examples.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="cpp17_examples.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h3 class="title">
|
||||||
|
<a name="asio.examples.cpp11_examples"></a><a class="link" href="cpp11_examples.html" title="C++11 Examples">C++11 Examples</a>
|
||||||
|
</h3></div></div></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h0"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.allocation"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.allocation">Allocation</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example shows how to customise the allocation of memory associated with
|
||||||
|
asynchronous operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/allocation/server.cpp" target="_top">../src/examples/cpp11/allocation/server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/allocation/server.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h1"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.buffers"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.buffers">Buffers</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example demonstrates how to create reference counted buffers that can
|
||||||
|
be used with socket read and write operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/buffers/reference_counted.cpp" target="_top">../src/examples/cpp11/buffers/reference_counted.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/buffers/reference_counted.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h2"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.chat"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.chat">Chat</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example implements a chat server and client. The programs use a custom
|
||||||
|
protocol with a fixed length message header and variable length message body.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/chat/chat_message.hpp" target="_top">../src/examples/cpp11/chat/chat_message.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/chat/chat_message.hpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/chat/chat_client.cpp" target="_top">../src/examples/cpp11/chat/chat_client.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/chat/chat_client.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/chat/chat_server.cpp" target="_top">../src/examples/cpp11/chat/chat_server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/chat/chat_server.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h3"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.echo"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.echo">Echo</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
A collection of simple clients and servers, showing the use of both synchronous
|
||||||
|
and asynchronous operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/echo/async_tcp_echo_server.cpp" target="_top">../src/examples/cpp11/echo/async_tcp_echo_server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/echo/async_tcp_echo_server.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/echo/async_udp_echo_server.cpp" target="_top">../src/examples/cpp11/echo/async_udp_echo_server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/echo/async_udp_echo_server.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/echo/blocking_tcp_echo_client.cpp" target="_top">../src/examples/cpp11/echo/blocking_tcp_echo_client.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/echo/blocking_tcp_echo_client.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/echo/blocking_tcp_echo_server.cpp" target="_top">../src/examples/cpp11/echo/blocking_tcp_echo_server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/echo/blocking_tcp_echo_server.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/echo/blocking_udp_echo_client.cpp" target="_top">../src/examples/cpp11/echo/blocking_udp_echo_client.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/echo/blocking_udp_echo_client.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/echo/blocking_udp_echo_server.cpp" target="_top">../src/examples/cpp11/echo/blocking_udp_echo_server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/echo/blocking_udp_echo_server.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h4"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.fork"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.fork">Fork</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
These POSIX-specific examples show how to use Asio in conjunction with the
|
||||||
|
<code class="computeroutput">fork()</code> system call. The first example illustrates the steps
|
||||||
|
required to start a daemon process:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/fork/daemon.cpp" target="_top">../src/examples/cpp11/fork/daemon.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/fork/daemon.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li></ul></div>
|
||||||
|
<p>
|
||||||
|
The second example demonstrates how it is possible to fork a process from
|
||||||
|
within a completion handler.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/fork/process_per_connection.cpp" target="_top">../src/examples/cpp11/fork/process_per_connection.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/fork/process_per_connection.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h5"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.futures"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.futures">Futures</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example demonstrates how to use std::future in conjunction with Asio's
|
||||||
|
asynchronous operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/futures/daytime_client.cpp" target="_top">../src/examples/cpp11/futures/daytime_client.cpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h6"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.handler_tracking"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.handler_tracking">Handler
|
||||||
|
Tracking</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example shows how to implement custom handler tracking.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/handler_tracking/custom_tracking.hpp" target="_top">../src/examples/cpp11/handler_tracking/custom_tracking.hpp</a>
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h7"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.http_server"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.http_server">HTTP
|
||||||
|
Server</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
This example illustrates the use of asio in a simple single-threaded server
|
||||||
|
implementation of HTTP 1.0. It demonstrates how to perform a clean shutdown
|
||||||
|
by cancelling all outstanding asynchronous operations.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/connection.cpp" target="_top">../src/examples/cpp11/http/server/connection.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/connection.cpp.html" target="_top">diff to
|
||||||
|
C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/connection.hpp" target="_top">../src/examples/cpp11/http/server/connection.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/connection.hpp.html" target="_top">diff to
|
||||||
|
C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/connection_manager.cpp" target="_top">../src/examples/cpp11/http/server/connection_manager.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/connection_manager.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/connection_manager.hpp" target="_top">../src/examples/cpp11/http/server/connection_manager.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/connection_manager.hpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/header.hpp" target="_top">../src/examples/cpp11/http/server/header.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/header.hpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/main.cpp" target="_top">../src/examples/cpp11/http/server/main.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/main.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/mime_types.cpp" target="_top">../src/examples/cpp11/http/server/mime_types.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/mime_types.cpp.html" target="_top">diff to
|
||||||
|
C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/mime_types.hpp" target="_top">../src/examples/cpp11/http/server/mime_types.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/mime_types.hpp.html" target="_top">diff to
|
||||||
|
C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/reply.cpp" target="_top">../src/examples/cpp11/http/server/reply.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/reply.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/reply.hpp" target="_top">../src/examples/cpp11/http/server/reply.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/reply.hpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/request.hpp" target="_top">../src/examples/cpp11/http/server/request.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/request.hpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/request_handler.cpp" target="_top">../src/examples/cpp11/http/server/request_handler.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/request_handler.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/request_handler.hpp" target="_top">../src/examples/cpp11/http/server/request_handler.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/request_handler.hpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/request_parser.cpp" target="_top">../src/examples/cpp11/http/server/request_parser.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/request_parser.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/request_parser.hpp" target="_top">../src/examples/cpp11/http/server/request_parser.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/request_parser.hpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/server.cpp" target="_top">../src/examples/cpp11/http/server/server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/server.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/http/server/server.hpp" target="_top">../src/examples/cpp11/http/server/server.hpp</a>
|
||||||
|
(<a href="../../examples/diffs/http/server/server.hpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h8"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.multicast"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.multicast">Multicast</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
An example showing the use of multicast to transmit packets to a group of
|
||||||
|
subscribers.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/multicast/receiver.cpp" target="_top">../src/examples/cpp11/multicast/receiver.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/multicast/receiver.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/multicast/sender.cpp" target="_top">../src/examples/cpp11/multicast/sender.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/multicast/sender.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h9"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.nonblocking"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.nonblocking">Nonblocking</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example demonstrating reactor-style operations for integrating a third-party
|
||||||
|
library that wants to perform the I/O operations itself.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/nonblocking/third_party_lib.cpp" target="_top">../src/examples/cpp11/nonblocking/third_party_lib.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/nonblocking/third_party_lib.cpp.html" target="_top">diff
|
||||||
|
to C++03</a>)
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h10"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.spawn"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.spawn">Spawn</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Example of using the asio::spawn() function, a wrapper around the <a href="http://www.boost.org/doc/libs/release/libs/coroutine/index.html" target="_top">Boost.Coroutine</a>
|
||||||
|
library, to implement a chain of asynchronous operations using stackful coroutines.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/spawn/echo_server.cpp" target="_top">../src/examples/cpp11/spawn/echo_server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/spawn/echo_server.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li></ul></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp11_examples.h11"></a>
|
||||||
|
<span><a name="asio.examples.cpp11_examples.unix_domain_sockets"></a></span><a class="link" href="cpp11_examples.html#asio.examples.cpp11_examples.unix_domain_sockets">UNIX
|
||||||
|
Domain Sockets</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Examples showing how to use UNIX domain (local) sockets.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/local/connect_pair.cpp" target="_top">../src/examples/cpp11/local/connect_pair.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/local/connect_pair.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/local/iostream_client.cpp" target="_top">../src/examples/cpp11/local/iostream_client.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/local/iostream_client.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/local/stream_server.cpp" target="_top">../src/examples/cpp11/local/stream_server.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/local/stream_server.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../../../src/examples/cpp11/local/stream_client.cpp" target="_top">../src/examples/cpp11/local/stream_client.cpp</a>
|
||||||
|
(<a href="../../examples/diffs/local/stream_client.cpp.html" target="_top">diff to C++03</a>)
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="cpp03_examples.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../examples.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="cpp17_examples.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
62
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/examples/cpp17_examples.html
vendored
Normal file
62
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/examples/cpp17_examples.html
vendored
Normal file
@@ -0,0 +1,62 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>C++17 Examples</title>
|
||||||
|
<link rel="stylesheet" href="../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../examples.html" title="Examples">
|
||||||
|
<link rel="prev" href="cpp11_examples.html" title="C++11 Examples">
|
||||||
|
<link rel="next" href="../reference.html" title="Reference">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="cpp11_examples.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../examples.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="../reference.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h3 class="title">
|
||||||
|
<a name="asio.examples.cpp17_examples"></a><a class="link" href="cpp17_examples.html" title="C++17 Examples">C++17 Examples</a>
|
||||||
|
</h3></div></div></div>
|
||||||
|
<h5>
|
||||||
|
<a name="asio.examples.cpp17_examples.h0"></a>
|
||||||
|
<span><a name="asio.examples.cpp17_examples.coroutines_ts_support"></a></span><a class="link" href="cpp17_examples.html#asio.examples.cpp17_examples.coroutines_ts_support">Coroutines
|
||||||
|
TS Support</a>
|
||||||
|
</h5>
|
||||||
|
<p>
|
||||||
|
Examples showing how to implement a chain of asynchronous operations using
|
||||||
|
the Coroutines TS.
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../example/cpp17/coroutines_ts/echo_server.cpp" target="_top">asio/example/cpp17/coroutines_ts/echo_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../example/cpp17/coroutines_ts/refactored_echo_server.cpp" target="_top">asio/example/cpp17/coroutines_ts/refactored_echo_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../example/cpp17/coroutines_ts/double_buffered_echo_server.cpp" target="_top">asio/example/cpp17/coroutines_ts/double_buffered_echo_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../example/cpp17/coroutines_ts/chat_server.cpp" target="_top">asio/example/cpp17/coroutines_ts/chat_server.cpp</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a href="../example/cpp17/coroutines_ts/range_based_for.cpp" target="_top">asio/example/cpp17/coroutines_ts/range_based_for.cpp</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="cpp11_examples.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../examples.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="../reference.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
1984
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/history.html
vendored
Normal file
1984
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/history.html
vendored
Normal file
File diff suppressed because it is too large
Load Diff
4960
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/index.html
vendored
Normal file
4960
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/index.html
vendored
Normal file
File diff suppressed because it is too large
Load Diff
1221
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/net_ts.html
vendored
Normal file
1221
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/net_ts.html
vendored
Normal file
File diff suppressed because it is too large
Load Diff
155
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview.html
vendored
Normal file
155
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview.html
vendored
Normal file
@@ -0,0 +1,155 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Overview</title>
|
||||||
|
<link rel="stylesheet" href="../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../index.html" title="Asio">
|
||||||
|
<link rel="prev" href="../index.html" title="Asio">
|
||||||
|
<link rel="next" href="overview/rationale.html" title="Rationale">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="../index.html"><img src="../prev.png" alt="Prev"></a><a accesskey="u" href="../index.html"><img src="../up.png" alt="Up"></a><a accesskey="h" href="../index.html"><img src="../home.png" alt="Home"></a><a accesskey="n" href="overview/rationale.html"><img src="../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h2 class="title" style="clear: both">
|
||||||
|
<a name="asio.overview"></a><a class="link" href="overview.html" title="Overview">Overview</a>
|
||||||
|
</h2></div></div></div>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/rationale.html" title="Rationale">Rationale</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core.html" title="Core Concepts and Functionality">Core Concepts and Functionality</a>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="circle">
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/basics.html" title="Basic Asio Anatomy">Basic Asio Anatomy</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/async.html" title="The Proactor Design Pattern: Concurrency Without Threads">The Proactor Design Pattern:
|
||||||
|
Concurrency Without Threads</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/threads.html" title="Threads and Asio">Threads and Asio</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/strands.html" title="Strands: Use Threads Without Explicit Locking">Strands: Use Threads Without
|
||||||
|
Explicit Locking</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/buffers.html" title="Buffers">Buffers</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/streams.html" title="Streams, Short Reads and Short Writes">Streams, Short Reads and
|
||||||
|
Short Writes</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/reactor.html" title="Reactor-Style Operations">Reactor-Style Operations</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/line_based.html" title="Line-Based Operations">Line-Based Operations</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/allocation.html" title="Custom Memory Allocation">Custom Memory Allocation</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/handler_tracking.html" title="Handler Tracking">Handler Tracking</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/concurrency_hint.html" title="Concurrency Hints">Concurrency Hints</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/coroutine.html" title="Stackless Coroutines">Stackless Coroutines</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/spawn.html" title="Stackful Coroutines">Stackful Coroutines</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/core/coroutines_ts.html" title="Coroutines TS Support (experimental)">Coroutines TS Support
|
||||||
|
(experimental)</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/networking.html" title="Networking">Networking</a>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="circle">
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/networking/protocols.html" title="TCP, UDP and ICMP">TCP, UDP and ICMP</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/networking/other_protocols.html" title="Support for Other Protocols">Support
|
||||||
|
for Other Protocols</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/networking/iostreams.html" title="Socket Iostreams">Socket Iostreams</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/networking/bsd_sockets.html" title="The BSD Socket API and Asio">The BSD Socket
|
||||||
|
API and Asio</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/timers.html" title="Timers">Timers</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/serial_ports.html" title="Serial Ports">Serial Ports</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/signals.html" title="Signal Handling">Signal Handling</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/posix.html" title="POSIX-Specific Functionality">POSIX-Specific Functionality</a>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="circle">
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/posix/local.html" title="UNIX Domain Sockets">UNIX Domain Sockets</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/posix/stream_descriptor.html" title="Stream-Oriented File Descriptors">Stream-Oriented
|
||||||
|
File Descriptors</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/windows.html" title="Windows-Specific Functionality">Windows-Specific Functionality</a>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="circle">
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/windows/stream_handle.html" title="Stream-Oriented HANDLEs">Stream-Oriented
|
||||||
|
HANDLEs</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/windows/random_access_handle.html" title="Random-Access HANDLEs">Random-Access
|
||||||
|
HANDLEs</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/ssl.html" title="SSL">SSL</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/cpp2011.html" title="C++ 2011 Support">C++ 2011 Support</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="overview/implementation.html" title="Platform-Specific Implementation Notes">Platform-Specific Implementation
|
||||||
|
Notes</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="../index.html"><img src="../prev.png" alt="Prev"></a><a accesskey="u" href="../index.html"><img src="../up.png" alt="Up"></a><a accesskey="h" href="../index.html"><img src="../home.png" alt="Home"></a><a accesskey="n" href="overview/rationale.html"><img src="../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
84
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core.html
vendored
Normal file
84
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core.html
vendored
Normal file
@@ -0,0 +1,84 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Core Concepts and Functionality</title>
|
||||||
|
<link rel="stylesheet" href="../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../overview.html" title="Overview">
|
||||||
|
<link rel="prev" href="rationale.html" title="Rationale">
|
||||||
|
<link rel="next" href="core/basics.html" title="Basic Asio Anatomy">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="rationale.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../overview.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="core/basics.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h3 class="title">
|
||||||
|
<a name="asio.overview.core"></a><a class="link" href="core.html" title="Core Concepts and Functionality">Core Concepts and Functionality</a>
|
||||||
|
</h3></div></div></div>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/basics.html" title="Basic Asio Anatomy">Basic Asio Anatomy</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/async.html" title="The Proactor Design Pattern: Concurrency Without Threads">The Proactor Design Pattern:
|
||||||
|
Concurrency Without Threads</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/threads.html" title="Threads and Asio">Threads and Asio</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/strands.html" title="Strands: Use Threads Without Explicit Locking">Strands: Use Threads Without
|
||||||
|
Explicit Locking</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/buffers.html" title="Buffers">Buffers</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/streams.html" title="Streams, Short Reads and Short Writes">Streams, Short Reads and Short
|
||||||
|
Writes</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/reactor.html" title="Reactor-Style Operations">Reactor-Style Operations</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/line_based.html" title="Line-Based Operations">Line-Based Operations</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/allocation.html" title="Custom Memory Allocation">Custom Memory Allocation</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/handler_tracking.html" title="Handler Tracking">Handler Tracking</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/concurrency_hint.html" title="Concurrency Hints">Concurrency Hints</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/coroutine.html" title="Stackless Coroutines">Stackless Coroutines</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/spawn.html" title="Stackful Coroutines">Stackful Coroutines</a>
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<a class="link" href="core/coroutines_ts.html" title="Coroutines TS Support (experimental)">Coroutines TS Support
|
||||||
|
(experimental)</a>
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="rationale.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../overview.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="core/basics.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
135
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/allocation.html
vendored
Normal file
135
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/allocation.html
vendored
Normal file
@@ -0,0 +1,135 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Custom Memory Allocation</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="line_based.html" title="Line-Based Operations">
|
||||||
|
<link rel="next" href="handler_tracking.html" title="Handler Tracking">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="line_based.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="handler_tracking.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.allocation"></a><a class="link" href="allocation.html" title="Custom Memory Allocation">Custom Memory Allocation</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Many asynchronous operations need to allocate an object to store state
|
||||||
|
associated with the operation. For example, a Win32 implementation needs
|
||||||
|
<code class="computeroutput"><span class="identifier">OVERLAPPED</span></code>-derived objects
|
||||||
|
to pass to Win32 API functions.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Furthermore, programs typically contain easily identifiable chains of asynchronous
|
||||||
|
operations. A half duplex protocol implementation (e.g. an HTTP server)
|
||||||
|
would have a single chain of operations per client (receives followed by
|
||||||
|
sends). A full duplex protocol implementation would have two chains executing
|
||||||
|
in parallel. Programs should be able to leverage this knowledge to reuse
|
||||||
|
memory for all asynchronous operations in a chain.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Given a copy of a user-defined <code class="computeroutput"><span class="identifier">Handler</span></code>
|
||||||
|
object <code class="computeroutput"><span class="identifier">h</span></code>, if the implementation
|
||||||
|
needs to allocate memory associated with that handler it will obtain an
|
||||||
|
allocator using the <code class="computeroutput"><span class="identifier">get_associated_allocator</span></code>
|
||||||
|
function. For example:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">associated_allocator_t</span><span class="special"><</span><span class="identifier">Handler</span><span class="special">></span> <span class="identifier">a</span> <span class="special">=</span> <span class="identifier">asio</span><span class="special">::</span><span class="identifier">get_associated_allocator</span><span class="special">(</span><span class="identifier">h</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The associated allocator must satisfy the standard Allocator requirements.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
By default, handlers use the standard allocator (which is implemented in
|
||||||
|
terms of <code class="computeroutput"><span class="special">::</span><span class="keyword">operator</span>
|
||||||
|
<span class="keyword">new</span><span class="special">()</span></code>
|
||||||
|
and <code class="computeroutput"><span class="special">::</span><span class="keyword">operator</span>
|
||||||
|
<span class="keyword">delete</span><span class="special">()</span></code>).
|
||||||
|
The allocator may be customised for a particular handler type by specifying
|
||||||
|
a nested type <code class="computeroutput"><span class="identifier">allocator_type</span></code>
|
||||||
|
and member function <code class="computeroutput"><span class="identifier">get_allocator</span><span class="special">()</span></code>:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">class</span> <span class="identifier">my_handler</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">public</span><span class="special">:</span>
|
||||||
|
<span class="comment">// Custom implementation of Allocator type requirements.</span>
|
||||||
|
<span class="keyword">typedef</span> <span class="identifier">my_allocator</span> <span class="identifier">allocator_type</span><span class="special">;</span>
|
||||||
|
|
||||||
|
<span class="comment">// Return a custom allocator implementation.</span>
|
||||||
|
<span class="identifier">allocator_type</span> <span class="identifier">get_allocator</span><span class="special">()</span> <span class="keyword">const</span> <span class="keyword">noexcept</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">return</span> <span class="identifier">my_allocator</span><span class="special">();</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
|
||||||
|
<span class="keyword">void</span> <span class="keyword">operator</span><span class="special">()()</span> <span class="special">{</span> <span class="special">...</span> <span class="special">}</span>
|
||||||
|
<span class="special">};</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
In more complex cases, the <code class="computeroutput"><span class="identifier">associated_allocator</span></code>
|
||||||
|
template may be partially specialised directly:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">namespace</span> <span class="identifier">asio</span> <span class="special">{</span>
|
||||||
|
|
||||||
|
<span class="keyword">template</span> <span class="special"><</span><span class="keyword">typename</span> <span class="identifier">Allocator</span><span class="special">></span>
|
||||||
|
<span class="keyword">struct</span> <span class="identifier">associated_allocator</span><span class="special"><</span><span class="identifier">my_handler</span><span class="special">,</span> <span class="identifier">Allocator</span><span class="special">></span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="comment">// Custom implementation of Allocator type requirements.</span>
|
||||||
|
<span class="keyword">typedef</span> <span class="identifier">my_allocator</span> <span class="identifier">type</span><span class="special">;</span>
|
||||||
|
|
||||||
|
<span class="comment">// Return a custom allocator implementation.</span>
|
||||||
|
<span class="keyword">static</span> <span class="identifier">type</span> <span class="identifier">get</span><span class="special">(</span><span class="keyword">const</span> <span class="identifier">my_handler</span><span class="special">&,</span>
|
||||||
|
<span class="keyword">const</span> <span class="identifier">Allocator</span><span class="special">&</span> <span class="identifier">a</span> <span class="special">=</span> <span class="identifier">Allocator</span><span class="special">())</span> <span class="keyword">noexcept</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">return</span> <span class="identifier">my_allocator</span><span class="special">();</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
<span class="special">};</span>
|
||||||
|
|
||||||
|
<span class="special">}</span> <span class="comment">// namespace asio</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The implementation guarantees that the deallocation will occur before the
|
||||||
|
associated handler is invoked, which means the memory is ready to be reused
|
||||||
|
for any new asynchronous operations started by the handler.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The custom memory allocation functions may be called from any user-created
|
||||||
|
thread that is calling a library function. The implementation guarantees
|
||||||
|
that, for the asynchronous operations included the library, the implementation
|
||||||
|
will not make concurrent calls to the memory allocation functions for that
|
||||||
|
handler. The implementation will insert appropriate memory barriers to
|
||||||
|
ensure correct memory visibility should allocation functions need to be
|
||||||
|
called from different threads.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.allocation.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.allocation.see_also"></a></span><a class="link" href="allocation.html#asio.overview.core.allocation.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/associated_allocator.html" title="associated_allocator">associated_allocator</a>,
|
||||||
|
<a class="link" href="../../reference/get_associated_allocator.html" title="get_associated_allocator">get_associated_allocator</a>,
|
||||||
|
<a class="link" href="../../examples/cpp03_examples.html#asio.examples.cpp03_examples.allocation">custom memory allocation
|
||||||
|
example (C++03)</a>, <a class="link" href="../../examples/cpp11_examples.html#asio.examples.cpp11_examples.allocation">custom
|
||||||
|
memory allocation example (C++11)</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="line_based.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="handler_tracking.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
279
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/async.html
vendored
Normal file
279
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/async.html
vendored
Normal file
@@ -0,0 +1,279 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>The Proactor Design Pattern: Concurrency Without Threads</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="basics.html" title="Basic Asio Anatomy">
|
||||||
|
<link rel="next" href="threads.html" title="Threads and Asio">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="basics.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="threads.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.async"></a><a class="link" href="async.html" title="The Proactor Design Pattern: Concurrency Without Threads">The Proactor Design Pattern:
|
||||||
|
Concurrency Without Threads</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
The Asio library offers side-by-side support for synchronous and asynchronous
|
||||||
|
operations. The asynchronous support is based on the Proactor design pattern
|
||||||
|
<a class="link" href="async.html#asio.overview.core.async.references">[POSA2]</a>. The
|
||||||
|
advantages and disadvantages of this approach, when compared to a synchronous-only
|
||||||
|
or Reactor approach, are outlined below.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.async.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.async.proactor_and_asio"></a></span><a class="link" href="async.html#asio.overview.core.async.proactor_and_asio">Proactor
|
||||||
|
and Asio</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
Let us examine how the Proactor design pattern is implemented in Asio,
|
||||||
|
without reference to platform-specific details.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<span class="inlinemediaobject"><img src="../../../proactor.png" alt="proactor"></span>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<span class="bold"><strong>Proactor design pattern (adapted from [POSA2])</strong></span>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
— Asynchronous Operation
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Defines an operation that is executed asynchronously, such as an asynchronous
|
||||||
|
read or write on a socket.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Asynchronous Operation Processor
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Executes asynchronous operations and queues events on a completion event
|
||||||
|
queue when operations complete. From a high-level point of view, internal
|
||||||
|
services like <code class="computeroutput"><span class="identifier">reactive_socket_service</span></code>
|
||||||
|
are asynchronous operation processors.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Completion Event Queue
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Buffers completion events until they are dequeued by an asynchronous
|
||||||
|
event demultiplexer.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Completion Handler
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Processes the result of an asynchronous operation. These are function
|
||||||
|
objects, often created using <code class="computeroutput"><span class="identifier">boost</span><span class="special">::</span><span class="identifier">bind</span></code>.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Asynchronous Event Demultiplexer
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Blocks waiting for events to occur on the completion event queue, and
|
||||||
|
returns a completed event to its caller.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Proactor
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Calls the asynchronous event demultiplexer to dequeue events, and dispatches
|
||||||
|
the completion handler (i.e. invokes the function object) associated
|
||||||
|
with the event. This abstraction is represented by the <code class="computeroutput"><span class="identifier">io_context</span></code> class.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Initiator
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Application-specific code that starts asynchronous operations. The initiator
|
||||||
|
interacts with an asynchronous operation processor via a high-level interface
|
||||||
|
such as <code class="computeroutput"><span class="identifier">basic_stream_socket</span></code>,
|
||||||
|
which in turn delegates to a service like <code class="computeroutput"><span class="identifier">reactive_socket_service</span></code>.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.async.h1"></a>
|
||||||
|
<span><a name="asio.overview.core.async.implementation_using_reactor"></a></span><a class="link" href="async.html#asio.overview.core.async.implementation_using_reactor">Implementation
|
||||||
|
Using Reactor</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
On many platforms, Asio implements the Proactor design pattern in terms
|
||||||
|
of a Reactor, such as <code class="computeroutput"><span class="identifier">select</span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">epoll</span></code> or <code class="computeroutput"><span class="identifier">kqueue</span></code>. This implementation approach
|
||||||
|
corresponds to the Proactor design pattern as follows:
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
— Asynchronous Operation Processor
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
A reactor implemented using <code class="computeroutput"><span class="identifier">select</span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">epoll</span></code> or <code class="computeroutput"><span class="identifier">kqueue</span></code>. When the reactor indicates
|
||||||
|
that the resource is ready to perform the operation, the processor executes
|
||||||
|
the asynchronous operation and enqueues the associated completion handler
|
||||||
|
on the completion event queue.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Completion Event Queue
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
A linked list of completion handlers (i.e. function objects).
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Asynchronous Event Demultiplexer
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
This is implemented by waiting on an event or condition variable until
|
||||||
|
a completion handler is available in the completion event queue.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.async.h2"></a>
|
||||||
|
<span><a name="asio.overview.core.async.implementation_using_windows_overlapped_i_o"></a></span><a class="link" href="async.html#asio.overview.core.async.implementation_using_windows_overlapped_i_o">Implementation
|
||||||
|
Using Windows Overlapped I/O</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
On Windows NT, 2000 and XP, Asio takes advantage of overlapped I/O to provide
|
||||||
|
an efficient implementation of the Proactor design pattern. This implementation
|
||||||
|
approach corresponds to the Proactor design pattern as follows:
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
— Asynchronous Operation Processor
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
This is implemented by the operating system. Operations are initiated
|
||||||
|
by calling an overlapped function such as <code class="computeroutput"><span class="identifier">AcceptEx</span></code>.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Completion Event Queue
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
This is implemented by the operating system, and is associated with an
|
||||||
|
I/O completion port. There is one I/O completion port for each <code class="computeroutput"><span class="identifier">io_context</span></code> instance.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Asynchronous Event Demultiplexer
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Called by Asio to dequeue events and their associated completion handlers.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.async.h3"></a>
|
||||||
|
<span><a name="asio.overview.core.async.advantages"></a></span><a class="link" href="async.html#asio.overview.core.async.advantages">Advantages</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
— Portability.
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Many operating systems offer a native asynchronous I/O API (such as overlapped
|
||||||
|
I/O on <span class="emphasis"><em>Windows</em></span>) as the preferred option for developing
|
||||||
|
high performance network applications. The library may be implemented
|
||||||
|
in terms of native asynchronous I/O. However, if native support is not
|
||||||
|
available, the library may also be implemented using synchronous event
|
||||||
|
demultiplexors that typify the Reactor pattern, such as <span class="emphasis"><em>POSIX</em></span>
|
||||||
|
<code class="computeroutput"><span class="identifier">select</span><span class="special">()</span></code>.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Decoupling threading from concurrency.
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Long-duration operations are performed asynchronously by the implementation
|
||||||
|
on behalf of the application. Consequently applications do not need to
|
||||||
|
spawn many threads in order to increase concurrency.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Performance and scalability.
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Implementation strategies such as thread-per-connection (which a synchronous-only
|
||||||
|
approach would require) can degrade system performance, due to increased
|
||||||
|
context switching, synchronisation and data movement among CPUs. With
|
||||||
|
asynchronous operations it is possible to avoid the cost of context switching
|
||||||
|
by minimising the number of operating system threads — typically a limited
|
||||||
|
resource — and only activating the logical threads of control that have
|
||||||
|
events to process.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Simplified application synchronisation.
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Asynchronous operation completion handlers can be written as though they
|
||||||
|
exist in a single-threaded environment, and so application logic can
|
||||||
|
be developed with little or no concern for synchronisation issues.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Function composition.
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Function composition refers to the implementation of functions to provide
|
||||||
|
a higher-level operation, such as sending a message in a particular format.
|
||||||
|
Each function is implemented in terms of multiple calls to lower-level
|
||||||
|
read or write operations.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
For example, consider a protocol where each message consists of a fixed-length
|
||||||
|
header followed by a variable length body, where the length of the body
|
||||||
|
is specified in the header. A hypothetical read_message operation could
|
||||||
|
be implemented using two lower-level reads, the first to receive the
|
||||||
|
header and, once the length is known, the second to receive the body.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
To compose functions in an asynchronous model, asynchronous operations
|
||||||
|
can be chained together. That is, a completion handler for one operation
|
||||||
|
can initiate the next. Starting the first call in the chain can be encapsulated
|
||||||
|
so that the caller need not be aware that the higher-level operation
|
||||||
|
is implemented as a chain of asynchronous operations.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
The ability to compose new operations in this way simplifies the development
|
||||||
|
of higher levels of abstraction above a networking library, such as functions
|
||||||
|
to support a specific protocol.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.async.h4"></a>
|
||||||
|
<span><a name="asio.overview.core.async.disadvantages"></a></span><a class="link" href="async.html#asio.overview.core.async.disadvantages">Disadvantages</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
— Program complexity.
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
It is more difficult to develop applications using asynchronous mechanisms
|
||||||
|
due to the separation in time and space between operation initiation
|
||||||
|
and completion. Applications may also be harder to debug due to the inverted
|
||||||
|
flow of control.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<p>
|
||||||
|
— Memory usage.
|
||||||
|
</p>
|
||||||
|
<div class="blockquote"><blockquote class="blockquote"><p>
|
||||||
|
Buffer space must be committed for the duration of a read or write operation,
|
||||||
|
which may continue indefinitely, and a separate buffer is required for
|
||||||
|
each concurrent operation. The Reactor pattern, on the other hand, does
|
||||||
|
not require buffer space until a socket is ready for reading or writing.
|
||||||
|
</p></blockquote></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.async.h5"></a>
|
||||||
|
<span><a name="asio.overview.core.async.references"></a></span><a class="link" href="async.html#asio.overview.core.async.references">References</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
[POSA2] D. Schmidt et al, <span class="emphasis"><em>Pattern Oriented Software Architecture,
|
||||||
|
Volume 2</em></span>. Wiley, 2000.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="basics.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="threads.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
166
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/basics.html
vendored
Normal file
166
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/basics.html
vendored
Normal file
@@ -0,0 +1,166 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Basic Asio Anatomy</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="next" href="async.html" title="The Proactor Design Pattern: Concurrency Without Threads">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="../core.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="async.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.basics"></a><a class="link" href="basics.html" title="Basic Asio Anatomy">Basic Asio Anatomy</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Asio may be used to perform both synchronous and asynchronous operations
|
||||||
|
on I/O objects such as sockets. Before using Asio it may be useful to get
|
||||||
|
a conceptual picture of the various parts of Asio, your program, and how
|
||||||
|
they work together.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
As an introductory example, let's consider what happens when you perform
|
||||||
|
a connect operation on a socket. We shall start by examining synchronous
|
||||||
|
operations.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<span class="inlinemediaobject"><img src="../../../sync_op.png" alt="sync_op"></span>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<span class="bold"><strong>Your program</strong></span> will have at least one <span class="bold"><strong>io_context</strong></span> object. The <span class="bold"><strong>io_context</strong></span>
|
||||||
|
represents <span class="bold"><strong>your program</strong></span>'s link to the
|
||||||
|
<span class="bold"><strong>operating system</strong></span>'s I/O services.
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">io_context</span> <span class="identifier">io_context</span><span class="special">;</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
To perform I/O operations <span class="bold"><strong>your program</strong></span>
|
||||||
|
will need an <span class="bold"><strong>I/O object</strong></span> such as a TCP
|
||||||
|
socket:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">ip</span><span class="special">::</span><span class="identifier">tcp</span><span class="special">::</span><span class="identifier">socket</span> <span class="identifier">socket</span><span class="special">(</span><span class="identifier">io_context</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
When a synchronous connect operation is performed, the following sequence
|
||||||
|
of events occurs:
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
1. <span class="bold"><strong>Your program</strong></span> initiates the connect
|
||||||
|
operation by calling the <span class="bold"><strong>I/O object</strong></span>:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">socket</span><span class="special">.</span><span class="identifier">connect</span><span class="special">(</span><span class="identifier">server_endpoint</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
2. The <span class="bold"><strong>I/O object</strong></span> forwards the request
|
||||||
|
to the <span class="bold"><strong>io_context</strong></span>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
3. The <span class="bold"><strong>io_context</strong></span> calls on the <span class="bold"><strong>operating system</strong></span> to perform the connect operation.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
4. The <span class="bold"><strong>operating system</strong></span> returns the result
|
||||||
|
of the operation to the <span class="bold"><strong>io_context</strong></span>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
5. The <span class="bold"><strong>io_context</strong></span> translates any error
|
||||||
|
resulting from the operation into an object of type <code class="computeroutput"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">error_code</span></code>.
|
||||||
|
An <code class="computeroutput"><span class="identifier">error_code</span></code> may be compared
|
||||||
|
with specific values, or tested as a boolean (where a <code class="computeroutput"><span class="keyword">false</span></code>
|
||||||
|
result means that no error occurred). The result is then forwarded back
|
||||||
|
up to the <span class="bold"><strong>I/O object</strong></span>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
6. The <span class="bold"><strong>I/O object</strong></span> throws an exception
|
||||||
|
of type <code class="computeroutput"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">system_error</span></code> if the operation failed.
|
||||||
|
If the code to initiate the operation had instead been written as:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">error_code</span> <span class="identifier">ec</span><span class="special">;</span>
|
||||||
|
<span class="identifier">socket</span><span class="special">.</span><span class="identifier">connect</span><span class="special">(</span><span class="identifier">server_endpoint</span><span class="special">,</span> <span class="identifier">ec</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
then the <code class="computeroutput"><span class="identifier">error_code</span></code> variable
|
||||||
|
<code class="computeroutput"><span class="identifier">ec</span></code> would be set to the
|
||||||
|
result of the operation, and no exception would be thrown.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
When an asynchronous operation is used, a different sequence of events
|
||||||
|
occurs.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<span class="inlinemediaobject"><img src="../../../async_op1.png" alt="async_op1"></span>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
1. <span class="bold"><strong>Your program</strong></span> initiates the connect
|
||||||
|
operation by calling the <span class="bold"><strong>I/O object</strong></span>:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">socket</span><span class="special">.</span><span class="identifier">async_connect</span><span class="special">(</span><span class="identifier">server_endpoint</span><span class="special">,</span> <span class="identifier">your_completion_handler</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
where <code class="computeroutput"><span class="identifier">your_completion_handler</span></code>
|
||||||
|
is a function or function object with the signature:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">void</span> <span class="identifier">your_completion_handler</span><span class="special">(</span><span class="keyword">const</span> <span class="identifier">asio</span><span class="special">::</span><span class="identifier">error_code</span><span class="special">&</span> <span class="identifier">ec</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The exact signature required depends on the asynchronous operation being
|
||||||
|
performed. The reference documentation indicates the appropriate form for
|
||||||
|
each operation.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
2. The <span class="bold"><strong>I/O object</strong></span> forwards the request
|
||||||
|
to the <span class="bold"><strong>io_context</strong></span>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
3. The <span class="bold"><strong>io_context</strong></span> signals to the <span class="bold"><strong>operating system</strong></span> that it should start an asynchronous
|
||||||
|
connect.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Time passes. (In the synchronous case this wait would have been contained
|
||||||
|
entirely within the duration of the connect operation.)
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<span class="inlinemediaobject"><img src="../../../async_op2.png" alt="async_op2"></span>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
4. The <span class="bold"><strong>operating system</strong></span> indicates that
|
||||||
|
the connect operation has completed by placing the result on a queue, ready
|
||||||
|
to be picked up by the <span class="bold"><strong>io_context</strong></span>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
5. <span class="bold"><strong>Your program</strong></span> must make a call to <code class="computeroutput"><span class="identifier">io_context</span><span class="special">::</span><span class="identifier">run</span><span class="special">()</span></code>
|
||||||
|
(or to one of the similar <span class="bold"><strong>io_context</strong></span> member
|
||||||
|
functions) in order for the result to be retrieved. A call to <code class="computeroutput"><span class="identifier">io_context</span><span class="special">::</span><span class="identifier">run</span><span class="special">()</span></code>
|
||||||
|
blocks while there are unfinished asynchronous operations, so you would
|
||||||
|
typically call it as soon as you have started your first asynchronous operation.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
6. While inside the call to <code class="computeroutput"><span class="identifier">io_context</span><span class="special">::</span><span class="identifier">run</span><span class="special">()</span></code>, the <span class="bold"><strong>io_context</strong></span>
|
||||||
|
dequeues the result of the operation, translates it into an <code class="computeroutput"><span class="identifier">error_code</span></code>, and then passes it to <span class="bold"><strong>your completion handler</strong></span>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
This is a simplified picture of how Asio operates. You will want to delve
|
||||||
|
further into the documentation if your needs are more advanced, such as
|
||||||
|
extending Asio to perform other types of asynchronous operations.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="../core.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="async.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
234
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/buffers.html
vendored
Normal file
234
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/buffers.html
vendored
Normal file
@@ -0,0 +1,234 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Buffers</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="strands.html" title="Strands: Use Threads Without Explicit Locking">
|
||||||
|
<link rel="next" href="streams.html" title="Streams, Short Reads and Short Writes">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="strands.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="streams.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.buffers"></a><a class="link" href="buffers.html" title="Buffers">Buffers</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Fundamentally, I/O involves the transfer of data to and from contiguous
|
||||||
|
regions of memory, called buffers. These buffers can be simply expressed
|
||||||
|
as a tuple consisting of a pointer and a size in bytes. However, to allow
|
||||||
|
the development of efficient network applications, Asio includes support
|
||||||
|
for scatter-gather operations. These operations involve one or more buffers:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
A scatter-read receives data into multiple buffers.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
A gather-write transmits multiple buffers.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
Therefore we require an abstraction to represent a collection of buffers.
|
||||||
|
The approach used in Asio is to define a type (actually two types) to represent
|
||||||
|
a single buffer. These can be stored in a container, which may be passed
|
||||||
|
to the scatter-gather operations.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
In addition to specifying buffers as a pointer and size in bytes, Asio
|
||||||
|
makes a distinction between modifiable memory (called mutable) and non-modifiable
|
||||||
|
memory (where the latter is created from the storage for a const-qualified
|
||||||
|
variable). These two types could therefore be defined as follows:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">typedef</span> <span class="identifier">std</span><span class="special">::</span><span class="identifier">pair</span><span class="special"><</span><span class="keyword">void</span><span class="special">*,</span> <span class="identifier">std</span><span class="special">::</span><span class="identifier">size_t</span><span class="special">></span> <span class="identifier">mutable_buffer</span><span class="special">;</span>
|
||||||
|
<span class="keyword">typedef</span> <span class="identifier">std</span><span class="special">::</span><span class="identifier">pair</span><span class="special"><</span><span class="keyword">const</span> <span class="keyword">void</span><span class="special">*,</span> <span class="identifier">std</span><span class="special">::</span><span class="identifier">size_t</span><span class="special">></span> <span class="identifier">const_buffer</span><span class="special">;</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
Here, a mutable_buffer would be convertible to a const_buffer, but conversion
|
||||||
|
in the opposite direction is not valid.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
However, Asio does not use the above definitions as-is, but instead defines
|
||||||
|
two classes: <code class="computeroutput"><span class="identifier">mutable_buffer</span></code>
|
||||||
|
and <code class="computeroutput"><span class="identifier">const_buffer</span></code>. The goal
|
||||||
|
of these is to provide an opaque representation of contiguous memory, where:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
Types behave as std::pair would in conversions. That is, a <code class="computeroutput"><span class="identifier">mutable_buffer</span></code> is convertible to
|
||||||
|
a <code class="computeroutput"><span class="identifier">const_buffer</span></code>, but
|
||||||
|
the opposite conversion is disallowed.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
There is protection against buffer overruns. Given a buffer instance,
|
||||||
|
a user can only create another buffer representing the same range of
|
||||||
|
memory or a sub-range of it. To provide further safety, the library
|
||||||
|
also includes mechanisms for automatically determining the size of
|
||||||
|
a buffer from an array, <code class="computeroutput"><span class="identifier">boost</span><span class="special">::</span><span class="identifier">array</span></code>
|
||||||
|
or <code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">vector</span></code> of POD elements, or from a
|
||||||
|
<code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">string</span></code>.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
The underlying memory is explicitly accessed using the <code class="computeroutput"><span class="identifier">data</span><span class="special">()</span></code>
|
||||||
|
member function. In general an application should never need to do
|
||||||
|
this, but it is required by the library implementation to pass the
|
||||||
|
raw memory to the underlying operating system functions.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
Finally, multiple buffers can be passed to scatter-gather operations (such
|
||||||
|
as <a class="link" href="../../reference/read.html" title="read">read()</a> or <a class="link" href="../../reference/write.html" title="write">write()</a>)
|
||||||
|
by putting the buffer objects into a container. The <code class="computeroutput"><span class="identifier">MutableBufferSequence</span></code>
|
||||||
|
and <code class="computeroutput"><span class="identifier">ConstBufferSequence</span></code>
|
||||||
|
concepts have been defined so that containers such as <code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">vector</span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">list</span></code>, <code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">vector</span></code>
|
||||||
|
or <code class="computeroutput"><span class="identifier">boost</span><span class="special">::</span><span class="identifier">array</span></code> can be used.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.buffers.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.buffers.streambuf_for_integration_with_iostreams"></a></span><a class="link" href="buffers.html#asio.overview.core.buffers.streambuf_for_integration_with_iostreams">Streambuf
|
||||||
|
for Integration with Iostreams</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
The class <code class="computeroutput"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">basic_streambuf</span></code> is derived from <code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">basic_streambuf</span></code> to associate the input
|
||||||
|
sequence and output sequence with one or more objects of some character
|
||||||
|
array type, whose elements store arbitrary values. These character array
|
||||||
|
objects are internal to the streambuf object, but direct access to the
|
||||||
|
array elements is provided to permit them to be used with I/O operations,
|
||||||
|
such as the send or receive operations of a socket:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
The input sequence of the streambuf is accessible via the <a class="link" href="../../reference/basic_streambuf/data.html" title="basic_streambuf::data">data()</a>
|
||||||
|
member function. The return type of this function meets the <code class="computeroutput"><span class="identifier">ConstBufferSequence</span></code> requirements.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
The output sequence of the streambuf is accessible via the <a class="link" href="../../reference/basic_streambuf/prepare.html" title="basic_streambuf::prepare">prepare()</a>
|
||||||
|
member function. The return type of this function meets the <code class="computeroutput"><span class="identifier">MutableBufferSequence</span></code> requirements.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
Data is transferred from the front of the output sequence to the back
|
||||||
|
of the input sequence by calling the <a class="link" href="../../reference/basic_streambuf/commit.html" title="basic_streambuf::commit">commit()</a>
|
||||||
|
member function.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
Data is removed from the front of the input sequence by calling the
|
||||||
|
<a class="link" href="../../reference/basic_streambuf/consume.html" title="basic_streambuf::consume">consume()</a>
|
||||||
|
member function.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
The streambuf constructor accepts a <code class="computeroutput"><span class="identifier">size_t</span></code>
|
||||||
|
argument specifying the maximum of the sum of the sizes of the input sequence
|
||||||
|
and output sequence. Any operation that would, if successful, grow the
|
||||||
|
internal data beyond this limit will throw a <code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">length_error</span></code>
|
||||||
|
exception.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.buffers.h1"></a>
|
||||||
|
<span><a name="asio.overview.core.buffers.bytewise_traversal_of_buffer_sequences"></a></span><a class="link" href="buffers.html#asio.overview.core.buffers.bytewise_traversal_of_buffer_sequences">Bytewise
|
||||||
|
Traversal of Buffer Sequences</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput"><span class="identifier">buffers_iterator</span><span class="special"><></span></code>
|
||||||
|
class template allows buffer sequences (i.e. types meeting <code class="computeroutput"><span class="identifier">MutableBufferSequence</span></code> or <code class="computeroutput"><span class="identifier">ConstBufferSequence</span></code> requirements) to
|
||||||
|
be traversed as though they were a contiguous sequence of bytes. Helper
|
||||||
|
functions called buffers_begin() and buffers_end() are also provided, where
|
||||||
|
the buffers_iterator<> template parameter is automatically deduced.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
As an example, to read a single line from a socket and into a <code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">string</span></code>, you may write:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">streambuf</span> <span class="identifier">sb</span><span class="special">;</span>
|
||||||
|
<span class="special">...</span>
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">size_t</span> <span class="identifier">n</span> <span class="special">=</span> <span class="identifier">asio</span><span class="special">::</span><span class="identifier">read_until</span><span class="special">(</span><span class="identifier">sock</span><span class="special">,</span> <span class="identifier">sb</span><span class="special">,</span> <span class="char">'\n'</span><span class="special">);</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">streambuf</span><span class="special">::</span><span class="identifier">const_buffers_type</span> <span class="identifier">bufs</span> <span class="special">=</span> <span class="identifier">sb</span><span class="special">.</span><span class="identifier">data</span><span class="special">();</span>
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">string</span> <span class="identifier">line</span><span class="special">(</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">buffers_begin</span><span class="special">(</span><span class="identifier">bufs</span><span class="special">),</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">buffers_begin</span><span class="special">(</span><span class="identifier">bufs</span><span class="special">)</span> <span class="special">+</span> <span class="identifier">n</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.buffers.h2"></a>
|
||||||
|
<span><a name="asio.overview.core.buffers.buffer_debugging"></a></span><a class="link" href="buffers.html#asio.overview.core.buffers.buffer_debugging">Buffer
|
||||||
|
Debugging</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
Some standard library implementations, such as the one that ships with
|
||||||
|
Microsoft Visual C++ 8.0 and later, provide a feature called iterator debugging.
|
||||||
|
What this means is that the validity of iterators is checked at runtime.
|
||||||
|
If a program tries to use an iterator that has been invalidated, an assertion
|
||||||
|
will be triggered. For example:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">std</span><span class="special">::</span><span class="identifier">vector</span><span class="special"><</span><span class="keyword">int</span><span class="special">></span> <span class="identifier">v</span><span class="special">(</span><span class="number">1</span><span class="special">)</span>
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">vector</span><span class="special"><</span><span class="keyword">int</span><span class="special">>::</span><span class="identifier">iterator</span> <span class="identifier">i</span> <span class="special">=</span> <span class="identifier">v</span><span class="special">.</span><span class="identifier">begin</span><span class="special">();</span>
|
||||||
|
<span class="identifier">v</span><span class="special">.</span><span class="identifier">clear</span><span class="special">();</span> <span class="comment">// invalidates iterators</span>
|
||||||
|
<span class="special">*</span><span class="identifier">i</span> <span class="special">=</span> <span class="number">0</span><span class="special">;</span> <span class="comment">// assertion!</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
Asio takes advantage of this feature to add buffer debugging. Consider
|
||||||
|
the following code:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">void</span> <span class="identifier">dont_do_this</span><span class="special">()</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">string</span> <span class="identifier">msg</span> <span class="special">=</span> <span class="string">"Hello, world!"</span><span class="special">;</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">async_write</span><span class="special">(</span><span class="identifier">sock</span><span class="special">,</span> <span class="identifier">asio</span><span class="special">::</span><span class="identifier">buffer</span><span class="special">(</span><span class="identifier">msg</span><span class="special">),</span> <span class="identifier">my_handler</span><span class="special">);</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
When you call an asynchronous read or write you need to ensure that the
|
||||||
|
buffers for the operation are valid until the completion handler is called.
|
||||||
|
In the above example, the buffer is the <code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">string</span></code>
|
||||||
|
variable <code class="computeroutput"><span class="identifier">msg</span></code>. This variable
|
||||||
|
is on the stack, and so it goes out of scope before the asynchronous operation
|
||||||
|
completes. If you're lucky then the application will crash, but random
|
||||||
|
failures are more likely.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
When buffer debugging is enabled, Asio stores an iterator into the string
|
||||||
|
until the asynchronous operation completes, and then dereferences it to
|
||||||
|
check its validity. In the above example you would observe an assertion
|
||||||
|
failure just before Asio tries to call the completion handler.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
This feature is automatically made available for Microsoft Visual Studio
|
||||||
|
8.0 or later and for GCC when <code class="computeroutput"><span class="identifier">_GLIBCXX_DEBUG</span></code>
|
||||||
|
is defined. There is a performance cost to this checking, so buffer debugging
|
||||||
|
is only enabled in debug builds. For other compilers it may be enabled
|
||||||
|
by defining <code class="computeroutput"><span class="identifier">ASIO_ENABLE_BUFFER_DEBUGGING</span></code>.
|
||||||
|
It can also be explicitly disabled by defining <code class="computeroutput"><span class="identifier">ASIO_DISABLE_BUFFER_DEBUGGING</span></code>.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.buffers.h3"></a>
|
||||||
|
<span><a name="asio.overview.core.buffers.see_also"></a></span><a class="link" href="buffers.html#asio.overview.core.buffers.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/buffer.html" title="buffer">buffer</a>, <a class="link" href="../../reference/buffers_begin.html" title="buffers_begin">buffers_begin</a>,
|
||||||
|
<a class="link" href="../../reference/buffers_end.html" title="buffers_end">buffers_end</a>, <a class="link" href="../../reference/buffers_iterator.html" title="buffers_iterator">buffers_iterator</a>,
|
||||||
|
<a class="link" href="../../reference/const_buffer.html" title="const_buffer">const_buffer</a>, <a class="link" href="../../reference/const_buffers_1.html" title="const_buffers_1">const_buffers_1</a>, <a class="link" href="../../reference/mutable_buffer.html" title="mutable_buffer">mutable_buffer</a>, <a class="link" href="../../reference/mutable_buffers_1.html" title="mutable_buffers_1">mutable_buffers_1</a>,
|
||||||
|
<a class="link" href="../../reference/streambuf.html" title="streambuf">streambuf</a>, <a class="link" href="../../reference/ConstBufferSequence.html" title="Constant buffer sequence requirements">ConstBufferSequence</a>,
|
||||||
|
<a class="link" href="../../reference/MutableBufferSequence.html" title="Mutable buffer sequence requirements">MutableBufferSequence</a>,
|
||||||
|
<a class="link" href="../../examples/cpp03_examples.html#asio.examples.cpp03_examples.buffers">buffers example (C++03)</a>,
|
||||||
|
<a class="link" href="../../examples/cpp11_examples.html#asio.examples.cpp11_examples.buffers">buffers example (c++11)</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="strands.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="streams.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
167
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/concurrency_hint.html
vendored
Normal file
167
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/concurrency_hint.html
vendored
Normal file
@@ -0,0 +1,167 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Concurrency Hints</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="handler_tracking.html" title="Handler Tracking">
|
||||||
|
<link rel="next" href="coroutine.html" title="Stackless Coroutines">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="handler_tracking.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="coroutine.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.concurrency_hint"></a><a class="link" href="concurrency_hint.html" title="Concurrency Hints">Concurrency Hints</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
The <a class="link" href="../../reference/io_context/io_context.html" title="io_context::io_context"><code class="computeroutput"><span class="identifier">io_context</span></code> constructor</a> allows
|
||||||
|
programs to specify a concurrency hint. This is a suggestion to the <code class="computeroutput"><span class="identifier">io_context</span></code> implementation as to the number
|
||||||
|
of active threads that should be used for running completion handlers.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
When the Windows I/O completion port backend is in use, this value is passed
|
||||||
|
to <code class="literal">CreateIoCompletionPort</code>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
When a reactor-based backend is used, the implementation recognises the
|
||||||
|
following special concurrency hint values:
|
||||||
|
</p>
|
||||||
|
<div class="informaltable"><table class="table">
|
||||||
|
<colgroup>
|
||||||
|
<col>
|
||||||
|
<col>
|
||||||
|
</colgroup>
|
||||||
|
<thead><tr>
|
||||||
|
<th>
|
||||||
|
<p>
|
||||||
|
Value
|
||||||
|
</p>
|
||||||
|
</th>
|
||||||
|
<th>
|
||||||
|
<p>
|
||||||
|
Description
|
||||||
|
</p>
|
||||||
|
</th>
|
||||||
|
</tr></thead>
|
||||||
|
<tbody>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="number">1</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
The implementation assumes that the <code class="computeroutput"><span class="identifier">io_context</span></code>
|
||||||
|
will be run from a single thread, and applies several optimisations
|
||||||
|
based on this assumption.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
For example, when a handler is posted from within another handler,
|
||||||
|
the new handler is added to a fast thread-local queue (with the
|
||||||
|
consequence that the new handler is held back until the currently
|
||||||
|
executing handler finishes).
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_CONCURRENCY_HINT_UNSAFE</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
This special concurrency hint disables locking in both the scheduler
|
||||||
|
and reactor I/O. This hint has the following restrictions:
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
— Care must be taken to ensure that all operations on the <code class="computeroutput"><span class="identifier">io_context</span></code> and any of its associated
|
||||||
|
I/O objects (such as sockets and timers) occur in only one thread
|
||||||
|
at a time.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
— Asynchronous resolve operations fail with <code class="computeroutput"><span class="identifier">operation_not_supported</span></code>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
— If a <code class="computeroutput"><span class="identifier">signal_set</span></code>
|
||||||
|
is used with the <code class="computeroutput"><span class="identifier">io_context</span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">signal_set</span></code> objects
|
||||||
|
cannot be used with any other io_context in the program.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_CONCURRENCY_HINT_UNSAFE_IO</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
This special concurrency hint disables locking in the reactor
|
||||||
|
I/O. This hint has the following restrictions:
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
— Care must be taken to ensure that run functions on the <code class="computeroutput"><span class="identifier">io_context</span></code>, and all operations
|
||||||
|
on the context's associated I/O objects (such as sockets and
|
||||||
|
timers), occur in only one thread at a time.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_CONCURRENCY_HINT_SAFE</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
The default. The <code class="computeroutput"><span class="identifier">io_context</span></code>
|
||||||
|
provides full thread safety, and distinct I/O objects may be
|
||||||
|
used from any thread.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
</tbody>
|
||||||
|
</table></div>
|
||||||
|
<p>
|
||||||
|
The concurrency hint used by default-constructed <code class="computeroutput">io_context</code>
|
||||||
|
objects can be overridden at compile time by defining the <code class="computeroutput">ASIO_CONCURRENCY_HINT_DEFAULT</code>
|
||||||
|
macro. For example, specifying
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">-DASIO_CONCURRENCY_HINT_DEFAULT=1
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
on the compiler command line means that a concurrency hint of <code class="computeroutput">1</code>
|
||||||
|
is used for all default-constructed <code class="computeroutput">io_context</code> objects in
|
||||||
|
the program. Similarly, the concurrency hint used by <code class="computeroutput">io_context</code>
|
||||||
|
objects constructed with <code class="computeroutput">1</code> can be overridden by defining
|
||||||
|
<code class="computeroutput">ASIO_CONCURRENCY_HINT_1</code>. For example, passing
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">-DASIO_CONCURRENCY_HINT_1=ASIO_CONCURRENCY_HINT_UNSAFE
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
to the compiler will disable thread safety for all of these objects.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="handler_tracking.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="coroutine.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
83
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/coroutine.html
vendored
Normal file
83
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/coroutine.html
vendored
Normal file
@@ -0,0 +1,83 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Stackless Coroutines</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="concurrency_hint.html" title="Concurrency Hints">
|
||||||
|
<link rel="next" href="spawn.html" title="Stackful Coroutines">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="concurrency_hint.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="spawn.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.coroutine"></a><a class="link" href="coroutine.html" title="Stackless Coroutines">Stackless Coroutines</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
The <a class="link" href="../../reference/coroutine.html" title="coroutine"><code class="computeroutput">coroutine</code></a>
|
||||||
|
class provides support for stackless coroutines. Stackless coroutines enable
|
||||||
|
programs to implement asynchronous logic in a synchronous manner, with
|
||||||
|
minimal overhead, as shown in the following example:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">struct session : asio::coroutine
|
||||||
|
{
|
||||||
|
boost::shared_ptr<tcp::socket> socket_;
|
||||||
|
boost::shared_ptr<std::vector<char> > buffer_;
|
||||||
|
|
||||||
|
session(boost::shared_ptr<tcp::socket> socket)
|
||||||
|
: socket_(socket),
|
||||||
|
buffer_(new std::vector<char>(1024))
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void operator()(asio::error_code ec = asio::error_code(), std::size_t n = 0)
|
||||||
|
{
|
||||||
|
if (!ec) reenter (this)
|
||||||
|
{
|
||||||
|
for (;;)
|
||||||
|
{
|
||||||
|
yield socket_->async_read_some(asio::buffer(*buffer_), *this);
|
||||||
|
yield asio::async_write(*socket_, asio::buffer(*buffer_, n), *this);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput">coroutine</code> class is used in conjunction with the pseudo-keywords
|
||||||
|
<code class="computeroutput">reenter</code>, <code class="computeroutput">yield</code> and <code class="computeroutput">fork</code>. These are
|
||||||
|
preprocessor macros, and are implemented in terms of a <code class="computeroutput">switch</code>
|
||||||
|
statement using a technique similar to Duff's Device. The <a class="link" href="../../reference/coroutine.html" title="coroutine"><code class="computeroutput">coroutine</code></a>
|
||||||
|
class's documentation provides a complete description of these pseudo-keywords.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.coroutine.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.coroutine.see_also"></a></span><a class="link" href="coroutine.html#asio.overview.core.coroutine.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/coroutine.html" title="coroutine">coroutine</a>, <a class="link" href="../../examples/cpp03_examples.html#asio.examples.cpp03_examples.http_server_4">HTTP
|
||||||
|
Server 4 example</a>, <a class="link" href="spawn.html" title="Stackful Coroutines">Stackful
|
||||||
|
Coroutines</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="concurrency_hint.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="spawn.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
147
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/coroutines_ts.html
vendored
Normal file
147
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/coroutines_ts.html
vendored
Normal file
@@ -0,0 +1,147 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Coroutines TS Support (experimental)</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="spawn.html" title="Stackful Coroutines">
|
||||||
|
<link rel="next" href="../networking.html" title="Networking">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="spawn.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="../networking.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.coroutines_ts"></a><a class="link" href="coroutines_ts.html" title="Coroutines TS Support (experimental)">Coroutines TS Support
|
||||||
|
(experimental)</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
(Note: "Experimental" means that this interface is provided to
|
||||||
|
gather feedback and may change in subsequent Asio releases.)
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Experimental support for the Coroutines TS is provided via the <a class="link" href="../../reference/experimental__co_spawn.html" title="experimental::co_spawn"><code class="computeroutput">experimental::co_spawn()</code></a>
|
||||||
|
function. This <code class="computeroutput">co_spawn()</code> function enables programs to implement
|
||||||
|
asynchronous logic in a synchronous manner, in conjunction with the <code class="computeroutput">co_await</code>
|
||||||
|
keyword, as shown in the following example:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">asio::experimental::co_spawn(executor,
|
||||||
|
[socket = std::move(socket)]() mutable
|
||||||
|
{
|
||||||
|
return echo(std::move(socket));
|
||||||
|
},
|
||||||
|
asio::experimental::detached);
|
||||||
|
|
||||||
|
// ...
|
||||||
|
|
||||||
|
asio::experimental::awaitable<void> echo(tcp::socket socket)
|
||||||
|
{
|
||||||
|
auto token = co_await asio::experimental::this_coro::token();
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
char data[1024];
|
||||||
|
for (;;)
|
||||||
|
{
|
||||||
|
std::size_t n = co_await socket.async_read_some(asio::buffer(data), token);
|
||||||
|
co_await async_write(socket, asio::buffer(data, n), token);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
catch (std::exception& e)
|
||||||
|
{
|
||||||
|
std::printf("echo Exception: %s\n", e.what());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The first argument to <code class="computeroutput">co_spawn()</code> is an <a class="link" href="../../reference/Executor1.html" title="Executor requirements">executor</a>
|
||||||
|
that determines the context in which the coroutine is permitted to execute.
|
||||||
|
For example, a server's per-client object may consist of multiple coroutines;
|
||||||
|
they should all run on the same <code class="computeroutput">strand</code> so that no explicit
|
||||||
|
synchronisation is required.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The second argument is a nullary function object that returns a <a class="link" href="../../reference/experimental__awaitable.html" title="experimental::awaitable"><code class="computeroutput">asio::awaitable<R></code></a>,
|
||||||
|
where <code class="computeroutput">R</code> is the type of return value produced by the coroutine.
|
||||||
|
In the above example, the coroutine returns <code class="computeroutput">void</code>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The third argument is a completion token, and this is used by <code class="computeroutput">co_spawn()</code>
|
||||||
|
to produce a completion handler with signature <code class="computeroutput">void(std::exception_ptr,
|
||||||
|
R)</code>. This completion handler is invoked with the result of the coroutine
|
||||||
|
once it has finished. In the above example we pass a completion token type,
|
||||||
|
<a class="link" href="../../reference/experimental__detached.html" title="experimental::detached"><code class="computeroutput">asio::experimental::detached</code></a>,
|
||||||
|
which is used to explicitly ignore the result of an asynchronous operation.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
In this example the body of the coroutine is implemented in the <code class="computeroutput">echo</code>
|
||||||
|
function. This function first obtains a completion token that represents
|
||||||
|
the current coroutine:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">auto token = co_await asio::experimental::this_coro::token();
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
When this completion token is passed to an asynchronous operation, the
|
||||||
|
operation's initiating function returns an <code class="computeroutput">awaitable</code> that
|
||||||
|
may be used with the <code class="computeroutput">co_await</code> keyword:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">std::size_t n = co_await socket.async_read_some(asio::buffer(data), token);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
Where an asynchronous operation's handler signature has the form:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">void handler(asio::error_code ec, result_type result);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
the resulting type of the <code class="computeroutput">co_await</code> expression is <code class="computeroutput">result_type</code>.
|
||||||
|
In the <code class="computeroutput">async_read_some</code> example above, this is <code class="computeroutput">size_t</code>.
|
||||||
|
If the asynchronous operation fails, the <code class="computeroutput">error_code</code> is converted
|
||||||
|
into a <code class="computeroutput">system_error</code> exception and thrown.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Where a handler signature has the form:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">void handler(asio::error_code ec);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
the <code class="computeroutput">co_await</code> expression produces a <code class="computeroutput">void</code> result.
|
||||||
|
As above, an error is passed back to the coroutine as a <code class="computeroutput">system_error</code>
|
||||||
|
exception.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.coroutines_ts.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.coroutines_ts.see_also"></a></span><a class="link" href="coroutines_ts.html#asio.overview.core.coroutines_ts.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/experimental__co_spawn.html" title="experimental::co_spawn">experimental::co_spawn</a>,
|
||||||
|
<a class="link" href="../../reference/experimental__detached.html" title="experimental::detached">experimental::detached</a>,
|
||||||
|
<a class="link" href="../../reference/experimental__redirect_error.html" title="experimental::redirect_error">experimental::redirect_error</a>,
|
||||||
|
<a class="link" href="../../reference/experimental__awaitable.html" title="experimental::awaitable">experimental::awaitable</a>,
|
||||||
|
<a class="link" href="../../reference/experimental__await_token.html" title="experimental::await_token">experimental::await_token</a>,
|
||||||
|
<a class="link" href="../../reference/experimental__this_coro__executor.html" title="experimental::this_coro::executor">experimental::this_coro::executor</a>,
|
||||||
|
<a class="link" href="../../reference/experimental__this_coro__token.html" title="experimental::this_coro::token">experimental::this_coro::token</a>,
|
||||||
|
<a class="link" href="../../examples/cpp17_examples.html#asio.examples.cpp17_examples.coroutines_ts_support">Coroutines
|
||||||
|
TS examples</a>, <a class="link" href="spawn.html" title="Stackful Coroutines">Stackful Coroutines</a>,
|
||||||
|
<a class="link" href="coroutine.html" title="Stackless Coroutines">Stackless Coroutines</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="spawn.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="../networking.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
414
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/handler_tracking.html
vendored
Normal file
414
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/handler_tracking.html
vendored
Normal file
@@ -0,0 +1,414 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Handler Tracking</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="allocation.html" title="Custom Memory Allocation">
|
||||||
|
<link rel="next" href="concurrency_hint.html" title="Concurrency Hints">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="allocation.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="concurrency_hint.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.handler_tracking"></a><a class="link" href="handler_tracking.html" title="Handler Tracking">Handler Tracking</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
To aid in debugging asynchronous programs, Asio provides support for handler
|
||||||
|
tracking. When enabled by defining <code class="computeroutput"><span class="identifier">ASIO_ENABLE_HANDLER_TRACKING</span></code>,
|
||||||
|
Asio writes debugging output to the standard error stream. The output records
|
||||||
|
asynchronous operations and the relationships between their handlers.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
This feature is useful when debugging and you need to know how your asynchronous
|
||||||
|
operations are chained together, or what the pending asynchronous operations
|
||||||
|
are. As an illustration, here is the output when you run the HTTP Server
|
||||||
|
example, handle a single request, then shut down via Ctrl+C:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">@asio|1512254357.979980|0*1|signal_set@0x7ffeaaaa20d8.async_wait
|
||||||
|
@asio|1512254357.980127|0*2|socket@0x7ffeaaaa20f8.async_accept
|
||||||
|
@asio|1512254357.980150|.2|non_blocking_accept,ec=asio.system:11
|
||||||
|
@asio|1512254357.980162|0|resolver@0x7ffeaaaa1fd8.cancel
|
||||||
|
@asio|1512254368.457147|.2|non_blocking_accept,ec=system:0
|
||||||
|
@asio|1512254368.457193|>2|ec=system:0
|
||||||
|
@asio|1512254368.457219|2*3|socket@0x55cf39f0a238.async_receive
|
||||||
|
@asio|1512254368.457244|.3|non_blocking_recv,ec=system:0,bytes_transferred=141
|
||||||
|
@asio|1512254368.457275|2*4|socket@0x7ffeaaaa20f8.async_accept
|
||||||
|
@asio|1512254368.457293|.4|non_blocking_accept,ec=asio.system:11
|
||||||
|
@asio|1512254368.457301|<2|
|
||||||
|
@asio|1512254368.457310|>3|ec=system:0,bytes_transferred=141
|
||||||
|
@asio|1512254368.457441|3*5|socket@0x55cf39f0a238.async_send
|
||||||
|
@asio|1512254368.457502|.5|non_blocking_send,ec=system:0,bytes_transferred=156
|
||||||
|
@asio|1512254368.457511|<3|
|
||||||
|
@asio|1512254368.457519|>5|ec=system:0,bytes_transferred=156
|
||||||
|
@asio|1512254368.457544|5|socket@0x55cf39f0a238.close
|
||||||
|
@asio|1512254368.457559|<5|
|
||||||
|
@asio|1512254371.385106|>1|ec=system:0,signal_number=2
|
||||||
|
@asio|1512254371.385130|1|socket@0x7ffeaaaa20f8.close
|
||||||
|
@asio|1512254371.385163|<1|
|
||||||
|
@asio|1512254371.385175|>4|ec=asio.system:125
|
||||||
|
@asio|1512254371.385182|<4|
|
||||||
|
@asio|1512254371.385202|0|signal_set@0x7ffeaaaa20d8.cancel
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
Each line is of the form:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><tag>|<timestamp>|<action>|<description>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput"><tag></code> is always <code class="computeroutput">@asio</code>, and is used
|
||||||
|
to identify and extract the handler tracking messages from the program
|
||||||
|
output.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput"><timestamp></code> is seconds and microseconds from 1 Jan
|
||||||
|
1970 UTC.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput"><action></code> takes one of the following forms:
|
||||||
|
</p>
|
||||||
|
<div class="variablelist">
|
||||||
|
<p class="title"><b></b></p>
|
||||||
|
<dl>
|
||||||
|
<dt><span class="term">>n</span></dt>
|
||||||
|
<dd><p>
|
||||||
|
The program entered the handler number <code class="computeroutput">n</code>. The <code class="computeroutput"><description></code>
|
||||||
|
shows the arguments to the handler.
|
||||||
|
</p></dd>
|
||||||
|
<dt><span class="term"><n</span></dt>
|
||||||
|
<dd><p>
|
||||||
|
The program left handler number <code class="computeroutput">n</code>.
|
||||||
|
</p></dd>
|
||||||
|
<dt><span class="term">!n</span></dt>
|
||||||
|
<dd><p>
|
||||||
|
The program left handler number n due to an exception.
|
||||||
|
</p></dd>
|
||||||
|
<dt><span class="term">~n</span></dt>
|
||||||
|
<dd><p>
|
||||||
|
The handler number <code class="computeroutput">n</code> was destroyed without having been
|
||||||
|
invoked. This is usually the case for any unfinished asynchronous
|
||||||
|
operations when the <code class="computeroutput">io_context</code> is destroyed.
|
||||||
|
</p></dd>
|
||||||
|
<dt><span class="term">n*m</span></dt>
|
||||||
|
<dd><p>
|
||||||
|
The handler number <code class="computeroutput">n</code> created a new asynchronous operation
|
||||||
|
with completion handler number <code class="computeroutput">m</code>. The <code class="computeroutput"><description></code>
|
||||||
|
shows what asynchronous operation was started.
|
||||||
|
</p></dd>
|
||||||
|
<dt><span class="term">n</span></dt>
|
||||||
|
<dd><p>
|
||||||
|
The handler number <code class="computeroutput">n</code> performed some other operation.
|
||||||
|
The <code class="computeroutput"><description></code> shows what function was called.
|
||||||
|
Currently only <code class="computeroutput">close()</code> and <code class="computeroutput">cancel()</code> operations
|
||||||
|
are logged, as these may affect the state of pending asynchronous
|
||||||
|
operations.
|
||||||
|
</p></dd>
|
||||||
|
<dt><span class="term">.n</span></dt>
|
||||||
|
<dd><p>
|
||||||
|
The implementation performed a system call as part of the asynchronous
|
||||||
|
operation for which handler number <code class="computeroutput">n</code> is the completion
|
||||||
|
handler. The <code class="computeroutput"><description></code> shows what function
|
||||||
|
was called and its results. These tracking events are only emitted
|
||||||
|
when using a reactor-based implementation.
|
||||||
|
</p></dd>
|
||||||
|
</dl>
|
||||||
|
</div>
|
||||||
|
<p>
|
||||||
|
Where the <code class="computeroutput"><description></code> shows a synchronous or asynchronous
|
||||||
|
operation, the format is <code class="computeroutput"><object-type>@<pointer>.<operation></code>.
|
||||||
|
For handler entry, it shows a comma-separated list of arguments and their
|
||||||
|
values.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
As shown above, Each handler is assigned a numeric identifier. Where the
|
||||||
|
handler tracking output shows a handler number of 0, it means that the
|
||||||
|
action was performed outside of any handler.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.handler_tracking.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.handler_tracking.visual_representations"></a></span><a class="link" href="handler_tracking.html#asio.overview.core.handler_tracking.visual_representations">Visual
|
||||||
|
Representations</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
The handler tracking output may be post-processed using the included <code class="literal">handlerviz.pl</code>
|
||||||
|
tool to create a visual representation of the handlers (requires the GraphViz
|
||||||
|
tool <code class="literal">dot</code>).
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.handler_tracking.h1"></a>
|
||||||
|
<span><a name="asio.overview.core.handler_tracking.custom_tracking"></a></span><a class="link" href="handler_tracking.html#asio.overview.core.handler_tracking.custom_tracking">Custom Tracking</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
Handling tracking may be customised by defining the <code class="computeroutput"><span class="identifier">ASIO_CUSTOM_HANDLER_TRACKING</span></code>
|
||||||
|
macro to the name of a header file (enclosed in <code class="computeroutput"><span class="string">""</span></code>
|
||||||
|
or <code class="computeroutput"><span class="special"><></span></code>). This header
|
||||||
|
file must implement the following preprocessor macros:
|
||||||
|
</p>
|
||||||
|
<div class="informaltable"><table class="table">
|
||||||
|
<colgroup>
|
||||||
|
<col>
|
||||||
|
<col>
|
||||||
|
</colgroup>
|
||||||
|
<thead><tr>
|
||||||
|
<th>
|
||||||
|
<p>
|
||||||
|
Macro
|
||||||
|
</p>
|
||||||
|
</th>
|
||||||
|
<th>
|
||||||
|
<p>
|
||||||
|
Description
|
||||||
|
</p>
|
||||||
|
</th>
|
||||||
|
</tr></thead>
|
||||||
|
<tbody>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_INHERIT_TRACKED_HANDLER</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
Specifies a base class for classes that implement asynchronous
|
||||||
|
operations. When used, the macro immediately follows the class
|
||||||
|
name, so it must have the form <code class="computeroutput"><span class="special">:</span>
|
||||||
|
<span class="keyword">public</span> <span class="identifier">my_class</span></code>.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_ALSO_INHERIT_TRACKED_HANDLER</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
Specifies a base class for classes that implement asynchronous
|
||||||
|
operations. When used, the macro follows other base classes,
|
||||||
|
so it must have the form <code class="computeroutput"><span class="special">,</span>
|
||||||
|
<span class="keyword">public</span> <span class="identifier">my_class</span></code>.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_TRACKING_INIT</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is used to initialise the tracking mechanism.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_CREATION</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called on creation of an asynchronous operation.
|
||||||
|
<code class="computeroutput"><span class="identifier">args</span></code> is a parenthesised
|
||||||
|
function argument list containing the owning execution context,
|
||||||
|
the tracked handler, the name of the object type, a pointer to
|
||||||
|
the object, the object's native handle, and the operation name.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_COMPLETION</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called on completion of an asynchronous
|
||||||
|
operation. <code class="computeroutput"><span class="identifier">args</span></code>
|
||||||
|
is a parenthesised function argument list containing the tracked
|
||||||
|
handler.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_INVOCATION_BEGIN</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called immediately before a completion
|
||||||
|
handler is invoked. <code class="computeroutput"><span class="identifier">args</span></code>
|
||||||
|
is a parenthesised function argument list containing the arguments
|
||||||
|
to the completion handler.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_INVOCATION_END</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called immediately after a completion handler
|
||||||
|
is invoked.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_OPERATION</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called when some synchronous object operation
|
||||||
|
is called (such as <code class="computeroutput"><span class="identifier">close</span><span class="special">()</span></code> or <code class="computeroutput"><span class="identifier">cancel</span><span class="special">()</span></code>). <code class="computeroutput"><span class="identifier">args</span></code>
|
||||||
|
is a parenthesised function argument list containing the owning
|
||||||
|
execution context, the name of the object type, a pointer to
|
||||||
|
the object, the object's native handle, and the operation name.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_REACTOR_REGISTRATION</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called when an object is registered with
|
||||||
|
the reactor. <code class="computeroutput"><span class="identifier">args</span></code>
|
||||||
|
is a parenthesised function argument list containing the owning
|
||||||
|
execution context, the object's native handle, and a unique registration
|
||||||
|
key.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_REACTOR_DEREGISTRATION</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called when an object is deregistered from
|
||||||
|
the reactor. <code class="computeroutput"><span class="identifier">args</span></code>
|
||||||
|
is a parenthesised function argument list containing the owning
|
||||||
|
execution context, the object's native handle, and a unique registration
|
||||||
|
key.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_REACTOR_READ_EVENT</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
A bitmask constant used to identify reactor read readiness events.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_REACTOR_WRITE_EVENT</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
A bitmask constant used to identify reactor write readiness events.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_REACTOR_ERROR_EVENT</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
A bitmask constant used to identify reactor error readiness events.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_REACTOR_EVENTS</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called when an object registered with the
|
||||||
|
reactor becomes ready. <code class="computeroutput"><span class="identifier">args</span></code>
|
||||||
|
is a parenthesised function argument list containing the owning
|
||||||
|
execution context, the unique registration key, and a bitmask
|
||||||
|
of the ready events.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
<code class="computeroutput"><span class="identifier">ASIO_HANDLER_REACTOR_OPERATION</span><span class="special">(</span><span class="identifier">args</span><span class="special">)</span></code>
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<p>
|
||||||
|
An expression that is called when the implementation performs
|
||||||
|
a system call as part of a reactor-based asynchronous operation.
|
||||||
|
<code class="computeroutput"><span class="identifier">args</span></code> is a parenthesised
|
||||||
|
function argument list containing the tracked handler, the operation
|
||||||
|
name, the error code produced by the operation, and (optionally)
|
||||||
|
the number of bytes transferred.
|
||||||
|
</p>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
</tbody>
|
||||||
|
</table></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.handler_tracking.h2"></a>
|
||||||
|
<span><a name="asio.overview.core.handler_tracking.see_also"></a></span><a class="link" href="handler_tracking.html#asio.overview.core.handler_tracking.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../examples/cpp11_examples.html#asio.examples.cpp11_examples.handler_tracking">Custom handler
|
||||||
|
tracking example</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="allocation.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="concurrency_hint.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
157
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/line_based.html
vendored
Normal file
157
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/line_based.html
vendored
Normal file
@@ -0,0 +1,157 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Line-Based Operations</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="reactor.html" title="Reactor-Style Operations">
|
||||||
|
<link rel="next" href="allocation.html" title="Custom Memory Allocation">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="reactor.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="allocation.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.line_based"></a><a class="link" href="line_based.html" title="Line-Based Operations">Line-Based Operations</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Many commonly-used internet protocols are line-based, which means that
|
||||||
|
they have protocol elements that are delimited by the character sequence
|
||||||
|
<code class="computeroutput"><span class="string">"\r\n"</span></code>. Examples
|
||||||
|
include HTTP, SMTP and FTP. To more easily permit the implementation of
|
||||||
|
line-based protocols, as well as other protocols that use delimiters, Asio
|
||||||
|
includes the functions <code class="computeroutput"><span class="identifier">read_until</span><span class="special">()</span></code> and <code class="computeroutput"><span class="identifier">async_read_until</span><span class="special">()</span></code>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The following example illustrates the use of <code class="computeroutput"><span class="identifier">async_read_until</span><span class="special">()</span></code> in an HTTP server, to receive the first
|
||||||
|
line of an HTTP request from a client:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">class</span> <span class="identifier">http_connection</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="special">...</span>
|
||||||
|
|
||||||
|
<span class="keyword">void</span> <span class="identifier">start</span><span class="special">()</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">async_read_until</span><span class="special">(</span><span class="identifier">socket_</span><span class="special">,</span> <span class="identifier">data_</span><span class="special">,</span> <span class="string">"\r\n"</span><span class="special">,</span>
|
||||||
|
<span class="identifier">boost</span><span class="special">::</span><span class="identifier">bind</span><span class="special">(&</span><span class="identifier">http_connection</span><span class="special">::</span><span class="identifier">handle_request_line</span><span class="special">,</span> <span class="keyword">this</span><span class="special">,</span> <span class="identifier">_1</span><span class="special">));</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
|
||||||
|
<span class="keyword">void</span> <span class="identifier">handle_request_line</span><span class="special">(</span><span class="identifier">asio</span><span class="special">::</span><span class="identifier">error_code</span> <span class="identifier">ec</span><span class="special">)</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">if</span> <span class="special">(!</span><span class="identifier">ec</span><span class="special">)</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">string</span> <span class="identifier">method</span><span class="special">,</span> <span class="identifier">uri</span><span class="special">,</span> <span class="identifier">version</span><span class="special">;</span>
|
||||||
|
<span class="keyword">char</span> <span class="identifier">sp1</span><span class="special">,</span> <span class="identifier">sp2</span><span class="special">,</span> <span class="identifier">cr</span><span class="special">,</span> <span class="identifier">lf</span><span class="special">;</span>
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">istream</span> <span class="identifier">is</span><span class="special">(&</span><span class="identifier">data_</span><span class="special">);</span>
|
||||||
|
<span class="identifier">is</span><span class="special">.</span><span class="identifier">unsetf</span><span class="special">(</span><span class="identifier">std</span><span class="special">::</span><span class="identifier">ios_base</span><span class="special">::</span><span class="identifier">skipws</span><span class="special">);</span>
|
||||||
|
<span class="identifier">is</span> <span class="special">>></span> <span class="identifier">method</span> <span class="special">>></span> <span class="identifier">sp1</span> <span class="special">>></span> <span class="identifier">uri</span> <span class="special">>></span> <span class="identifier">sp2</span> <span class="special">>></span> <span class="identifier">version</span> <span class="special">>></span> <span class="identifier">cr</span> <span class="special">>></span> <span class="identifier">lf</span><span class="special">;</span>
|
||||||
|
<span class="special">...</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
|
||||||
|
<span class="special">...</span>
|
||||||
|
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">ip</span><span class="special">::</span><span class="identifier">tcp</span><span class="special">::</span><span class="identifier">socket</span> <span class="identifier">socket_</span><span class="special">;</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">streambuf</span> <span class="identifier">data_</span><span class="special">;</span>
|
||||||
|
<span class="special">};</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput"><span class="identifier">streambuf</span></code> data member
|
||||||
|
serves as a place to store the data that has been read from the socket
|
||||||
|
before it is searched for the delimiter. It is important to remember that
|
||||||
|
there may be additional data <span class="emphasis"><em>after</em></span> the delimiter.
|
||||||
|
This surplus data should be left in the <code class="computeroutput"><span class="identifier">streambuf</span></code>
|
||||||
|
so that it may be inspected by a subsequent call to <code class="computeroutput"><span class="identifier">read_until</span><span class="special">()</span></code> or <code class="computeroutput"><span class="identifier">async_read_until</span><span class="special">()</span></code>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The delimiters may be specified as a single <code class="computeroutput"><span class="keyword">char</span></code>,
|
||||||
|
a <code class="computeroutput"><span class="identifier">std</span><span class="special">::</span><span class="identifier">string</span></code> or a <code class="computeroutput"><span class="identifier">boost</span><span class="special">::</span><span class="identifier">regex</span></code>.
|
||||||
|
The <code class="computeroutput"><span class="identifier">read_until</span><span class="special">()</span></code>
|
||||||
|
and <code class="computeroutput"><span class="identifier">async_read_until</span><span class="special">()</span></code>
|
||||||
|
functions also include overloads that accept a user-defined function object
|
||||||
|
called a match condition. For example, to read data into a streambuf until
|
||||||
|
whitespace is encountered:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">typedef</span> <span class="identifier">asio</span><span class="special">::</span><span class="identifier">buffers_iterator</span><span class="special"><</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">streambuf</span><span class="special">::</span><span class="identifier">const_buffers_type</span><span class="special">></span> <span class="identifier">iterator</span><span class="special">;</span>
|
||||||
|
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">pair</span><span class="special"><</span><span class="identifier">iterator</span><span class="special">,</span> <span class="keyword">bool</span><span class="special">></span>
|
||||||
|
<span class="identifier">match_whitespace</span><span class="special">(</span><span class="identifier">iterator</span> <span class="identifier">begin</span><span class="special">,</span> <span class="identifier">iterator</span> <span class="identifier">end</span><span class="special">)</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="identifier">iterator</span> <span class="identifier">i</span> <span class="special">=</span> <span class="identifier">begin</span><span class="special">;</span>
|
||||||
|
<span class="keyword">while</span> <span class="special">(</span><span class="identifier">i</span> <span class="special">!=</span> <span class="identifier">end</span><span class="special">)</span>
|
||||||
|
<span class="keyword">if</span> <span class="special">(</span><span class="identifier">std</span><span class="special">::</span><span class="identifier">isspace</span><span class="special">(*</span><span class="identifier">i</span><span class="special">++))</span>
|
||||||
|
<span class="keyword">return</span> <span class="identifier">std</span><span class="special">::</span><span class="identifier">make_pair</span><span class="special">(</span><span class="identifier">i</span><span class="special">,</span> <span class="keyword">true</span><span class="special">);</span>
|
||||||
|
<span class="keyword">return</span> <span class="identifier">std</span><span class="special">::</span><span class="identifier">make_pair</span><span class="special">(</span><span class="identifier">i</span><span class="special">,</span> <span class="keyword">false</span><span class="special">);</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
<span class="special">...</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">streambuf</span> <span class="identifier">b</span><span class="special">;</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">read_until</span><span class="special">(</span><span class="identifier">s</span><span class="special">,</span> <span class="identifier">b</span><span class="special">,</span> <span class="identifier">match_whitespace</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
To read data into a streambuf until a matching character is found:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">class</span> <span class="identifier">match_char</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">public</span><span class="special">:</span>
|
||||||
|
<span class="keyword">explicit</span> <span class="identifier">match_char</span><span class="special">(</span><span class="keyword">char</span> <span class="identifier">c</span><span class="special">)</span> <span class="special">:</span> <span class="identifier">c_</span><span class="special">(</span><span class="identifier">c</span><span class="special">)</span> <span class="special">{}</span>
|
||||||
|
|
||||||
|
<span class="keyword">template</span> <span class="special"><</span><span class="keyword">typename</span> <span class="identifier">Iterator</span><span class="special">></span>
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">pair</span><span class="special"><</span><span class="identifier">Iterator</span><span class="special">,</span> <span class="keyword">bool</span><span class="special">></span> <span class="keyword">operator</span><span class="special">()(</span>
|
||||||
|
<span class="identifier">Iterator</span> <span class="identifier">begin</span><span class="special">,</span> <span class="identifier">Iterator</span> <span class="identifier">end</span><span class="special">)</span> <span class="keyword">const</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="identifier">Iterator</span> <span class="identifier">i</span> <span class="special">=</span> <span class="identifier">begin</span><span class="special">;</span>
|
||||||
|
<span class="keyword">while</span> <span class="special">(</span><span class="identifier">i</span> <span class="special">!=</span> <span class="identifier">end</span><span class="special">)</span>
|
||||||
|
<span class="keyword">if</span> <span class="special">(</span><span class="identifier">c_</span> <span class="special">==</span> <span class="special">*</span><span class="identifier">i</span><span class="special">++)</span>
|
||||||
|
<span class="keyword">return</span> <span class="identifier">std</span><span class="special">::</span><span class="identifier">make_pair</span><span class="special">(</span><span class="identifier">i</span><span class="special">,</span> <span class="keyword">true</span><span class="special">);</span>
|
||||||
|
<span class="keyword">return</span> <span class="identifier">std</span><span class="special">::</span><span class="identifier">make_pair</span><span class="special">(</span><span class="identifier">i</span><span class="special">,</span> <span class="keyword">false</span><span class="special">);</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
|
||||||
|
<span class="keyword">private</span><span class="special">:</span>
|
||||||
|
<span class="keyword">char</span> <span class="identifier">c_</span><span class="special">;</span>
|
||||||
|
<span class="special">};</span>
|
||||||
|
|
||||||
|
<span class="keyword">namespace</span> <span class="identifier">asio</span> <span class="special">{</span>
|
||||||
|
<span class="keyword">template</span> <span class="special"><></span> <span class="keyword">struct</span> <span class="identifier">is_match_condition</span><span class="special"><</span><span class="identifier">match_char</span><span class="special">></span>
|
||||||
|
<span class="special">:</span> <span class="keyword">public</span> <span class="identifier">boost</span><span class="special">::</span><span class="identifier">true_type</span> <span class="special">{};</span>
|
||||||
|
<span class="special">}</span> <span class="comment">// namespace asio</span>
|
||||||
|
<span class="special">...</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">streambuf</span> <span class="identifier">b</span><span class="special">;</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">read_until</span><span class="special">(</span><span class="identifier">s</span><span class="special">,</span> <span class="identifier">b</span><span class="special">,</span> <span class="identifier">match_char</span><span class="special">(</span><span class="char">'a'</span><span class="special">));</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput"><span class="identifier">is_match_condition</span><span class="special"><></span></code> type trait automatically evaluates
|
||||||
|
to true for functions, and for function objects with a nested <code class="computeroutput"><span class="identifier">result_type</span></code> typedef. For other types
|
||||||
|
the trait must be explicitly specialised, as shown above.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.line_based.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.line_based.see_also"></a></span><a class="link" href="line_based.html#asio.overview.core.line_based.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/async_read_until.html" title="async_read_until">async_read_until()</a>,
|
||||||
|
<a class="link" href="../../reference/is_match_condition.html" title="is_match_condition">is_match_condition</a>,
|
||||||
|
<a class="link" href="../../reference/read_until.html" title="read_until">read_until()</a>, <a class="link" href="../../reference/streambuf.html" title="streambuf">streambuf</a>,
|
||||||
|
<a class="link" href="../../examples/cpp03_examples.html#asio.examples.cpp03_examples.http_client">HTTP client example</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="reactor.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="allocation.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
78
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/reactor.html
vendored
Normal file
78
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/reactor.html
vendored
Normal file
@@ -0,0 +1,78 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Reactor-Style Operations</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="streams.html" title="Streams, Short Reads and Short Writes">
|
||||||
|
<link rel="next" href="line_based.html" title="Line-Based Operations">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="streams.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="line_based.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.reactor"></a><a class="link" href="reactor.html" title="Reactor-Style Operations">Reactor-Style Operations</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Sometimes a program must be integrated with a third-party library that
|
||||||
|
wants to perform the I/O operations itself. To facilitate this, Asio includes
|
||||||
|
synchronous and asynchronous operations that may be used to wait for a
|
||||||
|
socket to become ready to read, ready to write, or to have a pending error
|
||||||
|
condition.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
As an example, to perform a non-blocking read something like the following
|
||||||
|
may be used:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">ip</span><span class="special">::</span><span class="identifier">tcp</span><span class="special">::</span><span class="identifier">socket</span> <span class="identifier">socket</span><span class="special">(</span><span class="identifier">my_io_context</span><span class="special">);</span>
|
||||||
|
<span class="special">...</span>
|
||||||
|
<span class="identifier">socket</span><span class="special">.</span><span class="identifier">non_blocking</span><span class="special">(</span><span class="keyword">true</span><span class="special">);</span>
|
||||||
|
<span class="special">...</span>
|
||||||
|
<span class="identifier">socket</span><span class="special">.</span><span class="identifier">async_wait</span><span class="special">(</span><span class="identifier">ip</span><span class="special">::</span><span class="identifier">tcp</span><span class="special">::</span><span class="identifier">socket</span><span class="special">::</span><span class="identifier">wait_read</span><span class="special">,</span> <span class="identifier">read_handler</span><span class="special">);</span>
|
||||||
|
<span class="special">...</span>
|
||||||
|
<span class="keyword">void</span> <span class="identifier">read_handler</span><span class="special">(</span><span class="identifier">asio</span><span class="special">::</span><span class="identifier">error_code</span> <span class="identifier">ec</span><span class="special">)</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">if</span> <span class="special">(!</span><span class="identifier">ec</span><span class="special">)</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="identifier">std</span><span class="special">::</span><span class="identifier">vector</span><span class="special"><</span><span class="keyword">char</span><span class="special">></span> <span class="identifier">buf</span><span class="special">(</span><span class="identifier">socket</span><span class="special">.</span><span class="identifier">available</span><span class="special">());</span>
|
||||||
|
<span class="identifier">socket</span><span class="special">.</span><span class="identifier">read_some</span><span class="special">(</span><span class="identifier">buffer</span><span class="special">(</span><span class="identifier">buf</span><span class="special">));</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
These operations are supported for sockets on all platforms, and for the
|
||||||
|
POSIX stream-oriented descriptor classes.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.reactor.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.reactor.see_also"></a></span><a class="link" href="reactor.html#asio.overview.core.reactor.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/basic_socket/wait.html" title="basic_socket::wait">basic_socket::wait()</a>,
|
||||||
|
<a class="link" href="../../reference/basic_socket/async_wait.html" title="basic_socket::async_wait">basic_socket::async_wait()</a>,
|
||||||
|
<a class="link" href="../../reference/basic_socket/non_blocking.html" title="basic_socket::non_blocking">basic_socket::non_blocking()</a>,
|
||||||
|
<a class="link" href="../../reference/basic_socket/native_non_blocking.html" title="basic_socket::native_non_blocking">basic_socket::native_non_blocking()</a>,
|
||||||
|
<a class="link" href="../../examples/cpp03_examples.html#asio.examples.cpp03_examples.nonblocking">nonblocking example</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="streams.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="line_based.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
145
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/spawn.html
vendored
Normal file
145
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/spawn.html
vendored
Normal file
@@ -0,0 +1,145 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Stackful Coroutines</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="coroutine.html" title="Stackless Coroutines">
|
||||||
|
<link rel="next" href="coroutines_ts.html" title="Coroutines TS Support (experimental)">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="coroutine.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="coroutines_ts.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.spawn"></a><a class="link" href="spawn.html" title="Stackful Coroutines">Stackful Coroutines</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
The <a class="link" href="../../reference/spawn.html" title="spawn"><code class="computeroutput">spawn()</code></a> function
|
||||||
|
is a high-level wrapper for running stackful coroutines. It is based on
|
||||||
|
the Boost.Coroutine library. The <code class="computeroutput">spawn()</code> function enables
|
||||||
|
programs to implement asynchronous logic in a synchronous manner, as shown
|
||||||
|
in the following example:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">asio::spawn(my_strand, do_echo);
|
||||||
|
|
||||||
|
// ...
|
||||||
|
|
||||||
|
void do_echo(asio::yield_context yield)
|
||||||
|
{
|
||||||
|
try
|
||||||
|
{
|
||||||
|
char data[128];
|
||||||
|
for (;;)
|
||||||
|
{
|
||||||
|
std::size_t length =
|
||||||
|
my_socket.async_read_some(
|
||||||
|
asio::buffer(data), yield);
|
||||||
|
|
||||||
|
asio::async_write(my_socket,
|
||||||
|
asio::buffer(data, length), yield);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
catch (std::exception& e)
|
||||||
|
{
|
||||||
|
// ...
|
||||||
|
}
|
||||||
|
}
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The first argument to <code class="computeroutput">spawn()</code> may be a <a class="link" href="../../reference/io_context__strand.html" title="io_context::strand"><code class="computeroutput">strand</code></a>,
|
||||||
|
<a class="link" href="../../reference/io_context.html" title="io_context"><code class="computeroutput">io_context</code></a>,
|
||||||
|
or <a class="link" href="../../reference/CompletionHandler.html" title="Completion handler requirements">completion handler</a>.
|
||||||
|
This argument determines the context in which the coroutine is permitted
|
||||||
|
to execute. For example, a server's per-client object may consist of multiple
|
||||||
|
coroutines; they should all run on the same <code class="computeroutput">strand</code> so that
|
||||||
|
no explicit synchronisation is required.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The second argument is a function object with signature:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">void coroutine(asio::yield_context yield);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
that specifies the code to be run as part of the coroutine. The parameter
|
||||||
|
<code class="computeroutput">yield</code> may be passed to an asynchronous operation in place
|
||||||
|
of the completion handler, as in:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">std::size_t length =
|
||||||
|
my_socket.async_read_some(
|
||||||
|
asio::buffer(data), yield);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
This starts the asynchronous operation and suspends the coroutine. The
|
||||||
|
coroutine will be resumed automatically when the asynchronous operation
|
||||||
|
completes.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Where an asynchronous operation's handler signature has the form:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">void handler(asio::error_code ec, result_type result);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
the initiating function returns the result_type. In the <code class="computeroutput">async_read_some</code>
|
||||||
|
example above, this is <code class="computeroutput">size_t</code>. If the asynchronous operation
|
||||||
|
fails, the <code class="computeroutput">error_code</code> is converted into a <code class="computeroutput">system_error</code>
|
||||||
|
exception and thrown.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Where a handler signature has the form:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">void handler(asio::error_code ec);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
the initiating function returns <code class="computeroutput">void</code>. As above, an error is
|
||||||
|
passed back to the coroutine as a <code class="computeroutput">system_error</code> exception.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
To collect the <code class="computeroutput">error_code</code> from an operation, rather than have
|
||||||
|
it throw an exception, associate the output variable with the <code class="computeroutput">yield_context</code>
|
||||||
|
as follows:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">asio::error_code ec;
|
||||||
|
std::size_t length =
|
||||||
|
my_socket.async_read_some(
|
||||||
|
asio::buffer(data), yield[ec]);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
<span class="bold"><strong>Note:</strong></span> if <code class="computeroutput">spawn()</code> is used
|
||||||
|
with a custom completion handler of type <code class="computeroutput">Handler</code>, the function
|
||||||
|
object signature is actually:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">void coroutine(asio::basic_yield_context<Handler> yield);
|
||||||
|
</pre>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.spawn.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.spawn.see_also"></a></span><a class="link" href="spawn.html#asio.overview.core.spawn.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/spawn.html" title="spawn">spawn</a>, <a class="link" href="../../reference/yield_context.html" title="yield_context">yield_context</a>,
|
||||||
|
<a class="link" href="../../reference/basic_yield_context.html" title="basic_yield_context">basic_yield_context</a>,
|
||||||
|
<a class="link" href="../../examples/cpp03_examples.html#asio.examples.cpp03_examples.spawn">Spawn example (C++03)</a>,
|
||||||
|
<a class="link" href="../../examples/cpp11_examples.html#asio.examples.cpp11_examples.spawn">Spawn example (C++11)</a>,
|
||||||
|
<a class="link" href="coroutine.html" title="Stackless Coroutines">Stackless Coroutines</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="coroutine.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="coroutines_ts.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
160
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/strands.html
vendored
Normal file
160
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/strands.html
vendored
Normal file
@@ -0,0 +1,160 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Strands: Use Threads Without Explicit Locking</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="threads.html" title="Threads and Asio">
|
||||||
|
<link rel="next" href="buffers.html" title="Buffers">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="threads.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="buffers.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.strands"></a><a class="link" href="strands.html" title="Strands: Use Threads Without Explicit Locking">Strands: Use Threads Without
|
||||||
|
Explicit Locking</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
A strand is defined as a strictly sequential invocation of event handlers
|
||||||
|
(i.e. no concurrent invocation). Use of strands allows execution of code
|
||||||
|
in a multithreaded program without the need for explicit locking (e.g.
|
||||||
|
using mutexes).
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Strands may be either implicit or explicit, as illustrated by the following
|
||||||
|
alternative approaches:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
Calling io_context::run() from only one thread means all event handlers
|
||||||
|
execute in an implicit strand, due to the io_context's guarantee that
|
||||||
|
handlers are only invoked from inside run().
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
Where there is a single chain of asynchronous operations associated
|
||||||
|
with a connection (e.g. in a half duplex protocol implementation like
|
||||||
|
HTTP) there is no possibility of concurrent execution of the handlers.
|
||||||
|
This is an implicit strand.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
An explicit strand is an instance of <code class="computeroutput"><span class="identifier">strand</span><span class="special"><></span></code> or <code class="computeroutput"><span class="identifier">io_context</span><span class="special">::</span><span class="identifier">strand</span></code>.
|
||||||
|
All event handler function objects need to be bound to the strand using
|
||||||
|
<code class="computeroutput"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">bind_executor</span><span class="special">()</span></code>
|
||||||
|
or otherwise posted/dispatched through the strand object.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
In the case of composed asynchronous operations, such as <code class="computeroutput"><span class="identifier">async_read</span><span class="special">()</span></code>
|
||||||
|
or <code class="computeroutput"><span class="identifier">async_read_until</span><span class="special">()</span></code>,
|
||||||
|
if a completion handler goes through a strand, then all intermediate handlers
|
||||||
|
should also go through the same strand. This is needed to ensure thread
|
||||||
|
safe access for any objects that are shared between the caller and the
|
||||||
|
composed operation (in the case of <code class="computeroutput"><span class="identifier">async_read</span><span class="special">()</span></code> it's the socket, which the caller can
|
||||||
|
<code class="computeroutput"><span class="identifier">close</span><span class="special">()</span></code>
|
||||||
|
to cancel the operation).
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
To achieve this, all asynchronous operations obtain the handler's associated
|
||||||
|
executor by using the <code class="computeroutput"><span class="identifier">get_associated_executor</span></code>
|
||||||
|
function. For example:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">associated_executor_t</span><span class="special"><</span><span class="identifier">Handler</span><span class="special">></span> <span class="identifier">a</span> <span class="special">=</span> <span class="identifier">asio</span><span class="special">::</span><span class="identifier">get_associated_executor</span><span class="special">(</span><span class="identifier">h</span><span class="special">);</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The associated executor must satisfy the Executor requirements. It will
|
||||||
|
be used by the asynchronous operation to submit both intermediate and final
|
||||||
|
handlers for execution.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The executor may be customised for a particular handler type by specifying
|
||||||
|
a nested type <code class="computeroutput"><span class="identifier">executor_type</span></code>
|
||||||
|
and member function <code class="computeroutput"><span class="identifier">get_executor</span><span class="special">()</span></code>:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">class</span> <span class="identifier">my_handler</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">public</span><span class="special">:</span>
|
||||||
|
<span class="comment">// Custom implementation of Executor type requirements.</span>
|
||||||
|
<span class="keyword">typedef</span> <span class="identifier">my_executor</span> <span class="identifier">executor_type</span><span class="special">;</span>
|
||||||
|
|
||||||
|
<span class="comment">// Return a custom executor implementation.</span>
|
||||||
|
<span class="identifier">executor_type</span> <span class="identifier">get_executor</span><span class="special">()</span> <span class="keyword">const</span> <span class="keyword">noexcept</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">return</span> <span class="identifier">my_executor</span><span class="special">();</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
|
||||||
|
<span class="keyword">void</span> <span class="keyword">operator</span><span class="special">()()</span> <span class="special">{</span> <span class="special">...</span> <span class="special">}</span>
|
||||||
|
<span class="special">};</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
In more complex cases, the <code class="computeroutput"><span class="identifier">associated_executor</span></code>
|
||||||
|
template may be partially specialised directly:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="keyword">struct</span> <span class="identifier">my_handler</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">void</span> <span class="keyword">operator</span><span class="special">()()</span> <span class="special">{</span> <span class="special">...</span> <span class="special">}</span>
|
||||||
|
<span class="special">};</span>
|
||||||
|
|
||||||
|
<span class="keyword">namespace</span> <span class="identifier">asio</span> <span class="special">{</span>
|
||||||
|
|
||||||
|
<span class="keyword">template</span> <span class="special"><</span><span class="keyword">class</span> <span class="identifier">Executor</span><span class="special">></span>
|
||||||
|
<span class="keyword">struct</span> <span class="identifier">associated_executor</span><span class="special"><</span><span class="identifier">my_handler</span><span class="special">,</span> <span class="identifier">Executor</span><span class="special">></span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="comment">// Custom implementation of Executor type requirements.</span>
|
||||||
|
<span class="keyword">typedef</span> <span class="identifier">my_executor</span> <span class="identifier">type</span><span class="special">;</span>
|
||||||
|
|
||||||
|
<span class="comment">// Return a custom executor implementation.</span>
|
||||||
|
<span class="keyword">static</span> <span class="identifier">type</span> <span class="identifier">get</span><span class="special">(</span><span class="keyword">const</span> <span class="identifier">my_handler</span><span class="special">&,</span>
|
||||||
|
<span class="keyword">const</span> <span class="identifier">Executor</span><span class="special">&</span> <span class="special">=</span> <span class="identifier">Executor</span><span class="special">())</span> <span class="keyword">noexcept</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="keyword">return</span> <span class="identifier">my_executor</span><span class="special">();</span>
|
||||||
|
<span class="special">}</span>
|
||||||
|
<span class="special">};</span>
|
||||||
|
|
||||||
|
<span class="special">}</span> <span class="comment">// namespace asio</span>
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput"><span class="identifier">asio</span><span class="special">::</span><span class="identifier">bind_executor</span><span class="special">()</span></code>
|
||||||
|
function is a helper to bind a specific executor object, such as a strand,
|
||||||
|
to a completion handler. This binding automatically associates an executor
|
||||||
|
as shown above. For example, to bind a strand to a completion handler we
|
||||||
|
would simply write:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting"><span class="identifier">my_socket</span><span class="special">.</span><span class="identifier">async_read_some</span><span class="special">(</span><span class="identifier">my_buffer</span><span class="special">,</span>
|
||||||
|
<span class="identifier">asio</span><span class="special">::</span><span class="identifier">bind_executor</span><span class="special">(</span><span class="identifier">my_strand</span><span class="special">,</span>
|
||||||
|
<span class="special">[](</span><span class="identifier">error_code</span> <span class="identifier">ec</span><span class="special">,</span> <span class="identifier">size_t</span> <span class="identifier">length</span><span class="special">)</span>
|
||||||
|
<span class="special">{</span>
|
||||||
|
<span class="comment">// ...</span>
|
||||||
|
<span class="special">}));</span>
|
||||||
|
</pre>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.strands.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.strands.see_also"></a></span><a class="link" href="strands.html#asio.overview.core.strands.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/associated_executor.html" title="associated_executor">associated_executor</a>,
|
||||||
|
<a class="link" href="../../reference/get_associated_executor.html" title="get_associated_executor">get_associated_executor</a>,
|
||||||
|
<a class="link" href="../../reference/bind_executor.html" title="bind_executor">bind_executor</a>, <a class="link" href="../../reference/strand.html" title="strand">strand</a>, <a class="link" href="../../reference/io_context__strand.html" title="io_context::strand">io_context::strand</a>,
|
||||||
|
<a class="link" href="../../tutorial/tuttimer5.html" title="Timer.5 - Synchronising handlers in multithreaded programs">tutorial Timer.5</a>, <a class="link" href="../../examples/cpp03_examples.html#asio.examples.cpp03_examples.http_server_3">HTTP server 3 example</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="threads.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="buffers.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
120
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/streams.html
vendored
Normal file
120
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/streams.html
vendored
Normal file
@@ -0,0 +1,120 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Streams, Short Reads and Short Writes</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="buffers.html" title="Buffers">
|
||||||
|
<link rel="next" href="reactor.html" title="Reactor-Style Operations">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="buffers.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="reactor.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.streams"></a><a class="link" href="streams.html" title="Streams, Short Reads and Short Writes">Streams, Short Reads and
|
||||||
|
Short Writes</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Many I/O objects in Asio are stream-oriented. This means that:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
There are no message boundaries. The data being transferred is a continuous
|
||||||
|
sequence of bytes.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
Read or write operations may transfer fewer bytes than requested. This
|
||||||
|
is referred to as a short read or short write.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
Objects that provide stream-oriented I/O model one or more of the following
|
||||||
|
type requirements:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
<code class="computeroutput"><span class="identifier">SyncReadStream</span></code>, where
|
||||||
|
synchronous read operations are performed using a member function called
|
||||||
|
<code class="computeroutput"><span class="identifier">read_some</span><span class="special">()</span></code>.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<code class="computeroutput"><span class="identifier">AsyncReadStream</span></code>, where
|
||||||
|
asynchronous read operations are performed using a member function
|
||||||
|
called <code class="computeroutput"><span class="identifier">async_read_some</span><span class="special">()</span></code>.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<code class="computeroutput"><span class="identifier">SyncWriteStream</span></code>, where
|
||||||
|
synchronous write operations are performed using a member function
|
||||||
|
called <code class="computeroutput"><span class="identifier">write_some</span><span class="special">()</span></code>.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
<code class="computeroutput"><span class="identifier">AsyncWriteStream</span></code>, where
|
||||||
|
synchronous write operations are performed using a member function
|
||||||
|
called <code class="computeroutput"><span class="identifier">async_write_some</span><span class="special">()</span></code>.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
Examples of stream-oriented I/O objects include <code class="computeroutput"><span class="identifier">ip</span><span class="special">::</span><span class="identifier">tcp</span><span class="special">::</span><span class="identifier">socket</span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">ssl</span><span class="special">::</span><span class="identifier">stream</span><span class="special"><></span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">posix</span><span class="special">::</span><span class="identifier">stream_descriptor</span></code>, <code class="computeroutput"><span class="identifier">windows</span><span class="special">::</span><span class="identifier">stream_handle</span></code>,
|
||||||
|
etc.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Programs typically want to transfer an exact number of bytes. When a short
|
||||||
|
read or short write occurs the program must restart the operation, and
|
||||||
|
continue to do so until the required number of bytes has been transferred.
|
||||||
|
Asio provides generic functions that do this automatically: <code class="computeroutput"><span class="identifier">read</span><span class="special">()</span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">async_read</span><span class="special">()</span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">write</span><span class="special">()</span></code>
|
||||||
|
and <code class="computeroutput"><span class="identifier">async_write</span><span class="special">()</span></code>.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.streams.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.streams.why_eof_is_an_error"></a></span><a class="link" href="streams.html#asio.overview.core.streams.why_eof_is_an_error">Why
|
||||||
|
EOF is an Error</a>
|
||||||
|
</h6>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
The end of a stream can cause <code class="computeroutput"><span class="identifier">read</span></code>,
|
||||||
|
<code class="computeroutput"><span class="identifier">async_read</span></code>, <code class="computeroutput"><span class="identifier">read_until</span></code> or <code class="computeroutput"><span class="identifier">async_read_until</span></code>
|
||||||
|
functions to violate their contract. E.g. a read of N bytes may finish
|
||||||
|
early due to EOF.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
An EOF error may be used to distinguish the end of a stream from a
|
||||||
|
successful read of size 0.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.streams.h1"></a>
|
||||||
|
<span><a name="asio.overview.core.streams.see_also"></a></span><a class="link" href="streams.html#asio.overview.core.streams.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/async_read.html" title="async_read">async_read()</a>, <a class="link" href="../../reference/async_write.html" title="async_write">async_write()</a>,
|
||||||
|
<a class="link" href="../../reference/read.html" title="read">read()</a>, <a class="link" href="../../reference/write.html" title="write">write()</a>,
|
||||||
|
<a class="link" href="../../reference/AsyncReadStream.html" title="Buffer-oriented asynchronous read stream requirements">AsyncReadStream</a>,
|
||||||
|
<a class="link" href="../../reference/AsyncWriteStream.html" title="Buffer-oriented asynchronous write stream requirements">AsyncWriteStream</a>,
|
||||||
|
<a class="link" href="../../reference/SyncReadStream.html" title="Buffer-oriented synchronous read stream requirements">SyncReadStream</a>, <a class="link" href="../../reference/SyncWriteStream.html" title="Buffer-oriented synchronous write stream requirements">SyncWriteStream</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="buffers.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="reactor.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
123
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/threads.html
vendored
Normal file
123
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/core/threads.html
vendored
Normal file
@@ -0,0 +1,123 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Threads and Asio</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../core.html" title="Core Concepts and Functionality">
|
||||||
|
<link rel="prev" href="async.html" title="The Proactor Design Pattern: Concurrency Without Threads">
|
||||||
|
<link rel="next" href="strands.html" title="Strands: Use Threads Without Explicit Locking">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="async.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="strands.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.core.threads"></a><a class="link" href="threads.html" title="Threads and Asio">Threads and Asio</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.threads.h0"></a>
|
||||||
|
<span><a name="asio.overview.core.threads.thread_safety"></a></span><a class="link" href="threads.html#asio.overview.core.threads.thread_safety">Thread
|
||||||
|
Safety</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
In general, it is safe to make concurrent use of distinct objects, but
|
||||||
|
unsafe to make concurrent use of a single object. However, types such as
|
||||||
|
<code class="computeroutput"><span class="identifier">io_context</span></code> provide a stronger
|
||||||
|
guarantee that it is safe to use a single object concurrently.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.threads.h1"></a>
|
||||||
|
<span><a name="asio.overview.core.threads.thread_pools"></a></span><a class="link" href="threads.html#asio.overview.core.threads.thread_pools">Thread
|
||||||
|
Pools</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
Multiple threads may call <code class="computeroutput"><span class="identifier">io_context</span><span class="special">::</span><span class="identifier">run</span><span class="special">()</span></code> to set up a pool of threads from which
|
||||||
|
completion handlers may be invoked. This approach may also be used with
|
||||||
|
<code class="computeroutput"><span class="identifier">post</span><span class="special">()</span></code>
|
||||||
|
as a means to perform arbitrary computational tasks across a thread pool.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Note that all threads that have joined an <code class="computeroutput"><span class="identifier">io_context</span></code>'s
|
||||||
|
pool are considered equivalent, and the <code class="computeroutput"><span class="identifier">io_context</span></code>
|
||||||
|
may distribute work across them in an arbitrary fashion.
|
||||||
|
</p>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.threads.h2"></a>
|
||||||
|
<span><a name="asio.overview.core.threads.internal_threads"></a></span><a class="link" href="threads.html#asio.overview.core.threads.internal_threads">Internal
|
||||||
|
Threads</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
The implementation of this library for a particular platform may make use
|
||||||
|
of one or more internal threads to emulate asynchronicity. As far as possible,
|
||||||
|
these threads must be invisible to the library user. In particular, the
|
||||||
|
threads:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
must not call the user's code directly; and
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
must block all signals.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
This approach is complemented by the following guarantee:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc"><li class="listitem">
|
||||||
|
Asynchronous completion handlers will only be called from threads that
|
||||||
|
are currently calling <code class="computeroutput"><span class="identifier">io_context</span><span class="special">::</span><span class="identifier">run</span><span class="special">()</span></code>.
|
||||||
|
</li></ul></div>
|
||||||
|
<p>
|
||||||
|
Consequently, it is the library user's responsibility to create and manage
|
||||||
|
all threads to which the notifications will be delivered.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
The reasons for this approach include:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
By only calling <code class="computeroutput"><span class="identifier">io_context</span><span class="special">::</span><span class="identifier">run</span><span class="special">()</span></code> from a single thread, the user's
|
||||||
|
code can avoid the development complexity associated with synchronisation.
|
||||||
|
For example, a library user can implement scalable servers that are
|
||||||
|
single-threaded (from the user's point of view).
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
A library user may need to perform initialisation in a thread shortly
|
||||||
|
after the thread starts and before any other application code is executed.
|
||||||
|
For example, users of Microsoft's COM must call <code class="computeroutput"><span class="identifier">CoInitializeEx</span></code>
|
||||||
|
before any other COM operations can be called from that thread.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
The library interface is decoupled from interfaces for thread creation
|
||||||
|
and management, and permits implementations on platforms where threads
|
||||||
|
are not available.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<h6>
|
||||||
|
<a name="asio.overview.core.threads.h3"></a>
|
||||||
|
<span><a name="asio.overview.core.threads.see_also"></a></span><a class="link" href="threads.html#asio.overview.core.threads.see_also">See
|
||||||
|
Also</a>
|
||||||
|
</h6>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/io_context.html" title="io_context">io_context</a>, <a class="link" href="../../reference/post.html" title="post">post</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="async.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../core.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="strands.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
64
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011.html
vendored
Normal file
64
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011.html
vendored
Normal file
@@ -0,0 +1,64 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>C++ 2011 Support</title>
|
||||||
|
<link rel="stylesheet" href="../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../overview.html" title="Overview">
|
||||||
|
<link rel="prev" href="ssl.html" title="SSL">
|
||||||
|
<link rel="next" href="cpp2011/system_error.html" title="System Errors and Error Codes">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="ssl.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../overview.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="cpp2011/system_error.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h3 class="title">
|
||||||
|
<a name="asio.overview.cpp2011"></a><a class="link" href="cpp2011.html" title="C++ 2011 Support">C++ 2011 Support</a>
|
||||||
|
</h3></div></div></div>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/system_error.html" title="System Errors and Error Codes">System Errors and Error
|
||||||
|
Codes</a>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/move_objects.html" title="Movable I/O Objects">Movable I/O Objects</a>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/move_handlers.html" title="Movable Handlers">Movable Handlers</a>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/variadic.html" title="Variadic Templates">Variadic Templates</a>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/array.html" title="Array Container">Array Container</a>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/atomic.html" title="Atomics">Atomics</a>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/shared_ptr.html" title="Shared Pointers">Shared Pointers</a>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/chrono.html" title="Chrono">Chrono</a>
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="cpp2011/futures.html" title="Futures">Futures</a>
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="ssl.html"><img src="../../prev.png" alt="Prev"></a><a accesskey="u" href="../overview.html"><img src="../../up.png" alt="Up"></a><a accesskey="h" href="../../index.html"><img src="../../home.png" alt="Home"></a><a accesskey="n" href="cpp2011/system_error.html"><img src="../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
62
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/array.html
vendored
Normal file
62
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/array.html
vendored
Normal file
@@ -0,0 +1,62 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Array Container</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="prev" href="variadic.html" title="Variadic Templates">
|
||||||
|
<link rel="next" href="atomic.html" title="Atomics">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="variadic.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="atomic.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.cpp2011.array"></a><a class="link" href="array.html" title="Array Container">Array Container</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Where the standard library provides <code class="computeroutput">std::array<></code>, Asio:
|
||||||
|
</p>
|
||||||
|
<div class="itemizedlist"><ul class="itemizedlist" type="disc">
|
||||||
|
<li class="listitem">
|
||||||
|
Provides overloads for the <a class="link" href="../../reference/buffer.html" title="buffer">buffer()</a>
|
||||||
|
function.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
Uses it in preference to <code class="computeroutput">boost::array<></code> for the
|
||||||
|
<a class="link" href="../../reference/ip__address_v4/bytes_type.html" title="ip::address_v4::bytes_type">ip::address_v4::bytes_type</a>
|
||||||
|
and <a class="link" href="../../reference/ip__address_v6/bytes_type.html" title="ip::address_v6::bytes_type">ip::address_v6::bytes_type</a>
|
||||||
|
types.
|
||||||
|
</li>
|
||||||
|
<li class="listitem">
|
||||||
|
Uses it in preference to <code class="computeroutput">boost::array<></code> where a
|
||||||
|
fixed size array type is needed in the implementation.
|
||||||
|
</li>
|
||||||
|
</ul></div>
|
||||||
|
<p>
|
||||||
|
Support for <code class="computeroutput">std::array<></code> is automatically enabled for
|
||||||
|
<code class="literal">g++</code> 4.3 and later, when the <code class="literal">-std=c++0x</code>
|
||||||
|
or <code class="literal">-std=gnu++0x</code> compiler options are used, as well as
|
||||||
|
for Microsoft Visual C++ 10. It may be disabled by defining <code class="computeroutput">ASIO_DISABLE_STD_ARRAY</code>,
|
||||||
|
or explicitly enabled for other compilers by defining <code class="computeroutput">ASIO_HAS_STD_ARRAY</code>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="variadic.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="atomic.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
47
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/atomic.html
vendored
Normal file
47
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/atomic.html
vendored
Normal file
@@ -0,0 +1,47 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Atomics</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="prev" href="array.html" title="Array Container">
|
||||||
|
<link rel="next" href="shared_ptr.html" title="Shared Pointers">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="array.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="shared_ptr.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.cpp2011.atomic"></a><a class="link" href="atomic.html" title="Atomics">Atomics</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Asio's implementation can use <code class="computeroutput">std::atomic<></code> in preference
|
||||||
|
to <code class="computeroutput">boost::detail::atomic_count</code>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Support for the standard atomic integer template is automatically enabled
|
||||||
|
for <code class="literal">g++</code> 4.5 and later, when the <code class="literal">-std=c++0x</code>
|
||||||
|
or <code class="literal">-std=gnu++0x</code> compiler options are used. It may be
|
||||||
|
disabled by defining <code class="computeroutput">ASIO_DISABLE_STD_ATOMIC</code>, or explicitly
|
||||||
|
enabled for other compilers by defining <code class="computeroutput">ASIO_HAS_STD_ATOMIC</code>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="array.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="shared_ptr.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
58
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/chrono.html
vendored
Normal file
58
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/chrono.html
vendored
Normal file
@@ -0,0 +1,58 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Chrono</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="prev" href="shared_ptr.html" title="Shared Pointers">
|
||||||
|
<link rel="next" href="futures.html" title="Futures">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="shared_ptr.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="futures.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.cpp2011.chrono"></a><a class="link" href="chrono.html" title="Chrono">Chrono</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Asio provides timers based on the <code class="computeroutput">std::chrono</code> facilities via
|
||||||
|
the <a class="link" href="../../reference/basic_waitable_timer.html" title="basic_waitable_timer">basic_waitable_timer</a>
|
||||||
|
class template. The typedefs <a class="link" href="../../reference/system_timer.html" title="system_timer">system_timer</a>,
|
||||||
|
<a class="link" href="../../reference/steady_timer.html" title="steady_timer">steady_timer</a> and <a class="link" href="../../reference/high_resolution_timer.html" title="high_resolution_timer">high_resolution_timer</a>
|
||||||
|
utilise the standard clocks <code class="computeroutput">system_clock</code>, <code class="computeroutput">steady_clock</code>
|
||||||
|
and <code class="computeroutput">high_resolution_clock</code> respectively.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Support for the <code class="computeroutput">std::chrono</code> facilities is automatically enabled
|
||||||
|
for <code class="literal">g++</code> 4.6 and later, when the <code class="literal">-std=c++0x</code>
|
||||||
|
or <code class="literal">-std=gnu++0x</code> compiler options are used. (Note that,
|
||||||
|
for <code class="literal">g++</code>, the draft-standard <code class="computeroutput">monotonic_clock</code>
|
||||||
|
is used in place of <code class="computeroutput">steady_clock</code>.) Support may be disabled
|
||||||
|
by defining <code class="computeroutput">ASIO_DISABLE_STD_CHRONO</code>, or explicitly enabled
|
||||||
|
for other compilers by defining <code class="computeroutput">ASIO_HAS_STD_CHRONO</code>.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
When standard <code class="computeroutput">chrono</code> is unavailable, Asio will otherwise use
|
||||||
|
the Boost.Chrono library. The <a class="link" href="../../reference/basic_waitable_timer.html" title="basic_waitable_timer">basic_waitable_timer</a>
|
||||||
|
class template may be used with either.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="shared_ptr.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="futures.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
74
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/futures.html
vendored
Normal file
74
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/futures.html
vendored
Normal file
@@ -0,0 +1,74 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Futures</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="prev" href="chrono.html" title="Chrono">
|
||||||
|
<link rel="next" href="../implementation.html" title="Platform-Specific Implementation Notes">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="chrono.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="../implementation.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.cpp2011.futures"></a><a class="link" href="futures.html" title="Futures">Futures</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
The <code class="computeroutput">asio::use_future</code> special value provides first-class support
|
||||||
|
for returning a C++11 <code class="computeroutput">std::future</code> from an asynchronous operation's
|
||||||
|
initiating function.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
To use <code class="computeroutput">asio::use_future</code>, pass it to an asynchronous operation
|
||||||
|
instead of a normal completion handler. For example:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">std::future<std::size_t> length =
|
||||||
|
my_socket.async_read_some(my_buffer, asio::use_future);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
Where a handler signature has the form:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">void handler(asio::error_code ec, result_type result);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
the initiating function returns a <code class="computeroutput">std::future</code> templated on
|
||||||
|
<code class="computeroutput">result_type</code>. In the above example, this is <code class="computeroutput">std::size_t</code>.
|
||||||
|
If the asynchronous operation fails, the <code class="computeroutput">error_code</code> is converted
|
||||||
|
into a <code class="computeroutput">system_error</code> exception and passed back to the caller
|
||||||
|
through the future.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Where a handler signature has the form:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">void handler(asio::error_code ec);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
the initiating function returns <code class="computeroutput">std::future<void></code>. As
|
||||||
|
above, an error is passed back in the future as a <code class="computeroutput">system_error</code>
|
||||||
|
exception.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
<a class="link" href="../../reference/use_future.html" title="use_future">use_future</a>, <a class="link" href="../../reference/use_future_t.html" title="use_future_t">use_future_t</a>,
|
||||||
|
<a class="link" href="../../examples/cpp11_examples.html#asio.examples.cpp11_examples.futures">Futures example (C++11)</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="chrono.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="../implementation.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
83
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/move_handlers.html
vendored
Normal file
83
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/move_handlers.html
vendored
Normal file
@@ -0,0 +1,83 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Movable Handlers</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="prev" href="move_objects.html" title="Movable I/O Objects">
|
||||||
|
<link rel="next" href="variadic.html" title="Variadic Templates">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="move_objects.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="variadic.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.cpp2011.move_handlers"></a><a class="link" href="move_handlers.html" title="Movable Handlers">Movable Handlers</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
As an optimisation, user-defined completion handlers may provide move constructors,
|
||||||
|
and Asio's implementation will use a handler's move constructor in preference
|
||||||
|
to its copy constructor. In certain circumstances, Asio may be able to
|
||||||
|
eliminate all calls to a handler's copy constructor. However, handler types
|
||||||
|
are still required to be copy constructible.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
When move support is enabled, asynchronous that are documented as follows:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">template <typename Handler>
|
||||||
|
void async_XYZ(..., Handler handler);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
are actually declared as:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">template <typename Handler>
|
||||||
|
void async_XYZ(..., Handler&& handler);
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
The handler argument is perfectly forwarded and the move construction occurs
|
||||||
|
within the body of <code class="computeroutput">async_XYZ()</code>. This ensures that all other
|
||||||
|
function arguments are evaluated prior to the move. This is critical when
|
||||||
|
the other arguments to <code class="computeroutput">async_XYZ()</code> are members of the handler.
|
||||||
|
For example:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">struct my_operation
|
||||||
|
{
|
||||||
|
shared_ptr<tcp::socket> socket;
|
||||||
|
shared_ptr<vector<char>> buffer;
|
||||||
|
...
|
||||||
|
void operator(error_code ec, size_t length)
|
||||||
|
{
|
||||||
|
...
|
||||||
|
socket->async_read_some(asio::buffer(*buffer), std::move(*this));
|
||||||
|
...
|
||||||
|
}
|
||||||
|
};
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
Move support is automatically enabled for <code class="literal">g++</code> 4.5 and
|
||||||
|
later, when the <code class="literal">-std=c++0x</code> or <code class="literal">-std=gnu++0x</code>
|
||||||
|
compiler options are used. It may be disabled by defining <code class="computeroutput">ASIO_DISABLE_MOVE</code>,
|
||||||
|
or explicitly enabled for other compilers by defining <code class="computeroutput">ASIO_HAS_MOVE</code>.
|
||||||
|
Note that these macros also affect the availability of <a class="link" href="move_objects.html" title="Movable I/O Objects">movable
|
||||||
|
I/O objects</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="move_objects.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="variadic.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
101
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/move_objects.html
vendored
Normal file
101
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/move_objects.html
vendored
Normal file
@@ -0,0 +1,101 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Movable I/O Objects</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="prev" href="system_error.html" title="System Errors and Error Codes">
|
||||||
|
<link rel="next" href="move_handlers.html" title="Movable Handlers">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="system_error.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="move_handlers.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.cpp2011.move_objects"></a><a class="link" href="move_objects.html" title="Movable I/O Objects">Movable I/O Objects</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
When move support is available (via rvalue references), Asio allows move
|
||||||
|
construction and assignment of sockets, serial ports, POSIX descriptors
|
||||||
|
and Windows handles.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Move support allows you to write code like:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">tcp::socket make_socket(io_context& i)
|
||||||
|
{
|
||||||
|
tcp::socket s(i);
|
||||||
|
...
|
||||||
|
std::move(s);
|
||||||
|
}
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
or:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">class connection : public enable_shared_from_this<connection>
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
tcp::socket socket_;
|
||||||
|
...
|
||||||
|
public:
|
||||||
|
connection(tcp::socket&& s) : socket_(std::move(s)) {}
|
||||||
|
...
|
||||||
|
};
|
||||||
|
|
||||||
|
...
|
||||||
|
|
||||||
|
class server
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
tcp::acceptor acceptor_;
|
||||||
|
...
|
||||||
|
void handle_accept(error_code ec, tcp::socket socket)
|
||||||
|
{
|
||||||
|
if (!ec)
|
||||||
|
std::make_shared<connection>(std::move(socket))->go();
|
||||||
|
acceptor_.async_accept(...);
|
||||||
|
}
|
||||||
|
...
|
||||||
|
};
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
as well as:
|
||||||
|
</p>
|
||||||
|
<pre class="programlisting">std::vector<tcp::socket> sockets;
|
||||||
|
sockets.push_back(tcp::socket(...));
|
||||||
|
</pre>
|
||||||
|
<p>
|
||||||
|
A word of warning: There is nothing stopping you from moving these objects
|
||||||
|
while there are pending asynchronous operations, but it is unlikely to
|
||||||
|
be a good idea to do so. In particular, composed operations like <a class="link" href="../../reference/async_read.html" title="async_read">async_read()</a> store a reference
|
||||||
|
to the stream object. Moving during the composed operation means that the
|
||||||
|
composed operation may attempt to access a moved-from object.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Move support is automatically enabled for <code class="literal">g++</code> 4.5 and
|
||||||
|
later, when the <code class="literal">-std=c++0x</code> or <code class="literal">-std=gnu++0x</code>
|
||||||
|
compiler options are used. It may be disabled by defining <code class="computeroutput">ASIO_DISABLE_MOVE</code>,
|
||||||
|
or explicitly enabled for other compilers by defining <code class="computeroutput">ASIO_HAS_MOVE</code>.
|
||||||
|
Note that these macros also affect the availability of <a class="link" href="move_handlers.html" title="Movable Handlers">movable
|
||||||
|
handlers</a>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="system_error.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="move_handlers.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
47
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/shared_ptr.html
vendored
Normal file
47
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/shared_ptr.html
vendored
Normal file
@@ -0,0 +1,47 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>Shared Pointers</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="prev" href="atomic.html" title="Atomics">
|
||||||
|
<link rel="next" href="chrono.html" title="Chrono">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="atomic.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="chrono.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.cpp2011.shared_ptr"></a><a class="link" href="shared_ptr.html" title="Shared Pointers">Shared Pointers</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
Asio's implementation can use <code class="computeroutput">std::shared_ptr<></code> and
|
||||||
|
<code class="computeroutput">std::weak_ptr<></code> in preference to the Boost equivalents.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
Support for the standard smart pointers is automatically enabled for <code class="literal">g++</code>
|
||||||
|
4.3 and later, when the <code class="literal">-std=c++0x</code> or <code class="literal">-std=gnu++0x</code>
|
||||||
|
compiler options are used, as well as for Microsoft Visual C++ 10. It may
|
||||||
|
be disabled by defining <code class="computeroutput">ASIO_DISABLE_STD_SHARED_PTR</code>, or explicitly
|
||||||
|
enabled for other compilers by defining <code class="computeroutput">ASIO_HAS_STD_SHARED_PTR</code>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="atomic.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="chrono.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
49
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/system_error.html
vendored
Normal file
49
scout_base/src/scout_sdk/src/third_party/asio/doc/asio/overview/cpp2011/system_error.html
vendored
Normal file
@@ -0,0 +1,49 @@
|
|||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta http-equiv="Content-Type" content="text/html; charset=US-ASCII">
|
||||||
|
<title>System Errors and Error Codes</title>
|
||||||
|
<link rel="stylesheet" href="../../../boostbook.css" type="text/css">
|
||||||
|
<meta name="generator" content="DocBook XSL Stylesheets V1.75.2">
|
||||||
|
<link rel="home" href="../../../index.html" title="Asio">
|
||||||
|
<link rel="up" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="prev" href="../cpp2011.html" title="C++ 2011 Support">
|
||||||
|
<link rel="next" href="move_objects.html" title="Movable I/O Objects">
|
||||||
|
</head>
|
||||||
|
<body bgcolor="white" text="black" link="#0000FF" vlink="#840084" alink="#0000FF">
|
||||||
|
<table cellpadding="2" width="100%"><tr><td valign="top"><img alt="asio C++ library" width="250" height="60" src="../../../asio.png"></td></tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="../cpp2011.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="move_objects.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
<div class="section">
|
||||||
|
<div class="titlepage"><div><div><h4 class="title">
|
||||||
|
<a name="asio.overview.cpp2011.system_error"></a><a class="link" href="system_error.html" title="System Errors and Error Codes">System Errors and
|
||||||
|
Error Codes</a>
|
||||||
|
</h4></div></div></div>
|
||||||
|
<p>
|
||||||
|
When available, Asio can use the <code class="computeroutput">std::error_code</code> and <code class="computeroutput">std::system_error</code>
|
||||||
|
classes for reporting errors. In this case, the names <code class="computeroutput">asio::error_code</code>
|
||||||
|
and <code class="computeroutput">asio::system_error</code> will be typedefs for these standard
|
||||||
|
classes.
|
||||||
|
</p>
|
||||||
|
<p>
|
||||||
|
System error support is automatically enabled for <code class="literal">g++</code>
|
||||||
|
4.6 and later, when the <code class="literal">-std=c++0x</code> or <code class="literal">-std=gnu++0x</code>
|
||||||
|
compiler options are used. It may be disabled by defining <code class="computeroutput">ASIO_DISABLE_STD_SYSTEM_ERROR</code>,
|
||||||
|
or explicitly enabled for other compilers by defining <code class="computeroutput">ASIO_HAS_STD_SYSTEM_ERROR</code>.
|
||||||
|
</p>
|
||||||
|
</div>
|
||||||
|
<table xmlns:rev="http://www.cs.rpi.edu/~gregod/boost/tools/doc/revision" width="100%"><tr>
|
||||||
|
<td align="left"></td>
|
||||||
|
<td align="right"><div class="copyright-footer">Copyright © 2003-2018 Christopher M. Kohlhoff<p>
|
||||||
|
Distributed under the Boost Software License, Version 1.0. (See accompanying
|
||||||
|
file LICENSE_1_0.txt or copy at <a href="http://www.boost.org/LICENSE_1_0.txt" target="_top">http://www.boost.org/LICENSE_1_0.txt</a>)
|
||||||
|
</p>
|
||||||
|
</div></td>
|
||||||
|
</tr></table>
|
||||||
|
<hr>
|
||||||
|
<div class="spirit-nav">
|
||||||
|
<a accesskey="p" href="../cpp2011.html"><img src="../../../prev.png" alt="Prev"></a><a accesskey="u" href="../cpp2011.html"><img src="../../../up.png" alt="Up"></a><a accesskey="h" href="../../../index.html"><img src="../../../home.png" alt="Home"></a><a accesskey="n" href="move_objects.html"><img src="../../../next.png" alt="Next"></a>
|
||||||
|
</div>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user