├── CMakeLists.txt ├── LICENSE ├── README.md ├── Tutorial_Mid-100.md ├── config ├── performance_precision.yaml └── performance_realtime.yaml ├── include └── tools │ ├── common.h │ ├── common_tools.h │ ├── logger.hpp │ ├── os_compatible.hpp │ ├── pcl_tools.hpp │ ├── rapidjson │ ├── allocators.h │ ├── cursorstreamwrapper.h │ ├── document.h │ ├── encodedstream.h │ ├── encodings.h │ ├── error │ │ ├── en.h │ │ └── error.h │ ├── filereadstream.h │ ├── filewritestream.h │ ├── fwd.h │ ├── internal │ │ ├── biginteger.h │ │ ├── diyfp.h │ │ ├── dtoa.h │ │ ├── ieee754.h │ │ ├── itoa.h │ │ ├── meta.h │ │ ├── pow10.h │ │ ├── regex.h │ │ ├── stack.h │ │ ├── strfunc.h │ │ ├── strtod.h │ │ └── swap.h │ ├── istreamwrapper.h │ ├── memorybuffer.h │ ├── memorystream.h │ ├── msinttypes │ │ ├── inttypes.h │ │ └── stdint.h │ ├── ostreamwrapper.h │ ├── pointer.h │ ├── prettywriter.h │ ├── rapidjson.h │ ├── reader.h │ ├── schema.h │ ├── stream.h │ ├── stringbuffer.h │ └── writer.h │ ├── tools_eigen_math.hpp │ ├── tools_json.hpp │ ├── tools_logger.hpp │ ├── tools_random.hpp │ └── tools_timer.hpp ├── launch ├── livox.launch ├── rosbag.launch ├── rosbag_largescale.launch ├── rosbag_loop.launch ├── rosbag_loop_simple.launch ├── rosbag_mid100.launch └── rosbag_realtime.launch ├── package.xml ├── pics ├── CYT_01.png ├── CYT_02.png ├── HKUST_01.png ├── HKUST_02.png ├── HKU_ZYM_01.png ├── HKU_ZYM_02.png ├── for_mid100 │ ├── mid_100_demo.gif │ ├── modify_the_launch_files.png │ ├── remap_topics.png │ └── rostopic.png ├── handheld.png ├── hkust_stair.gif ├── loop_4in1.png ├── loop_hku_main.png ├── loop_hku_zym.png ├── loop_simple.png ├── system_low_cost.png ├── video_lc.png ├── video_loam.png └── zym_rotate.gif ├── rviz_cfg ├── .bashrc ├── rosbag.rviz └── rosbag_b.rviz └── source ├── cell_map_keyframe.hpp ├── ceres_icp.hpp ├── ceres_pose_graph_3d.hpp ├── eigen_math.hpp ├── laser_feature_extractor.cpp ├── laser_feature_extractor.hpp ├── laser_mapping.cpp ├── laser_mapping.hpp ├── livox_feature_extractor.hpp ├── point_cloud_registration.hpp ├── read_camera.cpp └── scene_alignment.hpp /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(loam_livox) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | set(CMAKE_CXX_FLAGS "-std=c++14") 6 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g") 7 | 8 | find_package(catkin REQUIRED COMPONENTS 9 | geometry_msgs 10 | nav_msgs 11 | sensor_msgs 12 | roscpp 13 | rospy 14 | rosbag 15 | std_msgs 16 | image_transport 17 | cv_bridge 18 | tf 19 | ) 20 | 21 | find_package(Eigen3 REQUIRED) 22 | find_package(OpenCV REQUIRED) 23 | find_package(Ceres REQUIRED) 24 | 25 | find_package(PCL REQUIRED) 26 | message(STATUS "***** PCL version: ${PCL_VERSION} *****") 27 | #### 28 | 29 | include_directories( 30 | include 31 | ${catkin_INCLUDE_DIRS} 32 | ${PCL_INCLUDE_DIRS} 33 | ${OpenCV_INCLUDE_DIRS} 34 | ${CERES_INCLUDE_DIRS} 35 | ./include/tools/ 36 | ) 37 | 38 | catkin_package( 39 | CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs 40 | DEPENDS EIGEN3 PCL 41 | INCLUDE_DIRS include 42 | ) 43 | 44 | 45 | add_executable(livox_scanRegistration source/laser_feature_extractor.cpp) 46 | target_link_libraries(livox_scanRegistration ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS}) 47 | 48 | add_executable(livox_laserMapping source/laser_mapping.cpp ) 49 | target_link_libraries(livox_laserMapping ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${CERES_LIBRARIES} ) 50 | 51 | add_executable(read_camera source/read_camera.cpp) 52 | target_link_libraries(read_camera ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${CERES_LIBRARIES} ${OpenCV_LIBS}) 53 | 54 | 55 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # LOAM-Livox 2 | ## A robust LiDAR Odometry and Mapping (LOAM) package for Livox-LiDAR 3 | 4 |
5 | 6 | 7 |
8 | 9 | **Loam-Livox** is a robust, low drift, and real time odometry and mapping package for [*Livox LiDARs*](https://www.livoxtech.com/), significant low cost and high performance LiDARs that are designed for massive industrials uses. Our package address many key issues: feature extraction and selection in a very limited FOV, robust outliers rejection, moving objects filtering, and motion distortion compensation. In addition, we also integrate other features like parallelable pipeline, point cloud management using cells and maps, loop closure, utilities for maps saving and reload, etc. To know more about the details, please refer to our related paper:) 10 | 11 |
12 | 13 |
14 | 15 | 16 | In the development of our package, we reference to LOAM, [LOAM_NOTED](https://github.com/cuitaixiang/LOAM_NOTED), and [A-LOAM](https://github.com/HKUST-Aerial-Robotics/A-LOAM). 17 | 18 | **Developer:** [Jiarong Lin](https://github.com/ziv-lin) 19 | 20 | **Our related paper**: our related papers are now available on arxiv: 21 | 1. [Loam_livox: A fast, robust, high-precision LiDAR odometry and mapping package for LiDARs of small FoV](https://arxiv.org/abs/1909.06700) 22 | 2. [A fast, complete, point cloud based loop closure for LiDAR odometry and mapping](https://arxiv.org/abs/1909.11811) 23 | 24 | **Our related video**: our related videos are now available on YouTube (click below images to open): 25 |
26 | video 27 | video 28 |
29 | 30 | 31 | ## 1. Prerequisites 32 | ### 1.1 **Ubuntu** and **ROS** 33 | Ubuntu 64-bit 16.04 or 18.04. 34 | ROS Kinetic or Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation) and its additional ROS pacakge: 35 | 36 | ``` 37 | sudo apt-get install ros-XXX-cv-bridge ros-XXX-tf ros-XXX-message-filters ros-XXX-image-transport 38 | ``` 39 | **NOTICE:** remember to replace "XXX" on above command as your ROS distributions, for example, if your use ROS-kinetic, the command should be: 40 | 41 | ``` 42 | sudo apt-get install ros-kinetic-cv-bridge ros-kinetic-tf ros-kinetic-message-filters ros-kinetic-image-transport 43 | ``` 44 | 45 | ### 1.2. **Ceres Solver** 46 | Follow [Ceres Installation](http://ceres-solver.org/installation.html). 47 | 48 | ### 1.3. **PCL** 49 | Follow [PCL Installation](http://www.pointclouds.org/downloads/linux.html). 50 | 51 | **NOTICE:** Recently, we find that the point cloud output form the voxelgrid filter vary form PCL 1.7 and 1.9, and PCL 1.7 leads some failure in some of our examples ([issue #28](https://github.com/hku-mars/loam_livox/issues/28)). By this, we strongly recommand you to use update your PCL as version 1.9 if you are using the lower version. 52 | 53 | ## 2. Build 54 | Clone the repository and catkin_make: 55 | 56 | ``` 57 | cd ~/catkin_ws/src 58 | git clone https://github.com/hku-mars/loam_livox.git 59 | cd ../ 60 | catkin_make 61 | source ~/catkin_ws/devel/setup.bash 62 | ``` 63 | ## 3. Directly run 64 | ### 3.1 Livox Mid-40 65 | Connect to your PC to Livox LiDAR (Mid-40) by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then (launch our algorithm **first**, then livox-ros-driver): 66 | 67 | ``` 68 | roslaunch loam_livox livox.launch 69 | roslaunch livox_ros_driver livox_lidar.launch 70 | ``` 71 | ### 3.2 Livox Mid-100 72 | Unfortunately, the default configuration of Livox-ros-driver mix all three lidar point cloud as together, which causes some difficulties in our feature extraction and motion blur compensation. By this, some of the adaptations (modify some configurations) are required to launch our package. 73 | 74 | For more details, please kindly refer our [**tutorials (click me to open)**](./Tutorial_Mid-100.md). 75 | 76 | ## 4. Rosbag Example 77 | ### 4.1. **Common rosbag** 78 | Download [Our recorded rosbag](https://drive.google.com/drive/folders/1HWomWWPSEVvka2QVB2G41iRvSwIt5NWf?usp=sharing) and then 79 | ``` 80 | roslaunch loam_livox rosbag.launch 81 | rosbag play YOUR_DOWNLOADED.bag 82 | ``` 83 |
84 | 85 | 86 |
87 | 88 |
89 | 90 | 91 |
92 | 93 | ### 4.1. **Large-scale rosbag** 94 | For large scale rosbag (for example, the [HKUST_01.bag](https://drive.google.com/file/d/1OoAu0WcRhyDsQB9ltPLWeZ2WZlGJz6LO/view?usp=sharing) ), we recommand you launch with bigger line and plane resolution (using *rosbag_largescale.launch*) 95 | ``` 96 | roslaunch loam_livox rosbag_largescale.launch 97 | rosbag play YOUR_DOWNLOADED.bag 98 | ``` 99 |
100 | 101 | 102 |
103 | 104 | ### 4.2 **Livox Mid-100 example** 105 | Download our recorded rosbag files ([mid100_example.bag](https://drive.google.com/open?id=1hvjmt4YuGROE-3HWqOfUdofc6zvXxjmU) ), then: 106 | ``` 107 | roslaunch loam_livox rosbag_mid100.launch 108 | rosbag play mid100_example.bag 109 | ``` 110 |
111 | 112 |
113 | 114 | ## 5. Rosbag Example with loop closure enabled 115 | 116 | ### 5.1. **Loop closure demostration** 117 | We provide a rosbag file of small size (named "loop_loop_hku_zym.bag", [Download here](https://drive.google.com/file/d/1rXRzbiZYeFtCWhmwCj8OuZaUUkGCsNrM)) for demostration: 118 |
119 | 120 |
121 | 122 | ``` 123 | roslaunch loam_livox rosbag_loop_simple.launch 124 | rosbag play YOUR_PATH/loop_simple.bag 125 | ``` 126 | ### 5.2. **Other examples** 127 |
128 | 129 | 130 |
131 | 132 | For other example ([loop_loop_hku_zym.bag](https://drive.google.com/open?id=1J3sVQEwnkjaimf9abH1qjId1S4VEZuMu), [loop_hku_main.bag](https://drive.google.com/open?id=1HrlFkzLMfcYbQsbOiSlSlm5blybrSVd2)), launch with: 133 | ``` 134 | roslaunch loam_livox rosbag_loop.launch 135 | rosbag play YOUR_DOWNLOADED.bag 136 | ``` 137 | **NOTICE:** The only difference between launch files "rosbag_loop_simple.launch" and "rosbag_loop.launch" is the minimum number of keyframes (minimum_keyframe_differen) between two candidate frames of loop detection. 138 | 139 | 140 | ## 6. Have troubles in downloading the rosbag files? 141 | If you have some troubles in downloading the rosbag files form google net-disk (like [issue #33](https://github.com/hku-mars/loam_livox/issues/33)), you can download the same files from [Baidu net-disk](https://pan.baidu.com/s/1nMSJRuP8io8mEqLgACUT_w). 142 | ``` 143 | Link(链接): https://pan.baidu.com/s/1nMSJRuP8io8mEqLgACUT_w 144 | Extraction code(提取码): sv9z 145 | ``` 146 | If the share link is disabled, please feel free to email me (ziv.lin.ljr@gmail.com) for updating the link as soon as possible. 147 | 148 | ## 7. Our 3D-printable handheld device 149 | To get our following handheld device, please go to another one of our [open source reposity](https://github.com/ziv-lin/My_solidworks/tree/master/livox_handhold), all of the 3D parts are all designed of FDM printable. We also release our solidwork files so that you can freely make your own adjustments. 150 | 151 |
152 | 153 | 154 |
155 | 156 | ## 8.Acknowledgments 157 | Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time) LOAM, [LOAM_NOTED](https://github.com/cuitaixiang/LOAM_NOTED), and [A-LOAM](https://github.com/HKUST-Aerial-Robotics/A-LOAM). 158 | 159 | ## 9. License 160 | The source code is released under [GPLv2](http://www.gnu.org/licenses/) license. 161 | 162 | We are still working on improving the performance and reliability of our codes. For any technical issues, please contact me via email Jiarong Lin < ziv.lin.ljr@gmail.com >. 163 | 164 | For commercial use, please contact Dr. Fu Zhang < fuzhang@hku.hk > 165 | -------------------------------------------------------------------------------- /Tutorial_Mid-100.md: -------------------------------------------------------------------------------- 1 | # Launch our package with Livox Mid-100 2 | As we have mentioned in our [project page](./README.md), the default configuration of Livox-ros-driver mix all three lidar point cloud as together, which causes some difficulties in our feature extraction and motion blur compensation. By this, some of the adaptations (modify some configurations) are required to launch our package :) 3 |
4 | 5 |
6 | # 1. Installation the newest [Livox-SDK](https://github.com/Livox-SDK/Livox-SDK) and [Livox-ros-driver](https://github.com/Livox-SDK/livox_ros_driver) 7 | Publish the Mid-100 point cloud data as three independence topics is the relatively new feature of drivers. If you are using the older kits, please update your driver (including both the SDK and ROS-dirver) as the newest version. 8 | 9 | ## 1.1 Install Livox-SDK 10 | Follow [Livox-SDK Installation](https://github.com/Livox-SDK/Livox-SDK). 11 | ## 1.2 Install Livox-ros-driver 12 | 13 | Follow [Livox-ros-driver Installation](https://github.com/Livox-SDK/livox_ros_driver). 14 | 15 | ## 2. Publish Mid-100 point cloud data as three independence topics 16 | To change the way of publishing the point cloud, you can modify the parameter named "multi_topic" in the launch file ([livox_lidar.launch](https://github.com/Livox-SDK/livox_ros_driver/blob/master/livox_ros_driver/launch/livox_lidar.launch) ) from "0" to "1", like this: 17 |
18 | 19 |
20 | 21 | 22 | If your configurations are correct, you will see this the point cloud data are published by three rostopics, like this: 23 | ``` 24 | roslaunch livox_ros_driver livox_lidar.launch 25 | rostopic list 26 | ``` 27 |
28 | 29 |
30 | The ros-messages with its topic named **"/livox/lidar_SN"** is of the data published by Mid-100. 31 | 32 | ## 3. Launch our package 33 | Before launch our package, you need to remap the topic to ensure our package can receive the point cloud data. 34 | 35 | Open our launch files (for example, the [rosbag_mid100.launch](./launch/rosbag_mid100.launch)), then remap the topic name "/laser_points_0", "/laser_points_1" and "/laser_points_3" to the topic "/livox/lidar_SN", shown as the following figure: 36 |
37 | 38 |
39 | 40 | ## 4. Rosbag example 41 | Download our recorded rosbag files ([mid100_example.bag](mid100_example) ), then: 42 | ``` 43 | roslaunch loam_livox rosbag_mid100.launch 44 | rosbag play mid100_example.bag 45 | ``` -------------------------------------------------------------------------------- /config/performance_precision.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lidar_type: "livox" 3 | maximum_parallel_thread: 1 # number of thread use for interative pose optimization 4 | odom_mode: 1 5 | if_motion_deblur: 0 # motion deblur, 0: piesewise processing; 1: linear interpolation 6 | if_save_to_pcd_files: 0 7 | if_update_mean_and_cov_incrementally: 1 8 | threshold_cell_revisit: 2000 # if update frame index bigger than this threshold, treat target cell as revisited 9 | 10 | feature_extraction: 11 | scan_line: 64 12 | mapping_line_resolution: 0.1 13 | mapping_plane_resolution: 0.4 14 | livox_min_sigma: 7e-4 15 | livox_min_dis: 0.1 16 | corner_curvature: 0.1 17 | surface_curvature: 0.005 18 | minimum_view_angle: 5 19 | 20 | optimization: 21 | minimum_icp_R_diff: 0.01 22 | minimum_icp_T_diff: 0.01 23 | maximum_residual_blocks: 200 24 | max_allow_final_cost: 2.0 25 | icp_maximum_iteration: 15 26 | ceres_maximum_iteration: 50 27 | 28 | mapping: 29 | matching_mode: 0 # 0 = history, 1 = cube 30 | input_downsample_mode: 1 # 31 | init_accumulate_frames: 50 32 | maximum_mapping_buffer: 20000000 33 | maximum_histroy_buffer: 400 34 | maximum_in_fov_angle: 45 35 | maximum_pointcloud_delay_time: 0.1 36 | maximum_search_range_corner: 100 37 | maximum_search_range_surface: 100 38 | surround_pointcloud_resolution: 0.30 39 | max_allow_incre_R: 20 40 | max_allow_incre_T: 0.3 41 | max_allow_final_cost: 2.0 42 | 43 | loop_closure: 44 | if_enable_loop_closure: 0 45 | if_dump_keyframe_data: 0 46 | scans_of_each_keyframe: 300 47 | scans_between_two_keyframe: 100 48 | minimum_keyframe_differen: 200 49 | minimum_similarity_linear: 0.65 50 | minimum_similarity_planar: 0.94 51 | map_alignment_resolution: 0.1 52 | maximum_keyframe_in_waiting_list: 10 53 | map_alignment_maximum_icp_iteration: 5 54 | map_alignment_inlier_threshold: 0.20 55 | map_alignment_if_dump_matching_result: 0 56 | scene_alignment_maximum_residual_block: 3000 -------------------------------------------------------------------------------- /config/performance_realtime.yaml: -------------------------------------------------------------------------------- 1 | common: 2 | lidar_type: "livox" 3 | maximum_parallel_thread: 3 # number of thread use for interative pose optimization 4 | odom_mode: 1 5 | if_motion_deblur: 0 # motion deblur, 0: piesewise processing; 1: linear interpolation 6 | if_save_to_pcd_files: 0 7 | if_update_mean_and_cov_incrementally: 0 8 | threshold_cell_revisit: 100000 # if update frame index bigger than this threshold, treat target cell as revisited 9 | 10 | feature_extraction: 11 | scan_line: 64 12 | mapping_line_resolution: 0.2 13 | mapping_plane_resolution: 0.6 14 | livox_min_sigma: 7e-4 15 | livox_min_dis: 0.1 16 | corner_curvature: 0.1 17 | surface_curvature: 0.005 18 | minimum_view_angle: 5 19 | 20 | optimization: 21 | minimum_icp_R_diff: 0.01 22 | minimum_icp_T_diff: 0.01 23 | maximum_residual_blocks: 150 24 | max_allow_final_cost: 2.0 25 | icp_maximum_iteration: 15 26 | ceres_maximum_iteration: 50 27 | 28 | mapping: 29 | matching_mode: 0 # 0 = history, 1 = cube 30 | input_downsample_mode: 1 # 31 | init_accumulate_frames: 50 32 | maximum_mapping_buffer: 50 33 | maximum_histroy_buffer: 200 34 | maximum_in_fov_angle: 45 35 | maximum_pointcloud_delay_time: 1.0 36 | maximum_search_range_corner: 100 37 | maximum_search_range_surface: 100 38 | surround_pointcloud_resolution: 0.5 39 | 40 | loop_closure: 41 | if_enable_loop_closure: 0 42 | if_dump_keyframe_data: 0 43 | scans_of_each_keyframe: 300 44 | scans_between_two_keyframe: 100 45 | minimum_keyframe_differen: 200 46 | minimum_similarity_linear: 0.65 47 | minimum_similarity_planar: 0.94 48 | map_alignment_resolution: 0.1 49 | maximum_keyframe_in_waiting_list: 10 50 | map_alignment_maximum_icp_iteration: 5 51 | map_alignment_inlier_threshold: 0.20 52 | map_alignment_if_dump_matching_result: 0 53 | scene_alignment_maximum_residual_block: 3000 -------------------------------------------------------------------------------- /include/tools/common.h: -------------------------------------------------------------------------------- 1 | // Author: Jiarong Lin ziv.lin.ljr@gmail.com 2 | 3 | #pragma once 4 | 5 | #include 6 | 7 | #include 8 | #define printf_line printf( " %s %d \r\n", __FILE__, __LINE__ ); 9 | typedef pcl::PointXYZI PointType; 10 | 11 | inline double rad2deg(double radians) 12 | { 13 | return radians * 180.0 / M_PI; 14 | } 15 | 16 | inline double deg2rad(double degrees) 17 | { 18 | return degrees * M_PI / 180.0; 19 | } 20 | -------------------------------------------------------------------------------- /include/tools/common_tools.h: -------------------------------------------------------------------------------- 1 | #ifndef __COMMON_TOOLS_H__ 2 | #define __COMMON_TOOLS_H__ 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include "tools_logger.hpp" 12 | #include "tools_timer.hpp" 13 | #include "tools_random.hpp" 14 | #include "tools_json.hpp" 15 | #include "os_compatible.hpp" 16 | namespace Common_tools 17 | { 18 | template 19 | static std::vector vector_2d_to_1d(std::vector> & pt_vec_vec) 20 | { 21 | std::vector pt_vec; 22 | for (unsigned int i = 0; i < pt_vec_vec.size(); i++) 23 | { 24 | pt_vec.insert(pt_vec.end(), pt_vec_vec[i].begin(), pt_vec_vec[i].end()); 25 | } 26 | return pt_vec; 27 | }; 28 | 29 | template 30 | std::vector std_set_to_vector (const std::set & input_set) 31 | { 32 | std::vector output_vector; 33 | for(auto it = input_set.begin() ; it!= input_set.end(); it++) 34 | { 35 | output_vector.push_back(*(it)); 36 | } 37 | return output_vector; 38 | }; 39 | 40 | template 41 | std::set std_vector_to_set (const std::vector & input_vector) 42 | { 43 | std::set output_set; 44 | for(auto it = input_vector.begin() ; it!= input_vector.end(); it++) 45 | { 46 | output_set.insert(*(it)); 47 | } 48 | return output_set; 49 | }; 50 | 51 | template 52 | void maintain_maximum_thread_pool(std::list & thread_pool, size_t maximum_parallel_thread) 53 | { 54 | if(thread_pool.size() >= (size_t) maximum_parallel_thread) 55 | { 56 | //printf("******** Maximum thread number reach, current size = %d, wait finish... *****\r\n", thread_pool.size()); 57 | while ( 1 ) 58 | { 59 | //printf_line; 60 | for ( auto it = thread_pool.begin(); it != thread_pool.end(); it++ ) 61 | { 62 | 63 | auto status = (*it)->wait_for(std::chrono::nanoseconds(1)); 64 | if ( status == std::future_status::ready ) 65 | { 66 | //cout << "status == std::future_status::ready" << endl; 67 | delete *it; 68 | thread_pool.erase( it ); 69 | break; 70 | } 71 | } 72 | if(thread_pool.size() < (size_t) maximum_parallel_thread) 73 | { 74 | break; 75 | } 76 | std::this_thread::sleep_for( std::chrono::nanoseconds( 1 ) ); 77 | } 78 | 79 | } 80 | 81 | }; 82 | 83 | inline bool if_file_exit( const std::string &name ) 84 | { 85 | //Copy from: https://stackoverflow.com/questions/12774207/fastest-way-to-check-if-a-file-exist-using-standard-c-c11-c 86 | struct stat buffer; 87 | return ( stat( name.c_str(), &buffer ) == 0 ); 88 | }; 89 | } 90 | #endif 91 | -------------------------------------------------------------------------------- /include/tools/logger.hpp: -------------------------------------------------------------------------------- 1 | // Author: Lin Jiarong ziv.lin.ljr@gmail.com 2 | 3 | #ifndef __LOGGER_HPP__ 4 | #define __LOGGER_HPP__ 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include // mkdir dir 13 | #include //need for such like printf(...) 14 | using namespace std; 15 | 16 | // #define FILE_LOGGER_VERSION "V1.0" 17 | // #define FILE_LOGGER_VERSION_INFO "First version" 18 | 19 | #define FILE_LOGGER_VERSION "V1.1" 20 | #define FILE_LOGGER_VERSION_INFO "Add macro, make logger more easy to call" 21 | 22 | #define LOG_FILE_LINE( x ) \ 23 | *( ( x ).get_ostream() ) << __FILE__ << " " << __LINE__ << endl; \ 24 | ( x ).get_ostream()->flush(); 25 | #define LOG_FILE_LINE_AB( a, b ) \ 26 | *( ( a ).get_ostream( b ) ) << __FILE__ << " " << __LINE__ << endl; \ 27 | ( a ).get_ostream()->flush(); 28 | #define LOG_FUNCTION_LINE( x ) \ 29 | *( ( x ).get_ostream() ) << __FUNCTION__ << " " << __LINE__ << endl; \ 30 | ( x ).get_ostream()->flush(); 31 | #define LOG_FUNCTION_LINE_AB( a, b ) \ 32 | *( ( a ).get_ostream( b ) ) << __FUNCTION__ << " " << __LINE__ << endl; \ 33 | ( x ).get_ostream()->flush(); 34 | 35 | namespace Common_tools // Commond tools 36 | { 37 | class File_logger 38 | { 39 | public: 40 | std::map< string, std::ostream * > m_map_file_os; 41 | char m_temp_char[10000]; 42 | string m_temp_string; 43 | string m_save_dir_name = string ( "/home/ziv/data/" ); 44 | 45 | void release() 46 | { 47 | for ( auto it = m_map_file_os.begin(); it != m_map_file_os.end(); it++ ) 48 | { 49 | //cout << "File logger relese ostream, name = [" << it->first << "]"; 50 | it->second->flush(); 51 | ( it->second ) = NULL; 52 | delete it->second ; 53 | //cout << " Done!" < ( "screen", &std::cout ) ); 73 | } 74 | 75 | string version() 76 | { 77 | std::stringstream ss; 78 | ss << "===== This is version of File_logger =====" << endl; 79 | ss << "Version : " << FILE_LOGGER_VERSION << endl; 80 | ss << "Version info : " << FILE_LOGGER_VERSION_INFO << endl; 81 | ss << "Complie date : " << __DATE__ << " " << __TIME__ << endl; 82 | ss << "===== End =====" << endl; 83 | return string ( ss.str() ); 84 | } 85 | 86 | void init ( std::string _file_name, std::string prefix_name = string ( "log" ), int mode = std::ios::out ) 87 | { 88 | std::ofstream* ofs = new std::ofstream(); 89 | sprintf ( m_temp_char, "%s/%s_%s", m_save_dir_name.c_str(), prefix_name.c_str(), _file_name.c_str() ); 90 | ofs->open ( m_temp_char, ios::out ); 91 | 92 | if ( ofs->is_open() ) 93 | { 94 | cout << "Open " << _file_name << " successful." << endl; 95 | m_map_file_os.insert ( std::pair ( prefix_name, ofs ) ); 96 | } 97 | else 98 | { 99 | cout << "Fail to open " << _file_name << endl; 100 | m_map_file_os.insert ( std::pair ( prefix_name, &std::cout ) ); 101 | } 102 | }; 103 | 104 | std::ostream* get_ostream ( std::string prefix_name = string ( "log" ) ) 105 | { 106 | auto it = m_map_file_os.find ( prefix_name ); 107 | 108 | if ( it != m_map_file_os.end() ) 109 | { 110 | return ( it->second ); 111 | } 112 | else // if no exit, create a new one. 113 | { 114 | init ( "tempadd.txt", prefix_name ); 115 | return get_ostream ( prefix_name ); 116 | } 117 | } 118 | 119 | int printf ( const char * fmt, ... ) 120 | { 121 | va_list ap; 122 | char* result = 0; 123 | va_start ( ap, fmt ); 124 | if(vasprintf ( &result, fmt, ap )==0) 125 | { 126 | return 0; 127 | } 128 | //cout << "Fmt = " << fmt <flush(); 134 | return m_temp_string.length(); 135 | } 136 | 137 | }; 138 | }; 139 | #endif 140 | -------------------------------------------------------------------------------- /include/tools/os_compatible.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __OS_COMPATIBLE_HPP__ 2 | #define __OS_COMPATIBLE_HPP__ 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include //need for such like printf(...) 9 | #include 10 | #include 11 | #if defined _MSC_VER 12 | #include 13 | #elif defined __GNUC__ 14 | #include 15 | #include 16 | #endif 17 | namespace Common_tools 18 | { 19 | void create_dir(std::string dir) 20 | { 21 | #if defined _MSC_VER 22 | _mkdir(dir.data()); 23 | #elif defined __GNUC__ 24 | mkdir(dir.data(), 0777); 25 | #endif 26 | } 27 | 28 | // Using asprintf() on windows 29 | // https://stackoverflow.com/questions/40159892/using-asprintf-on-windows 30 | #ifndef _vscprintf 31 | /* For some reason, MSVC fails to honour this #ifndef. */ 32 | /* Hence function renamed to _vscprintf_so(). */ 33 | int _vscprintf_so(const char * format, va_list pargs) { 34 | int retval; 35 | va_list argcopy; 36 | va_copy(argcopy, pargs); 37 | retval = vsnprintf(NULL, 0, format, argcopy); 38 | va_end(argcopy); 39 | return retval; 40 | } 41 | #endif // 42 | 43 | #ifndef vasprintf 44 | int vasprintf(char **strp, const char *fmt, va_list ap) { 45 | int len = _vscprintf_so(fmt, ap); 46 | if (len == -1) return -1; 47 | char *str = (char*)malloc((size_t)len + 1); 48 | if (!str) return -1; 49 | int r = vsnprintf(str, len + 1, fmt, ap); /* "secure" version of vsprintf */ 50 | if (r == -1) return free(str), -1; 51 | *strp = str; 52 | return r; 53 | } 54 | #endif // vasprintf 55 | } 56 | #endif -------------------------------------------------------------------------------- /include/tools/rapidjson/cursorstreamwrapper.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_CURSORSTREAMWRAPPER_H_ 16 | #define RAPIDJSON_CURSORSTREAMWRAPPER_H_ 17 | 18 | #include "stream.h" 19 | 20 | #if defined(__GNUC__) 21 | RAPIDJSON_DIAG_PUSH 22 | RAPIDJSON_DIAG_OFF(effc++) 23 | #endif 24 | 25 | #if defined(_MSC_VER) && _MSC_VER <= 1800 26 | RAPIDJSON_DIAG_PUSH 27 | RAPIDJSON_DIAG_OFF(4702) // unreachable code 28 | RAPIDJSON_DIAG_OFF(4512) // assignment operator could not be generated 29 | #endif 30 | 31 | RAPIDJSON_NAMESPACE_BEGIN 32 | 33 | 34 | //! Cursor stream wrapper for counting line and column number if error exists. 35 | /*! 36 | \tparam InputStream Any stream that implements Stream Concept 37 | */ 38 | template > 39 | class CursorStreamWrapper : public GenericStreamWrapper { 40 | public: 41 | typedef typename Encoding::Ch Ch; 42 | 43 | CursorStreamWrapper(InputStream& is): 44 | GenericStreamWrapper(is), line_(1), col_(0) {} 45 | 46 | // counting line and column number 47 | Ch Take() { 48 | Ch ch = this->is_.Take(); 49 | if(ch == '\n') { 50 | line_ ++; 51 | col_ = 0; 52 | } else { 53 | col_ ++; 54 | } 55 | return ch; 56 | } 57 | 58 | //! Get the error line number, if error exists. 59 | size_t GetLine() const { return line_; } 60 | //! Get the error column number, if error exists. 61 | size_t GetColumn() const { return col_; } 62 | 63 | private: 64 | size_t line_; //!< Current Line 65 | size_t col_; //!< Current Column 66 | }; 67 | 68 | #if defined(_MSC_VER) && _MSC_VER <= 1800 69 | RAPIDJSON_DIAG_POP 70 | #endif 71 | 72 | #if defined(__GNUC__) 73 | RAPIDJSON_DIAG_POP 74 | #endif 75 | 76 | RAPIDJSON_NAMESPACE_END 77 | 78 | #endif // RAPIDJSON_CURSORSTREAMWRAPPER_H_ 79 | -------------------------------------------------------------------------------- /include/tools/rapidjson/error/en.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_ERROR_EN_H_ 16 | #define RAPIDJSON_ERROR_EN_H_ 17 | 18 | #include "error.h" 19 | 20 | #ifdef __clang__ 21 | RAPIDJSON_DIAG_PUSH 22 | RAPIDJSON_DIAG_OFF(switch-enum) 23 | RAPIDJSON_DIAG_OFF(covered-switch-default) 24 | #endif 25 | 26 | RAPIDJSON_NAMESPACE_BEGIN 27 | 28 | //! Maps error code of parsing into error message. 29 | /*! 30 | \ingroup RAPIDJSON_ERRORS 31 | \param parseErrorCode Error code obtained in parsing. 32 | \return the error message. 33 | \note User can make a copy of this function for localization. 34 | Using switch-case is safer for future modification of error codes. 35 | */ 36 | inline const RAPIDJSON_ERROR_CHARTYPE* GetParseError_En(ParseErrorCode parseErrorCode) { 37 | switch (parseErrorCode) { 38 | case kParseErrorNone: return RAPIDJSON_ERROR_STRING("No error."); 39 | 40 | case kParseErrorDocumentEmpty: return RAPIDJSON_ERROR_STRING("The document is empty."); 41 | case kParseErrorDocumentRootNotSingular: return RAPIDJSON_ERROR_STRING("The document root must not be followed by other values."); 42 | 43 | case kParseErrorValueInvalid: return RAPIDJSON_ERROR_STRING("Invalid value."); 44 | 45 | case kParseErrorObjectMissName: return RAPIDJSON_ERROR_STRING("Missing a name for object member."); 46 | case kParseErrorObjectMissColon: return RAPIDJSON_ERROR_STRING("Missing a colon after a name of object member."); 47 | case kParseErrorObjectMissCommaOrCurlyBracket: return RAPIDJSON_ERROR_STRING("Missing a comma or '}' after an object member."); 48 | 49 | case kParseErrorArrayMissCommaOrSquareBracket: return RAPIDJSON_ERROR_STRING("Missing a comma or ']' after an array element."); 50 | 51 | case kParseErrorStringUnicodeEscapeInvalidHex: return RAPIDJSON_ERROR_STRING("Incorrect hex digit after \\u escape in string."); 52 | case kParseErrorStringUnicodeSurrogateInvalid: return RAPIDJSON_ERROR_STRING("The surrogate pair in string is invalid."); 53 | case kParseErrorStringEscapeInvalid: return RAPIDJSON_ERROR_STRING("Invalid escape character in string."); 54 | case kParseErrorStringMissQuotationMark: return RAPIDJSON_ERROR_STRING("Missing a closing quotation mark in string."); 55 | case kParseErrorStringInvalidEncoding: return RAPIDJSON_ERROR_STRING("Invalid encoding in string."); 56 | 57 | case kParseErrorNumberTooBig: return RAPIDJSON_ERROR_STRING("Number too big to be stored in double."); 58 | case kParseErrorNumberMissFraction: return RAPIDJSON_ERROR_STRING("Miss fraction part in number."); 59 | case kParseErrorNumberMissExponent: return RAPIDJSON_ERROR_STRING("Miss exponent in number."); 60 | 61 | case kParseErrorTermination: return RAPIDJSON_ERROR_STRING("Terminate parsing due to Handler error."); 62 | case kParseErrorUnspecificSyntaxError: return RAPIDJSON_ERROR_STRING("Unspecific syntax error."); 63 | 64 | default: return RAPIDJSON_ERROR_STRING("Unknown error."); 65 | } 66 | } 67 | 68 | RAPIDJSON_NAMESPACE_END 69 | 70 | #ifdef __clang__ 71 | RAPIDJSON_DIAG_POP 72 | #endif 73 | 74 | #endif // RAPIDJSON_ERROR_EN_H_ 75 | -------------------------------------------------------------------------------- /include/tools/rapidjson/error/error.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_ERROR_ERROR_H_ 16 | #define RAPIDJSON_ERROR_ERROR_H_ 17 | 18 | #include "../rapidjson.h" 19 | 20 | #ifdef __clang__ 21 | RAPIDJSON_DIAG_PUSH 22 | RAPIDJSON_DIAG_OFF(padded) 23 | #endif 24 | 25 | /*! \file error.h */ 26 | 27 | /*! \defgroup RAPIDJSON_ERRORS RapidJSON error handling */ 28 | 29 | /////////////////////////////////////////////////////////////////////////////// 30 | // RAPIDJSON_ERROR_CHARTYPE 31 | 32 | //! Character type of error messages. 33 | /*! \ingroup RAPIDJSON_ERRORS 34 | The default character type is \c char. 35 | On Windows, user can define this macro as \c TCHAR for supporting both 36 | unicode/non-unicode settings. 37 | */ 38 | #ifndef RAPIDJSON_ERROR_CHARTYPE 39 | #define RAPIDJSON_ERROR_CHARTYPE char 40 | #endif 41 | 42 | /////////////////////////////////////////////////////////////////////////////// 43 | // RAPIDJSON_ERROR_STRING 44 | 45 | //! Macro for converting string literial to \ref RAPIDJSON_ERROR_CHARTYPE[]. 46 | /*! \ingroup RAPIDJSON_ERRORS 47 | By default this conversion macro does nothing. 48 | On Windows, user can define this macro as \c _T(x) for supporting both 49 | unicode/non-unicode settings. 50 | */ 51 | #ifndef RAPIDJSON_ERROR_STRING 52 | #define RAPIDJSON_ERROR_STRING(x) x 53 | #endif 54 | 55 | RAPIDJSON_NAMESPACE_BEGIN 56 | 57 | /////////////////////////////////////////////////////////////////////////////// 58 | // ParseErrorCode 59 | 60 | //! Error code of parsing. 61 | /*! \ingroup RAPIDJSON_ERRORS 62 | \see GenericReader::Parse, GenericReader::GetParseErrorCode 63 | */ 64 | enum ParseErrorCode { 65 | kParseErrorNone = 0, //!< No error. 66 | 67 | kParseErrorDocumentEmpty, //!< The document is empty. 68 | kParseErrorDocumentRootNotSingular, //!< The document root must not follow by other values. 69 | 70 | kParseErrorValueInvalid, //!< Invalid value. 71 | 72 | kParseErrorObjectMissName, //!< Missing a name for object member. 73 | kParseErrorObjectMissColon, //!< Missing a colon after a name of object member. 74 | kParseErrorObjectMissCommaOrCurlyBracket, //!< Missing a comma or '}' after an object member. 75 | 76 | kParseErrorArrayMissCommaOrSquareBracket, //!< Missing a comma or ']' after an array element. 77 | 78 | kParseErrorStringUnicodeEscapeInvalidHex, //!< Incorrect hex digit after \\u escape in string. 79 | kParseErrorStringUnicodeSurrogateInvalid, //!< The surrogate pair in string is invalid. 80 | kParseErrorStringEscapeInvalid, //!< Invalid escape character in string. 81 | kParseErrorStringMissQuotationMark, //!< Missing a closing quotation mark in string. 82 | kParseErrorStringInvalidEncoding, //!< Invalid encoding in string. 83 | 84 | kParseErrorNumberTooBig, //!< Number too big to be stored in double. 85 | kParseErrorNumberMissFraction, //!< Miss fraction part in number. 86 | kParseErrorNumberMissExponent, //!< Miss exponent in number. 87 | 88 | kParseErrorTermination, //!< Parsing was terminated. 89 | kParseErrorUnspecificSyntaxError //!< Unspecific syntax error. 90 | }; 91 | 92 | //! Result of parsing (wraps ParseErrorCode) 93 | /*! 94 | \ingroup RAPIDJSON_ERRORS 95 | \code 96 | Document doc; 97 | ParseResult ok = doc.Parse("[42]"); 98 | if (!ok) { 99 | fprintf(stderr, "JSON parse error: %s (%u)", 100 | GetParseError_En(ok.Code()), ok.Offset()); 101 | exit(EXIT_FAILURE); 102 | } 103 | \endcode 104 | \see GenericReader::Parse, GenericDocument::Parse 105 | */ 106 | struct ParseResult { 107 | //!! Unspecified boolean type 108 | typedef bool (ParseResult::*BooleanType)() const; 109 | public: 110 | //! Default constructor, no error. 111 | ParseResult() : code_(kParseErrorNone), offset_(0) {} 112 | //! Constructor to set an error. 113 | ParseResult(ParseErrorCode code, size_t offset) : code_(code), offset_(offset) {} 114 | 115 | //! Get the error code. 116 | ParseErrorCode Code() const { return code_; } 117 | //! Get the error offset, if \ref IsError(), 0 otherwise. 118 | size_t Offset() const { return offset_; } 119 | 120 | //! Explicit conversion to \c bool, returns \c true, iff !\ref IsError(). 121 | operator BooleanType() const { return !IsError() ? &ParseResult::IsError : NULL; } 122 | //! Whether the result is an error. 123 | bool IsError() const { return code_ != kParseErrorNone; } 124 | 125 | bool operator==(const ParseResult& that) const { return code_ == that.code_; } 126 | bool operator==(ParseErrorCode code) const { return code_ == code; } 127 | friend bool operator==(ParseErrorCode code, const ParseResult & err) { return code == err.code_; } 128 | 129 | bool operator!=(const ParseResult& that) const { return !(*this == that); } 130 | bool operator!=(ParseErrorCode code) const { return !(*this == code); } 131 | friend bool operator!=(ParseErrorCode code, const ParseResult & err) { return err != code; } 132 | 133 | //! Reset error code. 134 | void Clear() { Set(kParseErrorNone); } 135 | //! Update error code and offset. 136 | void Set(ParseErrorCode code, size_t offset = 0) { code_ = code; offset_ = offset; } 137 | 138 | private: 139 | ParseErrorCode code_; 140 | size_t offset_; 141 | }; 142 | 143 | //! Function pointer type of GetParseError(). 144 | /*! \ingroup RAPIDJSON_ERRORS 145 | 146 | This is the prototype for \c GetParseError_X(), where \c X is a locale. 147 | User can dynamically change locale in runtime, e.g.: 148 | \code 149 | GetParseErrorFunc GetParseError = GetParseError_En; // or whatever 150 | const RAPIDJSON_ERROR_CHARTYPE* s = GetParseError(document.GetParseErrorCode()); 151 | \endcode 152 | */ 153 | typedef const RAPIDJSON_ERROR_CHARTYPE* (*GetParseErrorFunc)(ParseErrorCode); 154 | 155 | RAPIDJSON_NAMESPACE_END 156 | 157 | #ifdef __clang__ 158 | RAPIDJSON_DIAG_POP 159 | #endif 160 | 161 | #endif // RAPIDJSON_ERROR_ERROR_H_ 162 | -------------------------------------------------------------------------------- /include/tools/rapidjson/filereadstream.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_FILEREADSTREAM_H_ 16 | #define RAPIDJSON_FILEREADSTREAM_H_ 17 | 18 | #include "stream.h" 19 | #include 20 | 21 | #ifdef __clang__ 22 | RAPIDJSON_DIAG_PUSH 23 | RAPIDJSON_DIAG_OFF(padded) 24 | RAPIDJSON_DIAG_OFF(unreachable-code) 25 | RAPIDJSON_DIAG_OFF(missing-noreturn) 26 | #endif 27 | 28 | RAPIDJSON_NAMESPACE_BEGIN 29 | 30 | //! File byte stream for input using fread(). 31 | /*! 32 | \note implements Stream concept 33 | */ 34 | class FileReadStream { 35 | public: 36 | typedef char Ch; //!< Character type (byte). 37 | 38 | //! Constructor. 39 | /*! 40 | \param fp File pointer opened for read. 41 | \param buffer user-supplied buffer. 42 | \param bufferSize size of buffer in bytes. Must >=4 bytes. 43 | */ 44 | FileReadStream(std::FILE* fp, char* buffer, size_t bufferSize) : fp_(fp), buffer_(buffer), bufferSize_(bufferSize), bufferLast_(0), current_(buffer_), readCount_(0), count_(0), eof_(false) { 45 | RAPIDJSON_ASSERT(fp_ != 0); 46 | RAPIDJSON_ASSERT(bufferSize >= 4); 47 | Read(); 48 | } 49 | 50 | Ch Peek() const { return *current_; } 51 | Ch Take() { Ch c = *current_; Read(); return c; } 52 | size_t Tell() const { return count_ + static_cast(current_ - buffer_); } 53 | 54 | // Not implemented 55 | void Put(Ch) { RAPIDJSON_ASSERT(false); } 56 | void Flush() { RAPIDJSON_ASSERT(false); } 57 | Ch* PutBegin() { RAPIDJSON_ASSERT(false); return 0; } 58 | size_t PutEnd(Ch*) { RAPIDJSON_ASSERT(false); return 0; } 59 | 60 | // For encoding detection only. 61 | const Ch* Peek4() const { 62 | return (current_ + 4 - !eof_ <= bufferLast_) ? current_ : 0; 63 | } 64 | 65 | private: 66 | void Read() { 67 | if (current_ < bufferLast_) 68 | ++current_; 69 | else if (!eof_) { 70 | count_ += readCount_; 71 | readCount_ = std::fread(buffer_, 1, bufferSize_, fp_); 72 | bufferLast_ = buffer_ + readCount_ - 1; 73 | current_ = buffer_; 74 | 75 | if (readCount_ < bufferSize_) { 76 | buffer_[readCount_] = '\0'; 77 | ++bufferLast_; 78 | eof_ = true; 79 | } 80 | } 81 | } 82 | 83 | std::FILE* fp_; 84 | Ch *buffer_; 85 | size_t bufferSize_; 86 | Ch *bufferLast_; 87 | Ch *current_; 88 | size_t readCount_; 89 | size_t count_; //!< Number of characters read 90 | bool eof_; 91 | }; 92 | 93 | RAPIDJSON_NAMESPACE_END 94 | 95 | #ifdef __clang__ 96 | RAPIDJSON_DIAG_POP 97 | #endif 98 | 99 | #endif // RAPIDJSON_FILESTREAM_H_ 100 | -------------------------------------------------------------------------------- /include/tools/rapidjson/filewritestream.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_FILEWRITESTREAM_H_ 16 | #define RAPIDJSON_FILEWRITESTREAM_H_ 17 | 18 | #include "stream.h" 19 | #include 20 | 21 | #ifdef __clang__ 22 | RAPIDJSON_DIAG_PUSH 23 | RAPIDJSON_DIAG_OFF(unreachable-code) 24 | #endif 25 | 26 | RAPIDJSON_NAMESPACE_BEGIN 27 | 28 | //! Wrapper of C file stream for output using fwrite(). 29 | /*! 30 | \note implements Stream concept 31 | */ 32 | class FileWriteStream { 33 | public: 34 | typedef char Ch; //!< Character type. Only support char. 35 | 36 | FileWriteStream(std::FILE* fp, char* buffer, size_t bufferSize) : fp_(fp), buffer_(buffer), bufferEnd_(buffer + bufferSize), current_(buffer_) { 37 | RAPIDJSON_ASSERT(fp_ != 0); 38 | } 39 | 40 | void Put(char c) { 41 | if (current_ >= bufferEnd_) 42 | Flush(); 43 | 44 | *current_++ = c; 45 | } 46 | 47 | void PutN(char c, size_t n) { 48 | size_t avail = static_cast(bufferEnd_ - current_); 49 | while (n > avail) { 50 | std::memset(current_, c, avail); 51 | current_ += avail; 52 | Flush(); 53 | n -= avail; 54 | avail = static_cast(bufferEnd_ - current_); 55 | } 56 | 57 | if (n > 0) { 58 | std::memset(current_, c, n); 59 | current_ += n; 60 | } 61 | } 62 | 63 | void Flush() { 64 | if (current_ != buffer_) { 65 | size_t result = std::fwrite(buffer_, 1, static_cast(current_ - buffer_), fp_); 66 | if (result < static_cast(current_ - buffer_)) { 67 | // failure deliberately ignored at this time 68 | // added to avoid warn_unused_result build errors 69 | } 70 | current_ = buffer_; 71 | } 72 | } 73 | 74 | // Not implemented 75 | char Peek() const { RAPIDJSON_ASSERT(false); return 0; } 76 | char Take() { RAPIDJSON_ASSERT(false); return 0; } 77 | size_t Tell() const { RAPIDJSON_ASSERT(false); return 0; } 78 | char* PutBegin() { RAPIDJSON_ASSERT(false); return 0; } 79 | size_t PutEnd(char*) { RAPIDJSON_ASSERT(false); return 0; } 80 | 81 | private: 82 | // Prohibit copy constructor & assignment operator. 83 | FileWriteStream(const FileWriteStream&); 84 | FileWriteStream& operator=(const FileWriteStream&); 85 | 86 | std::FILE* fp_; 87 | char *buffer_; 88 | char *bufferEnd_; 89 | char *current_; 90 | }; 91 | 92 | //! Implement specialized version of PutN() with memset() for better performance. 93 | template<> 94 | inline void PutN(FileWriteStream& stream, char c, size_t n) { 95 | stream.PutN(c, n); 96 | } 97 | 98 | RAPIDJSON_NAMESPACE_END 99 | 100 | #ifdef __clang__ 101 | RAPIDJSON_DIAG_POP 102 | #endif 103 | 104 | #endif // RAPIDJSON_FILESTREAM_H_ 105 | -------------------------------------------------------------------------------- /include/tools/rapidjson/fwd.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_FWD_H_ 16 | #define RAPIDJSON_FWD_H_ 17 | 18 | #include "rapidjson.h" 19 | 20 | RAPIDJSON_NAMESPACE_BEGIN 21 | 22 | // encodings.h 23 | 24 | template struct UTF8; 25 | template struct UTF16; 26 | template struct UTF16BE; 27 | template struct UTF16LE; 28 | template struct UTF32; 29 | template struct UTF32BE; 30 | template struct UTF32LE; 31 | template struct ASCII; 32 | template struct AutoUTF; 33 | 34 | template 35 | struct Transcoder; 36 | 37 | // allocators.h 38 | 39 | class CrtAllocator; 40 | 41 | template 42 | class MemoryPoolAllocator; 43 | 44 | // stream.h 45 | 46 | template 47 | struct GenericStringStream; 48 | 49 | typedef GenericStringStream > StringStream; 50 | 51 | template 52 | struct GenericInsituStringStream; 53 | 54 | typedef GenericInsituStringStream > InsituStringStream; 55 | 56 | // stringbuffer.h 57 | 58 | template 59 | class GenericStringBuffer; 60 | 61 | typedef GenericStringBuffer, CrtAllocator> StringBuffer; 62 | 63 | // filereadstream.h 64 | 65 | class FileReadStream; 66 | 67 | // filewritestream.h 68 | 69 | class FileWriteStream; 70 | 71 | // memorybuffer.h 72 | 73 | template 74 | struct GenericMemoryBuffer; 75 | 76 | typedef GenericMemoryBuffer MemoryBuffer; 77 | 78 | // memorystream.h 79 | 80 | struct MemoryStream; 81 | 82 | // reader.h 83 | 84 | template 85 | struct BaseReaderHandler; 86 | 87 | template 88 | class GenericReader; 89 | 90 | typedef GenericReader, UTF8, CrtAllocator> Reader; 91 | 92 | // writer.h 93 | 94 | template 95 | class Writer; 96 | 97 | // prettywriter.h 98 | 99 | template 100 | class PrettyWriter; 101 | 102 | // document.h 103 | 104 | template 105 | struct GenericMember; 106 | 107 | template 108 | class GenericMemberIterator; 109 | 110 | template 111 | struct GenericStringRef; 112 | 113 | template 114 | class GenericValue; 115 | 116 | typedef GenericValue, MemoryPoolAllocator > Value; 117 | 118 | template 119 | class GenericDocument; 120 | 121 | typedef GenericDocument, MemoryPoolAllocator, CrtAllocator> Document; 122 | 123 | // pointer.h 124 | 125 | template 126 | class GenericPointer; 127 | 128 | typedef GenericPointer Pointer; 129 | 130 | // schema.h 131 | 132 | template 133 | class IGenericRemoteSchemaDocumentProvider; 134 | 135 | template 136 | class GenericSchemaDocument; 137 | 138 | typedef GenericSchemaDocument SchemaDocument; 139 | typedef IGenericRemoteSchemaDocumentProvider IRemoteSchemaDocumentProvider; 140 | 141 | template < 142 | typename SchemaDocumentType, 143 | typename OutputHandler, 144 | typename StateAllocator> 145 | class GenericSchemaValidator; 146 | 147 | typedef GenericSchemaValidator, void>, CrtAllocator> SchemaValidator; 148 | 149 | RAPIDJSON_NAMESPACE_END 150 | 151 | #endif // RAPIDJSON_RAPIDJSONFWD_H_ 152 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/biginteger.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_BIGINTEGER_H_ 16 | #define RAPIDJSON_BIGINTEGER_H_ 17 | 18 | #include "../rapidjson.h" 19 | 20 | #if defined(_MSC_VER) && !__INTEL_COMPILER && defined(_M_AMD64) 21 | #include // for _umul128 22 | #pragma intrinsic(_umul128) 23 | #endif 24 | 25 | RAPIDJSON_NAMESPACE_BEGIN 26 | namespace internal { 27 | 28 | class BigInteger { 29 | public: 30 | typedef uint64_t Type; 31 | 32 | BigInteger(const BigInteger& rhs) : count_(rhs.count_) { 33 | std::memcpy(digits_, rhs.digits_, count_ * sizeof(Type)); 34 | } 35 | 36 | explicit BigInteger(uint64_t u) : count_(1) { 37 | digits_[0] = u; 38 | } 39 | 40 | BigInteger(const char* decimals, size_t length) : count_(1) { 41 | RAPIDJSON_ASSERT(length > 0); 42 | digits_[0] = 0; 43 | size_t i = 0; 44 | const size_t kMaxDigitPerIteration = 19; // 2^64 = 18446744073709551616 > 10^19 45 | while (length >= kMaxDigitPerIteration) { 46 | AppendDecimal64(decimals + i, decimals + i + kMaxDigitPerIteration); 47 | length -= kMaxDigitPerIteration; 48 | i += kMaxDigitPerIteration; 49 | } 50 | 51 | if (length > 0) 52 | AppendDecimal64(decimals + i, decimals + i + length); 53 | } 54 | 55 | BigInteger& operator=(const BigInteger &rhs) 56 | { 57 | if (this != &rhs) { 58 | count_ = rhs.count_; 59 | std::memcpy(digits_, rhs.digits_, count_ * sizeof(Type)); 60 | } 61 | return *this; 62 | } 63 | 64 | BigInteger& operator=(uint64_t u) { 65 | digits_[0] = u; 66 | count_ = 1; 67 | return *this; 68 | } 69 | 70 | BigInteger& operator+=(uint64_t u) { 71 | Type backup = digits_[0]; 72 | digits_[0] += u; 73 | for (size_t i = 0; i < count_ - 1; i++) { 74 | if (digits_[i] >= backup) 75 | return *this; // no carry 76 | backup = digits_[i + 1]; 77 | digits_[i + 1] += 1; 78 | } 79 | 80 | // Last carry 81 | if (digits_[count_ - 1] < backup) 82 | PushBack(1); 83 | 84 | return *this; 85 | } 86 | 87 | BigInteger& operator*=(uint64_t u) { 88 | if (u == 0) return *this = 0; 89 | if (u == 1) return *this; 90 | if (*this == 1) return *this = u; 91 | 92 | uint64_t k = 0; 93 | for (size_t i = 0; i < count_; i++) { 94 | uint64_t hi; 95 | digits_[i] = MulAdd64(digits_[i], u, k, &hi); 96 | k = hi; 97 | } 98 | 99 | if (k > 0) 100 | PushBack(k); 101 | 102 | return *this; 103 | } 104 | 105 | BigInteger& operator*=(uint32_t u) { 106 | if (u == 0) return *this = 0; 107 | if (u == 1) return *this; 108 | if (*this == 1) return *this = u; 109 | 110 | uint64_t k = 0; 111 | for (size_t i = 0; i < count_; i++) { 112 | const uint64_t c = digits_[i] >> 32; 113 | const uint64_t d = digits_[i] & 0xFFFFFFFF; 114 | const uint64_t uc = u * c; 115 | const uint64_t ud = u * d; 116 | const uint64_t p0 = ud + k; 117 | const uint64_t p1 = uc + (p0 >> 32); 118 | digits_[i] = (p0 & 0xFFFFFFFF) | (p1 << 32); 119 | k = p1 >> 32; 120 | } 121 | 122 | if (k > 0) 123 | PushBack(k); 124 | 125 | return *this; 126 | } 127 | 128 | BigInteger& operator<<=(size_t shift) { 129 | if (IsZero() || shift == 0) return *this; 130 | 131 | size_t offset = shift / kTypeBit; 132 | size_t interShift = shift % kTypeBit; 133 | RAPIDJSON_ASSERT(count_ + offset <= kCapacity); 134 | 135 | if (interShift == 0) { 136 | std::memmove(digits_ + offset, digits_, count_ * sizeof(Type)); 137 | count_ += offset; 138 | } 139 | else { 140 | digits_[count_] = 0; 141 | for (size_t i = count_; i > 0; i--) 142 | digits_[i + offset] = (digits_[i] << interShift) | (digits_[i - 1] >> (kTypeBit - interShift)); 143 | digits_[offset] = digits_[0] << interShift; 144 | count_ += offset; 145 | if (digits_[count_]) 146 | count_++; 147 | } 148 | 149 | std::memset(digits_, 0, offset * sizeof(Type)); 150 | 151 | return *this; 152 | } 153 | 154 | bool operator==(const BigInteger& rhs) const { 155 | return count_ == rhs.count_ && std::memcmp(digits_, rhs.digits_, count_ * sizeof(Type)) == 0; 156 | } 157 | 158 | bool operator==(const Type rhs) const { 159 | return count_ == 1 && digits_[0] == rhs; 160 | } 161 | 162 | BigInteger& MultiplyPow5(unsigned exp) { 163 | static const uint32_t kPow5[12] = { 164 | 5, 165 | 5 * 5, 166 | 5 * 5 * 5, 167 | 5 * 5 * 5 * 5, 168 | 5 * 5 * 5 * 5 * 5, 169 | 5 * 5 * 5 * 5 * 5 * 5, 170 | 5 * 5 * 5 * 5 * 5 * 5 * 5, 171 | 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5, 172 | 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5, 173 | 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5, 174 | 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5, 175 | 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 * 5 176 | }; 177 | if (exp == 0) return *this; 178 | for (; exp >= 27; exp -= 27) *this *= RAPIDJSON_UINT64_C2(0X6765C793, 0XFA10079D); // 5^27 179 | for (; exp >= 13; exp -= 13) *this *= static_cast(1220703125u); // 5^13 180 | if (exp > 0) *this *= kPow5[exp - 1]; 181 | return *this; 182 | } 183 | 184 | // Compute absolute difference of this and rhs. 185 | // Assume this != rhs 186 | bool Difference(const BigInteger& rhs, BigInteger* out) const { 187 | int cmp = Compare(rhs); 188 | RAPIDJSON_ASSERT(cmp != 0); 189 | const BigInteger *a, *b; // Makes a > b 190 | bool ret; 191 | if (cmp < 0) { a = &rhs; b = this; ret = true; } 192 | else { a = this; b = &rhs; ret = false; } 193 | 194 | Type borrow = 0; 195 | for (size_t i = 0; i < a->count_; i++) { 196 | Type d = a->digits_[i] - borrow; 197 | if (i < b->count_) 198 | d -= b->digits_[i]; 199 | borrow = (d > a->digits_[i]) ? 1 : 0; 200 | out->digits_[i] = d; 201 | if (d != 0) 202 | out->count_ = i + 1; 203 | } 204 | 205 | return ret; 206 | } 207 | 208 | int Compare(const BigInteger& rhs) const { 209 | if (count_ != rhs.count_) 210 | return count_ < rhs.count_ ? -1 : 1; 211 | 212 | for (size_t i = count_; i-- > 0;) 213 | if (digits_[i] != rhs.digits_[i]) 214 | return digits_[i] < rhs.digits_[i] ? -1 : 1; 215 | 216 | return 0; 217 | } 218 | 219 | size_t GetCount() const { return count_; } 220 | Type GetDigit(size_t index) const { RAPIDJSON_ASSERT(index < count_); return digits_[index]; } 221 | bool IsZero() const { return count_ == 1 && digits_[0] == 0; } 222 | 223 | private: 224 | void AppendDecimal64(const char* begin, const char* end) { 225 | uint64_t u = ParseUint64(begin, end); 226 | if (IsZero()) 227 | *this = u; 228 | else { 229 | unsigned exp = static_cast(end - begin); 230 | (MultiplyPow5(exp) <<= exp) += u; // *this = *this * 10^exp + u 231 | } 232 | } 233 | 234 | void PushBack(Type digit) { 235 | RAPIDJSON_ASSERT(count_ < kCapacity); 236 | digits_[count_++] = digit; 237 | } 238 | 239 | static uint64_t ParseUint64(const char* begin, const char* end) { 240 | uint64_t r = 0; 241 | for (const char* p = begin; p != end; ++p) { 242 | RAPIDJSON_ASSERT(*p >= '0' && *p <= '9'); 243 | r = r * 10u + static_cast(*p - '0'); 244 | } 245 | return r; 246 | } 247 | 248 | // Assume a * b + k < 2^128 249 | static uint64_t MulAdd64(uint64_t a, uint64_t b, uint64_t k, uint64_t* outHigh) { 250 | #if defined(_MSC_VER) && defined(_M_AMD64) 251 | uint64_t low = _umul128(a, b, outHigh) + k; 252 | if (low < k) 253 | (*outHigh)++; 254 | return low; 255 | #elif (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) && defined(__x86_64__) 256 | __extension__ typedef unsigned __int128 uint128; 257 | uint128 p = static_cast(a) * static_cast(b); 258 | p += k; 259 | *outHigh = static_cast(p >> 64); 260 | return static_cast(p); 261 | #else 262 | const uint64_t a0 = a & 0xFFFFFFFF, a1 = a >> 32, b0 = b & 0xFFFFFFFF, b1 = b >> 32; 263 | uint64_t x0 = a0 * b0, x1 = a0 * b1, x2 = a1 * b0, x3 = a1 * b1; 264 | x1 += (x0 >> 32); // can't give carry 265 | x1 += x2; 266 | if (x1 < x2) 267 | x3 += (static_cast(1) << 32); 268 | uint64_t lo = (x1 << 32) + (x0 & 0xFFFFFFFF); 269 | uint64_t hi = x3 + (x1 >> 32); 270 | 271 | lo += k; 272 | if (lo < k) 273 | hi++; 274 | *outHigh = hi; 275 | return lo; 276 | #endif 277 | } 278 | 279 | static const size_t kBitCount = 3328; // 64bit * 54 > 10^1000 280 | static const size_t kCapacity = kBitCount / sizeof(Type); 281 | static const size_t kTypeBit = sizeof(Type) * 8; 282 | 283 | Type digits_[kCapacity]; 284 | size_t count_; 285 | }; 286 | 287 | } // namespace internal 288 | RAPIDJSON_NAMESPACE_END 289 | 290 | #endif // RAPIDJSON_BIGINTEGER_H_ 291 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/dtoa.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | // This is a C++ header-only implementation of Grisu2 algorithm from the publication: 16 | // Loitsch, Florian. "Printing floating-point numbers quickly and accurately with 17 | // integers." ACM Sigplan Notices 45.6 (2010): 233-243. 18 | 19 | #ifndef RAPIDJSON_DTOA_ 20 | #define RAPIDJSON_DTOA_ 21 | 22 | #include "itoa.h" // GetDigitsLut() 23 | #include "diyfp.h" 24 | #include "ieee754.h" 25 | 26 | RAPIDJSON_NAMESPACE_BEGIN 27 | namespace internal { 28 | 29 | #ifdef __GNUC__ 30 | RAPIDJSON_DIAG_PUSH 31 | RAPIDJSON_DIAG_OFF(effc++) 32 | RAPIDJSON_DIAG_OFF(array-bounds) // some gcc versions generate wrong warnings https://gcc.gnu.org/bugzilla/show_bug.cgi?id=59124 33 | #endif 34 | 35 | inline void GrisuRound(char* buffer, int len, uint64_t delta, uint64_t rest, uint64_t ten_kappa, uint64_t wp_w) { 36 | while (rest < wp_w && delta - rest >= ten_kappa && 37 | (rest + ten_kappa < wp_w || /// closer 38 | wp_w - rest > rest + ten_kappa - wp_w)) { 39 | buffer[len - 1]--; 40 | rest += ten_kappa; 41 | } 42 | } 43 | 44 | inline int CountDecimalDigit32(uint32_t n) { 45 | // Simple pure C++ implementation was faster than __builtin_clz version in this situation. 46 | if (n < 10) return 1; 47 | if (n < 100) return 2; 48 | if (n < 1000) return 3; 49 | if (n < 10000) return 4; 50 | if (n < 100000) return 5; 51 | if (n < 1000000) return 6; 52 | if (n < 10000000) return 7; 53 | if (n < 100000000) return 8; 54 | // Will not reach 10 digits in DigitGen() 55 | //if (n < 1000000000) return 9; 56 | //return 10; 57 | return 9; 58 | } 59 | 60 | inline void DigitGen(const DiyFp& W, const DiyFp& Mp, uint64_t delta, char* buffer, int* len, int* K) { 61 | static const uint32_t kPow10[] = { 1, 10, 100, 1000, 10000, 100000, 1000000, 10000000, 100000000, 1000000000 }; 62 | const DiyFp one(uint64_t(1) << -Mp.e, Mp.e); 63 | const DiyFp wp_w = Mp - W; 64 | uint32_t p1 = static_cast(Mp.f >> -one.e); 65 | uint64_t p2 = Mp.f & (one.f - 1); 66 | int kappa = CountDecimalDigit32(p1); // kappa in [0, 9] 67 | *len = 0; 68 | 69 | while (kappa > 0) { 70 | uint32_t d = 0; 71 | switch (kappa) { 72 | case 9: d = p1 / 100000000; p1 %= 100000000; break; 73 | case 8: d = p1 / 10000000; p1 %= 10000000; break; 74 | case 7: d = p1 / 1000000; p1 %= 1000000; break; 75 | case 6: d = p1 / 100000; p1 %= 100000; break; 76 | case 5: d = p1 / 10000; p1 %= 10000; break; 77 | case 4: d = p1 / 1000; p1 %= 1000; break; 78 | case 3: d = p1 / 100; p1 %= 100; break; 79 | case 2: d = p1 / 10; p1 %= 10; break; 80 | case 1: d = p1; p1 = 0; break; 81 | default:; 82 | } 83 | if (d || *len) 84 | buffer[(*len)++] = static_cast('0' + static_cast(d)); 85 | kappa--; 86 | uint64_t tmp = (static_cast(p1) << -one.e) + p2; 87 | if (tmp <= delta) { 88 | *K += kappa; 89 | GrisuRound(buffer, *len, delta, tmp, static_cast(kPow10[kappa]) << -one.e, wp_w.f); 90 | return; 91 | } 92 | } 93 | 94 | // kappa = 0 95 | for (;;) { 96 | p2 *= 10; 97 | delta *= 10; 98 | char d = static_cast(p2 >> -one.e); 99 | if (d || *len) 100 | buffer[(*len)++] = static_cast('0' + d); 101 | p2 &= one.f - 1; 102 | kappa--; 103 | if (p2 < delta) { 104 | *K += kappa; 105 | int index = -kappa; 106 | GrisuRound(buffer, *len, delta, p2, one.f, wp_w.f * (index < 9 ? kPow10[index] : 0)); 107 | return; 108 | } 109 | } 110 | } 111 | 112 | inline void Grisu2(double value, char* buffer, int* length, int* K) { 113 | const DiyFp v(value); 114 | DiyFp w_m, w_p; 115 | v.NormalizedBoundaries(&w_m, &w_p); 116 | 117 | const DiyFp c_mk = GetCachedPower(w_p.e, K); 118 | const DiyFp W = v.Normalize() * c_mk; 119 | DiyFp Wp = w_p * c_mk; 120 | DiyFp Wm = w_m * c_mk; 121 | Wm.f++; 122 | Wp.f--; 123 | DigitGen(W, Wp, Wp.f - Wm.f, buffer, length, K); 124 | } 125 | 126 | inline char* WriteExponent(int K, char* buffer) { 127 | if (K < 0) { 128 | *buffer++ = '-'; 129 | K = -K; 130 | } 131 | 132 | if (K >= 100) { 133 | *buffer++ = static_cast('0' + static_cast(K / 100)); 134 | K %= 100; 135 | const char* d = GetDigitsLut() + K * 2; 136 | *buffer++ = d[0]; 137 | *buffer++ = d[1]; 138 | } 139 | else if (K >= 10) { 140 | const char* d = GetDigitsLut() + K * 2; 141 | *buffer++ = d[0]; 142 | *buffer++ = d[1]; 143 | } 144 | else 145 | *buffer++ = static_cast('0' + static_cast(K)); 146 | 147 | return buffer; 148 | } 149 | 150 | inline char* Prettify(char* buffer, int length, int k, int maxDecimalPlaces) { 151 | const int kk = length + k; // 10^(kk-1) <= v < 10^kk 152 | 153 | if (0 <= k && kk <= 21) { 154 | // 1234e7 -> 12340000000 155 | for (int i = length; i < kk; i++) 156 | buffer[i] = '0'; 157 | buffer[kk] = '.'; 158 | buffer[kk + 1] = '0'; 159 | return &buffer[kk + 2]; 160 | } 161 | else if (0 < kk && kk <= 21) { 162 | // 1234e-2 -> 12.34 163 | std::memmove(&buffer[kk + 1], &buffer[kk], static_cast(length - kk)); 164 | buffer[kk] = '.'; 165 | if (0 > k + maxDecimalPlaces) { 166 | // When maxDecimalPlaces = 2, 1.2345 -> 1.23, 1.102 -> 1.1 167 | // Remove extra trailing zeros (at least one) after truncation. 168 | for (int i = kk + maxDecimalPlaces; i > kk + 1; i--) 169 | if (buffer[i] != '0') 170 | return &buffer[i + 1]; 171 | return &buffer[kk + 2]; // Reserve one zero 172 | } 173 | else 174 | return &buffer[length + 1]; 175 | } 176 | else if (-6 < kk && kk <= 0) { 177 | // 1234e-6 -> 0.001234 178 | const int offset = 2 - kk; 179 | std::memmove(&buffer[offset], &buffer[0], static_cast(length)); 180 | buffer[0] = '0'; 181 | buffer[1] = '.'; 182 | for (int i = 2; i < offset; i++) 183 | buffer[i] = '0'; 184 | if (length - kk > maxDecimalPlaces) { 185 | // When maxDecimalPlaces = 2, 0.123 -> 0.12, 0.102 -> 0.1 186 | // Remove extra trailing zeros (at least one) after truncation. 187 | for (int i = maxDecimalPlaces + 1; i > 2; i--) 188 | if (buffer[i] != '0') 189 | return &buffer[i + 1]; 190 | return &buffer[3]; // Reserve one zero 191 | } 192 | else 193 | return &buffer[length + offset]; 194 | } 195 | else if (kk < -maxDecimalPlaces) { 196 | // Truncate to zero 197 | buffer[0] = '0'; 198 | buffer[1] = '.'; 199 | buffer[2] = '0'; 200 | return &buffer[3]; 201 | } 202 | else if (length == 1) { 203 | // 1e30 204 | buffer[1] = 'e'; 205 | return WriteExponent(kk - 1, &buffer[2]); 206 | } 207 | else { 208 | // 1234e30 -> 1.234e33 209 | std::memmove(&buffer[2], &buffer[1], static_cast(length - 1)); 210 | buffer[1] = '.'; 211 | buffer[length + 1] = 'e'; 212 | return WriteExponent(kk - 1, &buffer[0 + length + 2]); 213 | } 214 | } 215 | 216 | inline char* dtoa(double value, char* buffer, int maxDecimalPlaces = 324) { 217 | RAPIDJSON_ASSERT(maxDecimalPlaces >= 1); 218 | Double d(value); 219 | if (d.IsZero()) { 220 | if (d.Sign()) 221 | *buffer++ = '-'; // -0.0, Issue #289 222 | buffer[0] = '0'; 223 | buffer[1] = '.'; 224 | buffer[2] = '0'; 225 | return &buffer[3]; 226 | } 227 | else { 228 | if (value < 0) { 229 | *buffer++ = '-'; 230 | value = -value; 231 | } 232 | int length, K; 233 | Grisu2(value, buffer, &length, &K); 234 | return Prettify(buffer, length, K, maxDecimalPlaces); 235 | } 236 | } 237 | 238 | #ifdef __GNUC__ 239 | RAPIDJSON_DIAG_POP 240 | #endif 241 | 242 | } // namespace internal 243 | RAPIDJSON_NAMESPACE_END 244 | 245 | #endif // RAPIDJSON_DTOA_ 246 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/ieee754.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_IEEE754_ 16 | #define RAPIDJSON_IEEE754_ 17 | 18 | #include "../rapidjson.h" 19 | 20 | RAPIDJSON_NAMESPACE_BEGIN 21 | namespace internal { 22 | 23 | class Double { 24 | public: 25 | Double() {} 26 | Double(double d) : d_(d) {} 27 | Double(uint64_t u) : u_(u) {} 28 | 29 | double Value() const { return d_; } 30 | uint64_t Uint64Value() const { return u_; } 31 | 32 | double NextPositiveDouble() const { 33 | RAPIDJSON_ASSERT(!Sign()); 34 | return Double(u_ + 1).Value(); 35 | } 36 | 37 | bool Sign() const { return (u_ & kSignMask) != 0; } 38 | uint64_t Significand() const { return u_ & kSignificandMask; } 39 | int Exponent() const { return static_cast(((u_ & kExponentMask) >> kSignificandSize) - kExponentBias); } 40 | 41 | bool IsNan() const { return (u_ & kExponentMask) == kExponentMask && Significand() != 0; } 42 | bool IsInf() const { return (u_ & kExponentMask) == kExponentMask && Significand() == 0; } 43 | bool IsNanOrInf() const { return (u_ & kExponentMask) == kExponentMask; } 44 | bool IsNormal() const { return (u_ & kExponentMask) != 0 || Significand() == 0; } 45 | bool IsZero() const { return (u_ & (kExponentMask | kSignificandMask)) == 0; } 46 | 47 | uint64_t IntegerSignificand() const { return IsNormal() ? Significand() | kHiddenBit : Significand(); } 48 | int IntegerExponent() const { return (IsNormal() ? Exponent() : kDenormalExponent) - kSignificandSize; } 49 | uint64_t ToBias() const { return (u_ & kSignMask) ? ~u_ + 1 : u_ | kSignMask; } 50 | 51 | static int EffectiveSignificandSize(int order) { 52 | if (order >= -1021) 53 | return 53; 54 | else if (order <= -1074) 55 | return 0; 56 | else 57 | return order + 1074; 58 | } 59 | 60 | private: 61 | static const int kSignificandSize = 52; 62 | static const int kExponentBias = 0x3FF; 63 | static const int kDenormalExponent = 1 - kExponentBias; 64 | static const uint64_t kSignMask = RAPIDJSON_UINT64_C2(0x80000000, 0x00000000); 65 | static const uint64_t kExponentMask = RAPIDJSON_UINT64_C2(0x7FF00000, 0x00000000); 66 | static const uint64_t kSignificandMask = RAPIDJSON_UINT64_C2(0x000FFFFF, 0xFFFFFFFF); 67 | static const uint64_t kHiddenBit = RAPIDJSON_UINT64_C2(0x00100000, 0x00000000); 68 | 69 | union { 70 | double d_; 71 | uint64_t u_; 72 | }; 73 | }; 74 | 75 | } // namespace internal 76 | RAPIDJSON_NAMESPACE_END 77 | 78 | #endif // RAPIDJSON_IEEE754_ 79 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/itoa.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_ITOA_ 16 | #define RAPIDJSON_ITOA_ 17 | 18 | #include "../rapidjson.h" 19 | 20 | RAPIDJSON_NAMESPACE_BEGIN 21 | namespace internal { 22 | 23 | inline const char* GetDigitsLut() { 24 | static const char cDigitsLut[200] = { 25 | '0','0','0','1','0','2','0','3','0','4','0','5','0','6','0','7','0','8','0','9', 26 | '1','0','1','1','1','2','1','3','1','4','1','5','1','6','1','7','1','8','1','9', 27 | '2','0','2','1','2','2','2','3','2','4','2','5','2','6','2','7','2','8','2','9', 28 | '3','0','3','1','3','2','3','3','3','4','3','5','3','6','3','7','3','8','3','9', 29 | '4','0','4','1','4','2','4','3','4','4','4','5','4','6','4','7','4','8','4','9', 30 | '5','0','5','1','5','2','5','3','5','4','5','5','5','6','5','7','5','8','5','9', 31 | '6','0','6','1','6','2','6','3','6','4','6','5','6','6','6','7','6','8','6','9', 32 | '7','0','7','1','7','2','7','3','7','4','7','5','7','6','7','7','7','8','7','9', 33 | '8','0','8','1','8','2','8','3','8','4','8','5','8','6','8','7','8','8','8','9', 34 | '9','0','9','1','9','2','9','3','9','4','9','5','9','6','9','7','9','8','9','9' 35 | }; 36 | return cDigitsLut; 37 | } 38 | 39 | inline char* u32toa(uint32_t value, char* buffer) { 40 | RAPIDJSON_ASSERT(buffer != 0); 41 | 42 | const char* cDigitsLut = GetDigitsLut(); 43 | 44 | if (value < 10000) { 45 | const uint32_t d1 = (value / 100) << 1; 46 | const uint32_t d2 = (value % 100) << 1; 47 | 48 | if (value >= 1000) 49 | *buffer++ = cDigitsLut[d1]; 50 | if (value >= 100) 51 | *buffer++ = cDigitsLut[d1 + 1]; 52 | if (value >= 10) 53 | *buffer++ = cDigitsLut[d2]; 54 | *buffer++ = cDigitsLut[d2 + 1]; 55 | } 56 | else if (value < 100000000) { 57 | // value = bbbbcccc 58 | const uint32_t b = value / 10000; 59 | const uint32_t c = value % 10000; 60 | 61 | const uint32_t d1 = (b / 100) << 1; 62 | const uint32_t d2 = (b % 100) << 1; 63 | 64 | const uint32_t d3 = (c / 100) << 1; 65 | const uint32_t d4 = (c % 100) << 1; 66 | 67 | if (value >= 10000000) 68 | *buffer++ = cDigitsLut[d1]; 69 | if (value >= 1000000) 70 | *buffer++ = cDigitsLut[d1 + 1]; 71 | if (value >= 100000) 72 | *buffer++ = cDigitsLut[d2]; 73 | *buffer++ = cDigitsLut[d2 + 1]; 74 | 75 | *buffer++ = cDigitsLut[d3]; 76 | *buffer++ = cDigitsLut[d3 + 1]; 77 | *buffer++ = cDigitsLut[d4]; 78 | *buffer++ = cDigitsLut[d4 + 1]; 79 | } 80 | else { 81 | // value = aabbbbcccc in decimal 82 | 83 | const uint32_t a = value / 100000000; // 1 to 42 84 | value %= 100000000; 85 | 86 | if (a >= 10) { 87 | const unsigned i = a << 1; 88 | *buffer++ = cDigitsLut[i]; 89 | *buffer++ = cDigitsLut[i + 1]; 90 | } 91 | else 92 | *buffer++ = static_cast('0' + static_cast(a)); 93 | 94 | const uint32_t b = value / 10000; // 0 to 9999 95 | const uint32_t c = value % 10000; // 0 to 9999 96 | 97 | const uint32_t d1 = (b / 100) << 1; 98 | const uint32_t d2 = (b % 100) << 1; 99 | 100 | const uint32_t d3 = (c / 100) << 1; 101 | const uint32_t d4 = (c % 100) << 1; 102 | 103 | *buffer++ = cDigitsLut[d1]; 104 | *buffer++ = cDigitsLut[d1 + 1]; 105 | *buffer++ = cDigitsLut[d2]; 106 | *buffer++ = cDigitsLut[d2 + 1]; 107 | *buffer++ = cDigitsLut[d3]; 108 | *buffer++ = cDigitsLut[d3 + 1]; 109 | *buffer++ = cDigitsLut[d4]; 110 | *buffer++ = cDigitsLut[d4 + 1]; 111 | } 112 | return buffer; 113 | } 114 | 115 | inline char* i32toa(int32_t value, char* buffer) { 116 | RAPIDJSON_ASSERT(buffer != 0); 117 | uint32_t u = static_cast(value); 118 | if (value < 0) { 119 | *buffer++ = '-'; 120 | u = ~u + 1; 121 | } 122 | 123 | return u32toa(u, buffer); 124 | } 125 | 126 | inline char* u64toa(uint64_t value, char* buffer) { 127 | RAPIDJSON_ASSERT(buffer != 0); 128 | const char* cDigitsLut = GetDigitsLut(); 129 | const uint64_t kTen8 = 100000000; 130 | const uint64_t kTen9 = kTen8 * 10; 131 | const uint64_t kTen10 = kTen8 * 100; 132 | const uint64_t kTen11 = kTen8 * 1000; 133 | const uint64_t kTen12 = kTen8 * 10000; 134 | const uint64_t kTen13 = kTen8 * 100000; 135 | const uint64_t kTen14 = kTen8 * 1000000; 136 | const uint64_t kTen15 = kTen8 * 10000000; 137 | const uint64_t kTen16 = kTen8 * kTen8; 138 | 139 | if (value < kTen8) { 140 | uint32_t v = static_cast(value); 141 | if (v < 10000) { 142 | const uint32_t d1 = (v / 100) << 1; 143 | const uint32_t d2 = (v % 100) << 1; 144 | 145 | if (v >= 1000) 146 | *buffer++ = cDigitsLut[d1]; 147 | if (v >= 100) 148 | *buffer++ = cDigitsLut[d1 + 1]; 149 | if (v >= 10) 150 | *buffer++ = cDigitsLut[d2]; 151 | *buffer++ = cDigitsLut[d2 + 1]; 152 | } 153 | else { 154 | // value = bbbbcccc 155 | const uint32_t b = v / 10000; 156 | const uint32_t c = v % 10000; 157 | 158 | const uint32_t d1 = (b / 100) << 1; 159 | const uint32_t d2 = (b % 100) << 1; 160 | 161 | const uint32_t d3 = (c / 100) << 1; 162 | const uint32_t d4 = (c % 100) << 1; 163 | 164 | if (value >= 10000000) 165 | *buffer++ = cDigitsLut[d1]; 166 | if (value >= 1000000) 167 | *buffer++ = cDigitsLut[d1 + 1]; 168 | if (value >= 100000) 169 | *buffer++ = cDigitsLut[d2]; 170 | *buffer++ = cDigitsLut[d2 + 1]; 171 | 172 | *buffer++ = cDigitsLut[d3]; 173 | *buffer++ = cDigitsLut[d3 + 1]; 174 | *buffer++ = cDigitsLut[d4]; 175 | *buffer++ = cDigitsLut[d4 + 1]; 176 | } 177 | } 178 | else if (value < kTen16) { 179 | const uint32_t v0 = static_cast(value / kTen8); 180 | const uint32_t v1 = static_cast(value % kTen8); 181 | 182 | const uint32_t b0 = v0 / 10000; 183 | const uint32_t c0 = v0 % 10000; 184 | 185 | const uint32_t d1 = (b0 / 100) << 1; 186 | const uint32_t d2 = (b0 % 100) << 1; 187 | 188 | const uint32_t d3 = (c0 / 100) << 1; 189 | const uint32_t d4 = (c0 % 100) << 1; 190 | 191 | const uint32_t b1 = v1 / 10000; 192 | const uint32_t c1 = v1 % 10000; 193 | 194 | const uint32_t d5 = (b1 / 100) << 1; 195 | const uint32_t d6 = (b1 % 100) << 1; 196 | 197 | const uint32_t d7 = (c1 / 100) << 1; 198 | const uint32_t d8 = (c1 % 100) << 1; 199 | 200 | if (value >= kTen15) 201 | *buffer++ = cDigitsLut[d1]; 202 | if (value >= kTen14) 203 | *buffer++ = cDigitsLut[d1 + 1]; 204 | if (value >= kTen13) 205 | *buffer++ = cDigitsLut[d2]; 206 | if (value >= kTen12) 207 | *buffer++ = cDigitsLut[d2 + 1]; 208 | if (value >= kTen11) 209 | *buffer++ = cDigitsLut[d3]; 210 | if (value >= kTen10) 211 | *buffer++ = cDigitsLut[d3 + 1]; 212 | if (value >= kTen9) 213 | *buffer++ = cDigitsLut[d4]; 214 | 215 | *buffer++ = cDigitsLut[d4 + 1]; 216 | *buffer++ = cDigitsLut[d5]; 217 | *buffer++ = cDigitsLut[d5 + 1]; 218 | *buffer++ = cDigitsLut[d6]; 219 | *buffer++ = cDigitsLut[d6 + 1]; 220 | *buffer++ = cDigitsLut[d7]; 221 | *buffer++ = cDigitsLut[d7 + 1]; 222 | *buffer++ = cDigitsLut[d8]; 223 | *buffer++ = cDigitsLut[d8 + 1]; 224 | } 225 | else { 226 | const uint32_t a = static_cast(value / kTen16); // 1 to 1844 227 | value %= kTen16; 228 | 229 | if (a < 10) 230 | *buffer++ = static_cast('0' + static_cast(a)); 231 | else if (a < 100) { 232 | const uint32_t i = a << 1; 233 | *buffer++ = cDigitsLut[i]; 234 | *buffer++ = cDigitsLut[i + 1]; 235 | } 236 | else if (a < 1000) { 237 | *buffer++ = static_cast('0' + static_cast(a / 100)); 238 | 239 | const uint32_t i = (a % 100) << 1; 240 | *buffer++ = cDigitsLut[i]; 241 | *buffer++ = cDigitsLut[i + 1]; 242 | } 243 | else { 244 | const uint32_t i = (a / 100) << 1; 245 | const uint32_t j = (a % 100) << 1; 246 | *buffer++ = cDigitsLut[i]; 247 | *buffer++ = cDigitsLut[i + 1]; 248 | *buffer++ = cDigitsLut[j]; 249 | *buffer++ = cDigitsLut[j + 1]; 250 | } 251 | 252 | const uint32_t v0 = static_cast(value / kTen8); 253 | const uint32_t v1 = static_cast(value % kTen8); 254 | 255 | const uint32_t b0 = v0 / 10000; 256 | const uint32_t c0 = v0 % 10000; 257 | 258 | const uint32_t d1 = (b0 / 100) << 1; 259 | const uint32_t d2 = (b0 % 100) << 1; 260 | 261 | const uint32_t d3 = (c0 / 100) << 1; 262 | const uint32_t d4 = (c0 % 100) << 1; 263 | 264 | const uint32_t b1 = v1 / 10000; 265 | const uint32_t c1 = v1 % 10000; 266 | 267 | const uint32_t d5 = (b1 / 100) << 1; 268 | const uint32_t d6 = (b1 % 100) << 1; 269 | 270 | const uint32_t d7 = (c1 / 100) << 1; 271 | const uint32_t d8 = (c1 % 100) << 1; 272 | 273 | *buffer++ = cDigitsLut[d1]; 274 | *buffer++ = cDigitsLut[d1 + 1]; 275 | *buffer++ = cDigitsLut[d2]; 276 | *buffer++ = cDigitsLut[d2 + 1]; 277 | *buffer++ = cDigitsLut[d3]; 278 | *buffer++ = cDigitsLut[d3 + 1]; 279 | *buffer++ = cDigitsLut[d4]; 280 | *buffer++ = cDigitsLut[d4 + 1]; 281 | *buffer++ = cDigitsLut[d5]; 282 | *buffer++ = cDigitsLut[d5 + 1]; 283 | *buffer++ = cDigitsLut[d6]; 284 | *buffer++ = cDigitsLut[d6 + 1]; 285 | *buffer++ = cDigitsLut[d7]; 286 | *buffer++ = cDigitsLut[d7 + 1]; 287 | *buffer++ = cDigitsLut[d8]; 288 | *buffer++ = cDigitsLut[d8 + 1]; 289 | } 290 | 291 | return buffer; 292 | } 293 | 294 | inline char* i64toa(int64_t value, char* buffer) { 295 | RAPIDJSON_ASSERT(buffer != 0); 296 | uint64_t u = static_cast(value); 297 | if (value < 0) { 298 | *buffer++ = '-'; 299 | u = ~u + 1; 300 | } 301 | 302 | return u64toa(u, buffer); 303 | } 304 | 305 | } // namespace internal 306 | RAPIDJSON_NAMESPACE_END 307 | 308 | #endif // RAPIDJSON_ITOA_ 309 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/meta.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_INTERNAL_META_H_ 16 | #define RAPIDJSON_INTERNAL_META_H_ 17 | 18 | #include "../rapidjson.h" 19 | 20 | #ifdef __GNUC__ 21 | RAPIDJSON_DIAG_PUSH 22 | RAPIDJSON_DIAG_OFF(effc++) 23 | #endif 24 | 25 | #if defined(_MSC_VER) && !defined(__clang__) 26 | RAPIDJSON_DIAG_PUSH 27 | RAPIDJSON_DIAG_OFF(6334) 28 | #endif 29 | 30 | #if RAPIDJSON_HAS_CXX11_TYPETRAITS 31 | #include 32 | #endif 33 | 34 | //@cond RAPIDJSON_INTERNAL 35 | RAPIDJSON_NAMESPACE_BEGIN 36 | namespace internal { 37 | 38 | // Helper to wrap/convert arbitrary types to void, useful for arbitrary type matching 39 | template struct Void { typedef void Type; }; 40 | 41 | /////////////////////////////////////////////////////////////////////////////// 42 | // BoolType, TrueType, FalseType 43 | // 44 | template struct BoolType { 45 | static const bool Value = Cond; 46 | typedef BoolType Type; 47 | }; 48 | typedef BoolType TrueType; 49 | typedef BoolType FalseType; 50 | 51 | 52 | /////////////////////////////////////////////////////////////////////////////// 53 | // SelectIf, BoolExpr, NotExpr, AndExpr, OrExpr 54 | // 55 | 56 | template struct SelectIfImpl { template struct Apply { typedef T1 Type; }; }; 57 | template <> struct SelectIfImpl { template struct Apply { typedef T2 Type; }; }; 58 | template struct SelectIfCond : SelectIfImpl::template Apply {}; 59 | template struct SelectIf : SelectIfCond {}; 60 | 61 | template struct AndExprCond : FalseType {}; 62 | template <> struct AndExprCond : TrueType {}; 63 | template struct OrExprCond : TrueType {}; 64 | template <> struct OrExprCond : FalseType {}; 65 | 66 | template struct BoolExpr : SelectIf::Type {}; 67 | template struct NotExpr : SelectIf::Type {}; 68 | template struct AndExpr : AndExprCond::Type {}; 69 | template struct OrExpr : OrExprCond::Type {}; 70 | 71 | 72 | /////////////////////////////////////////////////////////////////////////////// 73 | // AddConst, MaybeAddConst, RemoveConst 74 | template struct AddConst { typedef const T Type; }; 75 | template struct MaybeAddConst : SelectIfCond {}; 76 | template struct RemoveConst { typedef T Type; }; 77 | template struct RemoveConst { typedef T Type; }; 78 | 79 | 80 | /////////////////////////////////////////////////////////////////////////////// 81 | // IsSame, IsConst, IsMoreConst, IsPointer 82 | // 83 | template struct IsSame : FalseType {}; 84 | template struct IsSame : TrueType {}; 85 | 86 | template struct IsConst : FalseType {}; 87 | template struct IsConst : TrueType {}; 88 | 89 | template 90 | struct IsMoreConst 91 | : AndExpr::Type, typename RemoveConst::Type>, 92 | BoolType::Value >= IsConst::Value> >::Type {}; 93 | 94 | template struct IsPointer : FalseType {}; 95 | template struct IsPointer : TrueType {}; 96 | 97 | /////////////////////////////////////////////////////////////////////////////// 98 | // IsBaseOf 99 | // 100 | #if RAPIDJSON_HAS_CXX11_TYPETRAITS 101 | 102 | template struct IsBaseOf 103 | : BoolType< ::std::is_base_of::value> {}; 104 | 105 | #else // simplified version adopted from Boost 106 | 107 | template struct IsBaseOfImpl { 108 | RAPIDJSON_STATIC_ASSERT(sizeof(B) != 0); 109 | RAPIDJSON_STATIC_ASSERT(sizeof(D) != 0); 110 | 111 | typedef char (&Yes)[1]; 112 | typedef char (&No) [2]; 113 | 114 | template 115 | static Yes Check(const D*, T); 116 | static No Check(const B*, int); 117 | 118 | struct Host { 119 | operator const B*() const; 120 | operator const D*(); 121 | }; 122 | 123 | enum { Value = (sizeof(Check(Host(), 0)) == sizeof(Yes)) }; 124 | }; 125 | 126 | template struct IsBaseOf 127 | : OrExpr, BoolExpr > >::Type {}; 128 | 129 | #endif // RAPIDJSON_HAS_CXX11_TYPETRAITS 130 | 131 | 132 | ////////////////////////////////////////////////////////////////////////// 133 | // EnableIf / DisableIf 134 | // 135 | template struct EnableIfCond { typedef T Type; }; 136 | template struct EnableIfCond { /* empty */ }; 137 | 138 | template struct DisableIfCond { typedef T Type; }; 139 | template struct DisableIfCond { /* empty */ }; 140 | 141 | template 142 | struct EnableIf : EnableIfCond {}; 143 | 144 | template 145 | struct DisableIf : DisableIfCond {}; 146 | 147 | // SFINAE helpers 148 | struct SfinaeTag {}; 149 | template struct RemoveSfinaeTag; 150 | template struct RemoveSfinaeTag { typedef T Type; }; 151 | 152 | #define RAPIDJSON_REMOVEFPTR_(type) \ 153 | typename ::RAPIDJSON_NAMESPACE::internal::RemoveSfinaeTag \ 154 | < ::RAPIDJSON_NAMESPACE::internal::SfinaeTag&(*) type>::Type 155 | 156 | #define RAPIDJSON_ENABLEIF(cond) \ 157 | typename ::RAPIDJSON_NAMESPACE::internal::EnableIf \ 158 | ::Type * = NULL 159 | 160 | #define RAPIDJSON_DISABLEIF(cond) \ 161 | typename ::RAPIDJSON_NAMESPACE::internal::DisableIf \ 162 | ::Type * = NULL 163 | 164 | #define RAPIDJSON_ENABLEIF_RETURN(cond,returntype) \ 165 | typename ::RAPIDJSON_NAMESPACE::internal::EnableIf \ 166 | ::Type 168 | 169 | #define RAPIDJSON_DISABLEIF_RETURN(cond,returntype) \ 170 | typename ::RAPIDJSON_NAMESPACE::internal::DisableIf \ 171 | ::Type 173 | 174 | } // namespace internal 175 | RAPIDJSON_NAMESPACE_END 176 | //@endcond 177 | 178 | #if defined(_MSC_VER) && !defined(__clang__) 179 | RAPIDJSON_DIAG_POP 180 | #endif 181 | 182 | #ifdef __GNUC__ 183 | RAPIDJSON_DIAG_POP 184 | #endif 185 | 186 | #endif // RAPIDJSON_INTERNAL_META_H_ 187 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/pow10.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_POW10_ 16 | #define RAPIDJSON_POW10_ 17 | 18 | #include "../rapidjson.h" 19 | 20 | RAPIDJSON_NAMESPACE_BEGIN 21 | namespace internal { 22 | 23 | //! Computes integer powers of 10 in double (10.0^n). 24 | /*! This function uses lookup table for fast and accurate results. 25 | \param n non-negative exponent. Must <= 308. 26 | \return 10.0^n 27 | */ 28 | inline double Pow10(int n) { 29 | static const double e[] = { // 1e-0...1e308: 309 * 8 bytes = 2472 bytes 30 | 1e+0, 31 | 1e+1, 1e+2, 1e+3, 1e+4, 1e+5, 1e+6, 1e+7, 1e+8, 1e+9, 1e+10, 1e+11, 1e+12, 1e+13, 1e+14, 1e+15, 1e+16, 1e+17, 1e+18, 1e+19, 1e+20, 32 | 1e+21, 1e+22, 1e+23, 1e+24, 1e+25, 1e+26, 1e+27, 1e+28, 1e+29, 1e+30, 1e+31, 1e+32, 1e+33, 1e+34, 1e+35, 1e+36, 1e+37, 1e+38, 1e+39, 1e+40, 33 | 1e+41, 1e+42, 1e+43, 1e+44, 1e+45, 1e+46, 1e+47, 1e+48, 1e+49, 1e+50, 1e+51, 1e+52, 1e+53, 1e+54, 1e+55, 1e+56, 1e+57, 1e+58, 1e+59, 1e+60, 34 | 1e+61, 1e+62, 1e+63, 1e+64, 1e+65, 1e+66, 1e+67, 1e+68, 1e+69, 1e+70, 1e+71, 1e+72, 1e+73, 1e+74, 1e+75, 1e+76, 1e+77, 1e+78, 1e+79, 1e+80, 35 | 1e+81, 1e+82, 1e+83, 1e+84, 1e+85, 1e+86, 1e+87, 1e+88, 1e+89, 1e+90, 1e+91, 1e+92, 1e+93, 1e+94, 1e+95, 1e+96, 1e+97, 1e+98, 1e+99, 1e+100, 36 | 1e+101,1e+102,1e+103,1e+104,1e+105,1e+106,1e+107,1e+108,1e+109,1e+110,1e+111,1e+112,1e+113,1e+114,1e+115,1e+116,1e+117,1e+118,1e+119,1e+120, 37 | 1e+121,1e+122,1e+123,1e+124,1e+125,1e+126,1e+127,1e+128,1e+129,1e+130,1e+131,1e+132,1e+133,1e+134,1e+135,1e+136,1e+137,1e+138,1e+139,1e+140, 38 | 1e+141,1e+142,1e+143,1e+144,1e+145,1e+146,1e+147,1e+148,1e+149,1e+150,1e+151,1e+152,1e+153,1e+154,1e+155,1e+156,1e+157,1e+158,1e+159,1e+160, 39 | 1e+161,1e+162,1e+163,1e+164,1e+165,1e+166,1e+167,1e+168,1e+169,1e+170,1e+171,1e+172,1e+173,1e+174,1e+175,1e+176,1e+177,1e+178,1e+179,1e+180, 40 | 1e+181,1e+182,1e+183,1e+184,1e+185,1e+186,1e+187,1e+188,1e+189,1e+190,1e+191,1e+192,1e+193,1e+194,1e+195,1e+196,1e+197,1e+198,1e+199,1e+200, 41 | 1e+201,1e+202,1e+203,1e+204,1e+205,1e+206,1e+207,1e+208,1e+209,1e+210,1e+211,1e+212,1e+213,1e+214,1e+215,1e+216,1e+217,1e+218,1e+219,1e+220, 42 | 1e+221,1e+222,1e+223,1e+224,1e+225,1e+226,1e+227,1e+228,1e+229,1e+230,1e+231,1e+232,1e+233,1e+234,1e+235,1e+236,1e+237,1e+238,1e+239,1e+240, 43 | 1e+241,1e+242,1e+243,1e+244,1e+245,1e+246,1e+247,1e+248,1e+249,1e+250,1e+251,1e+252,1e+253,1e+254,1e+255,1e+256,1e+257,1e+258,1e+259,1e+260, 44 | 1e+261,1e+262,1e+263,1e+264,1e+265,1e+266,1e+267,1e+268,1e+269,1e+270,1e+271,1e+272,1e+273,1e+274,1e+275,1e+276,1e+277,1e+278,1e+279,1e+280, 45 | 1e+281,1e+282,1e+283,1e+284,1e+285,1e+286,1e+287,1e+288,1e+289,1e+290,1e+291,1e+292,1e+293,1e+294,1e+295,1e+296,1e+297,1e+298,1e+299,1e+300, 46 | 1e+301,1e+302,1e+303,1e+304,1e+305,1e+306,1e+307,1e+308 47 | }; 48 | RAPIDJSON_ASSERT(n >= 0 && n <= 308); 49 | return e[n]; 50 | } 51 | 52 | } // namespace internal 53 | RAPIDJSON_NAMESPACE_END 54 | 55 | #endif // RAPIDJSON_POW10_ 56 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/stack.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_INTERNAL_STACK_H_ 16 | #define RAPIDJSON_INTERNAL_STACK_H_ 17 | 18 | #include "../allocators.h" 19 | #include "swap.h" 20 | #include 21 | 22 | #if defined(__clang__) 23 | RAPIDJSON_DIAG_PUSH 24 | RAPIDJSON_DIAG_OFF(c++98-compat) 25 | #endif 26 | 27 | RAPIDJSON_NAMESPACE_BEGIN 28 | namespace internal { 29 | 30 | /////////////////////////////////////////////////////////////////////////////// 31 | // Stack 32 | 33 | //! A type-unsafe stack for storing different types of data. 34 | /*! \tparam Allocator Allocator for allocating stack memory. 35 | */ 36 | template 37 | class Stack { 38 | public: 39 | // Optimization note: Do not allocate memory for stack_ in constructor. 40 | // Do it lazily when first Push() -> Expand() -> Resize(). 41 | Stack(Allocator* allocator, size_t stackCapacity) : allocator_(allocator), ownAllocator_(0), stack_(0), stackTop_(0), stackEnd_(0), initialCapacity_(stackCapacity) { 42 | } 43 | 44 | #if RAPIDJSON_HAS_CXX11_RVALUE_REFS 45 | Stack(Stack&& rhs) 46 | : allocator_(rhs.allocator_), 47 | ownAllocator_(rhs.ownAllocator_), 48 | stack_(rhs.stack_), 49 | stackTop_(rhs.stackTop_), 50 | stackEnd_(rhs.stackEnd_), 51 | initialCapacity_(rhs.initialCapacity_) 52 | { 53 | rhs.allocator_ = 0; 54 | rhs.ownAllocator_ = 0; 55 | rhs.stack_ = 0; 56 | rhs.stackTop_ = 0; 57 | rhs.stackEnd_ = 0; 58 | rhs.initialCapacity_ = 0; 59 | } 60 | #endif 61 | 62 | ~Stack() { 63 | Destroy(); 64 | } 65 | 66 | #if RAPIDJSON_HAS_CXX11_RVALUE_REFS 67 | Stack& operator=(Stack&& rhs) { 68 | if (&rhs != this) 69 | { 70 | Destroy(); 71 | 72 | allocator_ = rhs.allocator_; 73 | ownAllocator_ = rhs.ownAllocator_; 74 | stack_ = rhs.stack_; 75 | stackTop_ = rhs.stackTop_; 76 | stackEnd_ = rhs.stackEnd_; 77 | initialCapacity_ = rhs.initialCapacity_; 78 | 79 | rhs.allocator_ = 0; 80 | rhs.ownAllocator_ = 0; 81 | rhs.stack_ = 0; 82 | rhs.stackTop_ = 0; 83 | rhs.stackEnd_ = 0; 84 | rhs.initialCapacity_ = 0; 85 | } 86 | return *this; 87 | } 88 | #endif 89 | 90 | void Swap(Stack& rhs) RAPIDJSON_NOEXCEPT { 91 | internal::Swap(allocator_, rhs.allocator_); 92 | internal::Swap(ownAllocator_, rhs.ownAllocator_); 93 | internal::Swap(stack_, rhs.stack_); 94 | internal::Swap(stackTop_, rhs.stackTop_); 95 | internal::Swap(stackEnd_, rhs.stackEnd_); 96 | internal::Swap(initialCapacity_, rhs.initialCapacity_); 97 | } 98 | 99 | void Clear() { stackTop_ = stack_; } 100 | 101 | void ShrinkToFit() { 102 | if (Empty()) { 103 | // If the stack is empty, completely deallocate the memory. 104 | Allocator::Free(stack_); // NOLINT (+clang-analyzer-unix.Malloc) 105 | stack_ = 0; 106 | stackTop_ = 0; 107 | stackEnd_ = 0; 108 | } 109 | else 110 | Resize(GetSize()); 111 | } 112 | 113 | // Optimization note: try to minimize the size of this function for force inline. 114 | // Expansion is run very infrequently, so it is moved to another (probably non-inline) function. 115 | template 116 | RAPIDJSON_FORCEINLINE void Reserve(size_t count = 1) { 117 | // Expand the stack if needed 118 | if (RAPIDJSON_UNLIKELY(static_cast(sizeof(T) * count) > (stackEnd_ - stackTop_))) 119 | Expand(count); 120 | } 121 | 122 | template 123 | RAPIDJSON_FORCEINLINE T* Push(size_t count = 1) { 124 | Reserve(count); 125 | return PushUnsafe(count); 126 | } 127 | 128 | template 129 | RAPIDJSON_FORCEINLINE T* PushUnsafe(size_t count = 1) { 130 | RAPIDJSON_ASSERT(stackTop_); 131 | RAPIDJSON_ASSERT(static_cast(sizeof(T) * count) <= (stackEnd_ - stackTop_)); 132 | T* ret = reinterpret_cast(stackTop_); 133 | stackTop_ += sizeof(T) * count; 134 | return ret; 135 | } 136 | 137 | template 138 | T* Pop(size_t count) { 139 | RAPIDJSON_ASSERT(GetSize() >= count * sizeof(T)); 140 | stackTop_ -= count * sizeof(T); 141 | return reinterpret_cast(stackTop_); 142 | } 143 | 144 | template 145 | T* Top() { 146 | RAPIDJSON_ASSERT(GetSize() >= sizeof(T)); 147 | return reinterpret_cast(stackTop_ - sizeof(T)); 148 | } 149 | 150 | template 151 | const T* Top() const { 152 | RAPIDJSON_ASSERT(GetSize() >= sizeof(T)); 153 | return reinterpret_cast(stackTop_ - sizeof(T)); 154 | } 155 | 156 | template 157 | T* End() { return reinterpret_cast(stackTop_); } 158 | 159 | template 160 | const T* End() const { return reinterpret_cast(stackTop_); } 161 | 162 | template 163 | T* Bottom() { return reinterpret_cast(stack_); } 164 | 165 | template 166 | const T* Bottom() const { return reinterpret_cast(stack_); } 167 | 168 | bool HasAllocator() const { 169 | return allocator_ != 0; 170 | } 171 | 172 | Allocator& GetAllocator() { 173 | RAPIDJSON_ASSERT(allocator_); 174 | return *allocator_; 175 | } 176 | 177 | bool Empty() const { return stackTop_ == stack_; } 178 | size_t GetSize() const { return static_cast(stackTop_ - stack_); } 179 | size_t GetCapacity() const { return static_cast(stackEnd_ - stack_); } 180 | 181 | private: 182 | template 183 | void Expand(size_t count) { 184 | // Only expand the capacity if the current stack exists. Otherwise just create a stack with initial capacity. 185 | size_t newCapacity; 186 | if (stack_ == 0) { 187 | if (!allocator_) 188 | ownAllocator_ = allocator_ = RAPIDJSON_NEW(Allocator)(); 189 | newCapacity = initialCapacity_; 190 | } else { 191 | newCapacity = GetCapacity(); 192 | newCapacity += (newCapacity + 1) / 2; 193 | } 194 | size_t newSize = GetSize() + sizeof(T) * count; 195 | if (newCapacity < newSize) 196 | newCapacity = newSize; 197 | 198 | Resize(newCapacity); 199 | } 200 | 201 | void Resize(size_t newCapacity) { 202 | const size_t size = GetSize(); // Backup the current size 203 | stack_ = static_cast(allocator_->Realloc(stack_, GetCapacity(), newCapacity)); 204 | stackTop_ = stack_ + size; 205 | stackEnd_ = stack_ + newCapacity; 206 | } 207 | 208 | void Destroy() { 209 | Allocator::Free(stack_); 210 | RAPIDJSON_DELETE(ownAllocator_); // Only delete if it is owned by the stack 211 | } 212 | 213 | // Prohibit copy constructor & assignment operator. 214 | Stack(const Stack&); 215 | Stack& operator=(const Stack&); 216 | 217 | Allocator* allocator_; 218 | Allocator* ownAllocator_; 219 | char *stack_; 220 | char *stackTop_; 221 | char *stackEnd_; 222 | size_t initialCapacity_; 223 | }; 224 | 225 | } // namespace internal 226 | RAPIDJSON_NAMESPACE_END 227 | 228 | #if defined(__clang__) 229 | RAPIDJSON_DIAG_POP 230 | #endif 231 | 232 | #endif // RAPIDJSON_STACK_H_ 233 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/strfunc.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_INTERNAL_STRFUNC_H_ 16 | #define RAPIDJSON_INTERNAL_STRFUNC_H_ 17 | 18 | #include "../stream.h" 19 | #include 20 | 21 | RAPIDJSON_NAMESPACE_BEGIN 22 | namespace internal { 23 | 24 | //! Custom strlen() which works on different character types. 25 | /*! \tparam Ch Character type (e.g. char, wchar_t, short) 26 | \param s Null-terminated input string. 27 | \return Number of characters in the string. 28 | \note This has the same semantics as strlen(), the return value is not number of Unicode codepoints. 29 | */ 30 | template 31 | inline SizeType StrLen(const Ch* s) { 32 | RAPIDJSON_ASSERT(s != 0); 33 | const Ch* p = s; 34 | while (*p) ++p; 35 | return SizeType(p - s); 36 | } 37 | 38 | template <> 39 | inline SizeType StrLen(const char* s) { 40 | return SizeType(std::strlen(s)); 41 | } 42 | 43 | template <> 44 | inline SizeType StrLen(const wchar_t* s) { 45 | return SizeType(std::wcslen(s)); 46 | } 47 | 48 | //! Returns number of code points in a encoded string. 49 | template 50 | bool CountStringCodePoint(const typename Encoding::Ch* s, SizeType length, SizeType* outCount) { 51 | RAPIDJSON_ASSERT(s != 0); 52 | RAPIDJSON_ASSERT(outCount != 0); 53 | GenericStringStream is(s); 54 | const typename Encoding::Ch* end = s + length; 55 | SizeType count = 0; 56 | while (is.src_ < end) { 57 | unsigned codepoint; 58 | if (!Encoding::Decode(is, &codepoint)) 59 | return false; 60 | count++; 61 | } 62 | *outCount = count; 63 | return true; 64 | } 65 | 66 | } // namespace internal 67 | RAPIDJSON_NAMESPACE_END 68 | 69 | #endif // RAPIDJSON_INTERNAL_STRFUNC_H_ 70 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/strtod.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_STRTOD_ 16 | #define RAPIDJSON_STRTOD_ 17 | 18 | #include "ieee754.h" 19 | #include "biginteger.h" 20 | #include "diyfp.h" 21 | #include "pow10.h" 22 | #include 23 | #include 24 | 25 | RAPIDJSON_NAMESPACE_BEGIN 26 | namespace internal { 27 | 28 | inline double FastPath(double significand, int exp) { 29 | if (exp < -308) 30 | return 0.0; 31 | else if (exp >= 0) 32 | return significand * internal::Pow10(exp); 33 | else 34 | return significand / internal::Pow10(-exp); 35 | } 36 | 37 | inline double StrtodNormalPrecision(double d, int p) { 38 | if (p < -308) { 39 | // Prevent expSum < -308, making Pow10(p) = 0 40 | d = FastPath(d, -308); 41 | d = FastPath(d, p + 308); 42 | } 43 | else 44 | d = FastPath(d, p); 45 | return d; 46 | } 47 | 48 | template 49 | inline T Min3(T a, T b, T c) { 50 | T m = a; 51 | if (m > b) m = b; 52 | if (m > c) m = c; 53 | return m; 54 | } 55 | 56 | inline int CheckWithinHalfULP(double b, const BigInteger& d, int dExp) { 57 | const Double db(b); 58 | const uint64_t bInt = db.IntegerSignificand(); 59 | const int bExp = db.IntegerExponent(); 60 | const int hExp = bExp - 1; 61 | 62 | int dS_Exp2 = 0, dS_Exp5 = 0, bS_Exp2 = 0, bS_Exp5 = 0, hS_Exp2 = 0, hS_Exp5 = 0; 63 | 64 | // Adjust for decimal exponent 65 | if (dExp >= 0) { 66 | dS_Exp2 += dExp; 67 | dS_Exp5 += dExp; 68 | } 69 | else { 70 | bS_Exp2 -= dExp; 71 | bS_Exp5 -= dExp; 72 | hS_Exp2 -= dExp; 73 | hS_Exp5 -= dExp; 74 | } 75 | 76 | // Adjust for binary exponent 77 | if (bExp >= 0) 78 | bS_Exp2 += bExp; 79 | else { 80 | dS_Exp2 -= bExp; 81 | hS_Exp2 -= bExp; 82 | } 83 | 84 | // Adjust for half ulp exponent 85 | if (hExp >= 0) 86 | hS_Exp2 += hExp; 87 | else { 88 | dS_Exp2 -= hExp; 89 | bS_Exp2 -= hExp; 90 | } 91 | 92 | // Remove common power of two factor from all three scaled values 93 | int common_Exp2 = Min3(dS_Exp2, bS_Exp2, hS_Exp2); 94 | dS_Exp2 -= common_Exp2; 95 | bS_Exp2 -= common_Exp2; 96 | hS_Exp2 -= common_Exp2; 97 | 98 | BigInteger dS = d; 99 | dS.MultiplyPow5(static_cast(dS_Exp5)) <<= static_cast(dS_Exp2); 100 | 101 | BigInteger bS(bInt); 102 | bS.MultiplyPow5(static_cast(bS_Exp5)) <<= static_cast(bS_Exp2); 103 | 104 | BigInteger hS(1); 105 | hS.MultiplyPow5(static_cast(hS_Exp5)) <<= static_cast(hS_Exp2); 106 | 107 | BigInteger delta(0); 108 | dS.Difference(bS, &delta); 109 | 110 | return delta.Compare(hS); 111 | } 112 | 113 | inline bool StrtodFast(double d, int p, double* result) { 114 | // Use fast path for string-to-double conversion if possible 115 | // see http://www.exploringbinary.com/fast-path-decimal-to-floating-point-conversion/ 116 | if (p > 22 && p < 22 + 16) { 117 | // Fast Path Cases In Disguise 118 | d *= internal::Pow10(p - 22); 119 | p = 22; 120 | } 121 | 122 | if (p >= -22 && p <= 22 && d <= 9007199254740991.0) { // 2^53 - 1 123 | *result = FastPath(d, p); 124 | return true; 125 | } 126 | else 127 | return false; 128 | } 129 | 130 | // Compute an approximation and see if it is within 1/2 ULP 131 | inline bool StrtodDiyFp(const char* decimals, int dLen, int dExp, double* result) { 132 | uint64_t significand = 0; 133 | int i = 0; // 2^64 - 1 = 18446744073709551615, 1844674407370955161 = 0x1999999999999999 134 | for (; i < dLen; i++) { 135 | if (significand > RAPIDJSON_UINT64_C2(0x19999999, 0x99999999) || 136 | (significand == RAPIDJSON_UINT64_C2(0x19999999, 0x99999999) && decimals[i] > '5')) 137 | break; 138 | significand = significand * 10u + static_cast(decimals[i] - '0'); 139 | } 140 | 141 | if (i < dLen && decimals[i] >= '5') // Rounding 142 | significand++; 143 | 144 | int remaining = dLen - i; 145 | const int kUlpShift = 3; 146 | const int kUlp = 1 << kUlpShift; 147 | int64_t error = (remaining == 0) ? 0 : kUlp / 2; 148 | 149 | DiyFp v(significand, 0); 150 | v = v.Normalize(); 151 | error <<= -v.e; 152 | 153 | dExp += remaining; 154 | 155 | int actualExp; 156 | DiyFp cachedPower = GetCachedPower10(dExp, &actualExp); 157 | if (actualExp != dExp) { 158 | static const DiyFp kPow10[] = { 159 | DiyFp(RAPIDJSON_UINT64_C2(0xa0000000, 0x00000000), -60), // 10^1 160 | DiyFp(RAPIDJSON_UINT64_C2(0xc8000000, 0x00000000), -57), // 10^2 161 | DiyFp(RAPIDJSON_UINT64_C2(0xfa000000, 0x00000000), -54), // 10^3 162 | DiyFp(RAPIDJSON_UINT64_C2(0x9c400000, 0x00000000), -50), // 10^4 163 | DiyFp(RAPIDJSON_UINT64_C2(0xc3500000, 0x00000000), -47), // 10^5 164 | DiyFp(RAPIDJSON_UINT64_C2(0xf4240000, 0x00000000), -44), // 10^6 165 | DiyFp(RAPIDJSON_UINT64_C2(0x98968000, 0x00000000), -40) // 10^7 166 | }; 167 | int adjustment = dExp - actualExp; 168 | RAPIDJSON_ASSERT(adjustment >= 1 && adjustment < 8); 169 | v = v * kPow10[adjustment - 1]; 170 | if (dLen + adjustment > 19) // has more digits than decimal digits in 64-bit 171 | error += kUlp / 2; 172 | } 173 | 174 | v = v * cachedPower; 175 | 176 | error += kUlp + (error == 0 ? 0 : 1); 177 | 178 | const int oldExp = v.e; 179 | v = v.Normalize(); 180 | error <<= oldExp - v.e; 181 | 182 | const int effectiveSignificandSize = Double::EffectiveSignificandSize(64 + v.e); 183 | int precisionSize = 64 - effectiveSignificandSize; 184 | if (precisionSize + kUlpShift >= 64) { 185 | int scaleExp = (precisionSize + kUlpShift) - 63; 186 | v.f >>= scaleExp; 187 | v.e += scaleExp; 188 | error = (error >> scaleExp) + 1 + kUlp; 189 | precisionSize -= scaleExp; 190 | } 191 | 192 | DiyFp rounded(v.f >> precisionSize, v.e + precisionSize); 193 | const uint64_t precisionBits = (v.f & ((uint64_t(1) << precisionSize) - 1)) * kUlp; 194 | const uint64_t halfWay = (uint64_t(1) << (precisionSize - 1)) * kUlp; 195 | if (precisionBits >= halfWay + static_cast(error)) { 196 | rounded.f++; 197 | if (rounded.f & (DiyFp::kDpHiddenBit << 1)) { // rounding overflows mantissa (issue #340) 198 | rounded.f >>= 1; 199 | rounded.e++; 200 | } 201 | } 202 | 203 | *result = rounded.ToDouble(); 204 | 205 | return halfWay - static_cast(error) >= precisionBits || precisionBits >= halfWay + static_cast(error); 206 | } 207 | 208 | inline double StrtodBigInteger(double approx, const char* decimals, int dLen, int dExp) { 209 | RAPIDJSON_ASSERT(dLen >= 0); 210 | const BigInteger dInt(decimals, static_cast(dLen)); 211 | Double a(approx); 212 | int cmp = CheckWithinHalfULP(a.Value(), dInt, dExp); 213 | if (cmp < 0) 214 | return a.Value(); // within half ULP 215 | else if (cmp == 0) { 216 | // Round towards even 217 | if (a.Significand() & 1) 218 | return a.NextPositiveDouble(); 219 | else 220 | return a.Value(); 221 | } 222 | else // adjustment 223 | return a.NextPositiveDouble(); 224 | } 225 | 226 | inline double StrtodFullPrecision(double d, int p, const char* decimals, size_t length, size_t decimalPosition, int exp) { 227 | RAPIDJSON_ASSERT(d >= 0.0); 228 | RAPIDJSON_ASSERT(length >= 1); 229 | 230 | double result = 0.0; 231 | if (StrtodFast(d, p, &result)) 232 | return result; 233 | 234 | RAPIDJSON_ASSERT(length <= INT_MAX); 235 | int dLen = static_cast(length); 236 | 237 | RAPIDJSON_ASSERT(length >= decimalPosition); 238 | RAPIDJSON_ASSERT(length - decimalPosition <= INT_MAX); 239 | int dExpAdjust = static_cast(length - decimalPosition); 240 | 241 | RAPIDJSON_ASSERT(exp >= INT_MIN + dExpAdjust); 242 | int dExp = exp - dExpAdjust; 243 | 244 | // Make sure length+dExp does not overflow 245 | RAPIDJSON_ASSERT(dExp <= INT_MAX - dLen); 246 | 247 | // Trim leading zeros 248 | while (dLen > 0 && *decimals == '0') { 249 | dLen--; 250 | decimals++; 251 | } 252 | 253 | // Trim trailing zeros 254 | while (dLen > 0 && decimals[dLen - 1] == '0') { 255 | dLen--; 256 | dExp++; 257 | } 258 | 259 | if (dLen == 0) { // Buffer only contains zeros. 260 | return 0.0; 261 | } 262 | 263 | // Trim right-most digits 264 | const int kMaxDecimalDigit = 767 + 1; 265 | if (dLen > kMaxDecimalDigit) { 266 | dExp += dLen - kMaxDecimalDigit; 267 | dLen = kMaxDecimalDigit; 268 | } 269 | 270 | // If too small, underflow to zero. 271 | // Any x <= 10^-324 is interpreted as zero. 272 | if (dLen + dExp <= -324) 273 | return 0.0; 274 | 275 | // If too large, overflow to infinity. 276 | // Any x >= 10^309 is interpreted as +infinity. 277 | if (dLen + dExp > 309) 278 | return std::numeric_limits::infinity(); 279 | 280 | if (StrtodDiyFp(decimals, dLen, dExp, &result)) 281 | return result; 282 | 283 | // Use approximation from StrtodDiyFp and make adjustment with BigInteger comparison 284 | return StrtodBigInteger(result, decimals, dLen, dExp); 285 | } 286 | 287 | } // namespace internal 288 | RAPIDJSON_NAMESPACE_END 289 | 290 | #endif // RAPIDJSON_STRTOD_ 291 | -------------------------------------------------------------------------------- /include/tools/rapidjson/internal/swap.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_INTERNAL_SWAP_H_ 16 | #define RAPIDJSON_INTERNAL_SWAP_H_ 17 | 18 | #include "../rapidjson.h" 19 | 20 | #if defined(__clang__) 21 | RAPIDJSON_DIAG_PUSH 22 | RAPIDJSON_DIAG_OFF(c++98-compat) 23 | #endif 24 | 25 | RAPIDJSON_NAMESPACE_BEGIN 26 | namespace internal { 27 | 28 | //! Custom swap() to avoid dependency on C++ header 29 | /*! \tparam T Type of the arguments to swap, should be instantiated with primitive C++ types only. 30 | \note This has the same semantics as std::swap(). 31 | */ 32 | template 33 | inline void Swap(T& a, T& b) RAPIDJSON_NOEXCEPT { 34 | T tmp = a; 35 | a = b; 36 | b = tmp; 37 | } 38 | 39 | } // namespace internal 40 | RAPIDJSON_NAMESPACE_END 41 | 42 | #if defined(__clang__) 43 | RAPIDJSON_DIAG_POP 44 | #endif 45 | 46 | #endif // RAPIDJSON_INTERNAL_SWAP_H_ 47 | -------------------------------------------------------------------------------- /include/tools/rapidjson/istreamwrapper.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_ISTREAMWRAPPER_H_ 16 | #define RAPIDJSON_ISTREAMWRAPPER_H_ 17 | 18 | #include "stream.h" 19 | #include 20 | #include 21 | 22 | #ifdef __clang__ 23 | RAPIDJSON_DIAG_PUSH 24 | RAPIDJSON_DIAG_OFF(padded) 25 | #elif defined(_MSC_VER) 26 | RAPIDJSON_DIAG_PUSH 27 | RAPIDJSON_DIAG_OFF(4351) // new behavior: elements of array 'array' will be default initialized 28 | #endif 29 | 30 | RAPIDJSON_NAMESPACE_BEGIN 31 | 32 | //! Wrapper of \c std::basic_istream into RapidJSON's Stream concept. 33 | /*! 34 | The classes can be wrapped including but not limited to: 35 | 36 | - \c std::istringstream 37 | - \c std::stringstream 38 | - \c std::wistringstream 39 | - \c std::wstringstream 40 | - \c std::ifstream 41 | - \c std::fstream 42 | - \c std::wifstream 43 | - \c std::wfstream 44 | 45 | \tparam StreamType Class derived from \c std::basic_istream. 46 | */ 47 | 48 | template 49 | class BasicIStreamWrapper { 50 | public: 51 | typedef typename StreamType::char_type Ch; 52 | 53 | //! Constructor. 54 | /*! 55 | \param stream stream opened for read. 56 | */ 57 | BasicIStreamWrapper(StreamType &stream) : stream_(stream), buffer_(peekBuffer_), bufferSize_(4), bufferLast_(0), current_(buffer_), readCount_(0), count_(0), eof_(false) { 58 | Read(); 59 | } 60 | 61 | //! Constructor. 62 | /*! 63 | \param stream stream opened for read. 64 | \param buffer user-supplied buffer. 65 | \param bufferSize size of buffer in bytes. Must >=4 bytes. 66 | */ 67 | BasicIStreamWrapper(StreamType &stream, char* buffer, size_t bufferSize) : stream_(stream), buffer_(buffer), bufferSize_(bufferSize), bufferLast_(0), current_(buffer_), readCount_(0), count_(0), eof_(false) { 68 | RAPIDJSON_ASSERT(bufferSize >= 4); 69 | Read(); 70 | } 71 | 72 | Ch Peek() const { return *current_; } 73 | Ch Take() { Ch c = *current_; Read(); return c; } 74 | size_t Tell() const { return count_ + static_cast(current_ - buffer_); } 75 | 76 | // Not implemented 77 | void Put(Ch) { RAPIDJSON_ASSERT(false); } 78 | void Flush() { RAPIDJSON_ASSERT(false); } 79 | Ch* PutBegin() { RAPIDJSON_ASSERT(false); return 0; } 80 | size_t PutEnd(Ch*) { RAPIDJSON_ASSERT(false); return 0; } 81 | 82 | // For encoding detection only. 83 | const Ch* Peek4() const { 84 | return (current_ + 4 - !eof_ <= bufferLast_) ? current_ : 0; 85 | } 86 | 87 | private: 88 | BasicIStreamWrapper(); 89 | BasicIStreamWrapper(const BasicIStreamWrapper&); 90 | BasicIStreamWrapper& operator=(const BasicIStreamWrapper&); 91 | 92 | void Read() { 93 | if (current_ < bufferLast_) 94 | ++current_; 95 | else if (!eof_) { 96 | count_ += readCount_; 97 | readCount_ = bufferSize_; 98 | bufferLast_ = buffer_ + readCount_ - 1; 99 | current_ = buffer_; 100 | 101 | if (!stream_.read(buffer_, static_cast(bufferSize_))) { 102 | readCount_ = static_cast(stream_.gcount()); 103 | *(bufferLast_ = buffer_ + readCount_) = '\0'; 104 | eof_ = true; 105 | } 106 | } 107 | } 108 | 109 | StreamType &stream_; 110 | Ch peekBuffer_[4], *buffer_; 111 | size_t bufferSize_; 112 | Ch *bufferLast_; 113 | Ch *current_; 114 | size_t readCount_; 115 | size_t count_; //!< Number of characters read 116 | bool eof_; 117 | }; 118 | 119 | typedef BasicIStreamWrapper IStreamWrapper; 120 | typedef BasicIStreamWrapper WIStreamWrapper; 121 | 122 | #if defined(__clang__) || defined(_MSC_VER) 123 | RAPIDJSON_DIAG_POP 124 | #endif 125 | 126 | RAPIDJSON_NAMESPACE_END 127 | 128 | #endif // RAPIDJSON_ISTREAMWRAPPER_H_ 129 | -------------------------------------------------------------------------------- /include/tools/rapidjson/memorybuffer.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_MEMORYBUFFER_H_ 16 | #define RAPIDJSON_MEMORYBUFFER_H_ 17 | 18 | #include "stream.h" 19 | #include "internal/stack.h" 20 | 21 | RAPIDJSON_NAMESPACE_BEGIN 22 | 23 | //! Represents an in-memory output byte stream. 24 | /*! 25 | This class is mainly for being wrapped by EncodedOutputStream or AutoUTFOutputStream. 26 | 27 | It is similar to FileWriteBuffer but the destination is an in-memory buffer instead of a file. 28 | 29 | Differences between MemoryBuffer and StringBuffer: 30 | 1. StringBuffer has Encoding but MemoryBuffer is only a byte buffer. 31 | 2. StringBuffer::GetString() returns a null-terminated string. MemoryBuffer::GetBuffer() returns a buffer without terminator. 32 | 33 | \tparam Allocator type for allocating memory buffer. 34 | \note implements Stream concept 35 | */ 36 | template 37 | struct GenericMemoryBuffer { 38 | typedef char Ch; // byte 39 | 40 | GenericMemoryBuffer(Allocator* allocator = 0, size_t capacity = kDefaultCapacity) : stack_(allocator, capacity) {} 41 | 42 | void Put(Ch c) { *stack_.template Push() = c; } 43 | void Flush() {} 44 | 45 | void Clear() { stack_.Clear(); } 46 | void ShrinkToFit() { stack_.ShrinkToFit(); } 47 | Ch* Push(size_t count) { return stack_.template Push(count); } 48 | void Pop(size_t count) { stack_.template Pop(count); } 49 | 50 | const Ch* GetBuffer() const { 51 | return stack_.template Bottom(); 52 | } 53 | 54 | size_t GetSize() const { return stack_.GetSize(); } 55 | 56 | static const size_t kDefaultCapacity = 256; 57 | mutable internal::Stack stack_; 58 | }; 59 | 60 | typedef GenericMemoryBuffer<> MemoryBuffer; 61 | 62 | //! Implement specialized version of PutN() with memset() for better performance. 63 | template<> 64 | inline void PutN(MemoryBuffer& memoryBuffer, char c, size_t n) { 65 | std::memset(memoryBuffer.stack_.Push(n), c, n * sizeof(c)); 66 | } 67 | 68 | RAPIDJSON_NAMESPACE_END 69 | 70 | #endif // RAPIDJSON_MEMORYBUFFER_H_ 71 | -------------------------------------------------------------------------------- /include/tools/rapidjson/memorystream.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_MEMORYSTREAM_H_ 16 | #define RAPIDJSON_MEMORYSTREAM_H_ 17 | 18 | #include "stream.h" 19 | 20 | #ifdef __clang__ 21 | RAPIDJSON_DIAG_PUSH 22 | RAPIDJSON_DIAG_OFF(unreachable-code) 23 | RAPIDJSON_DIAG_OFF(missing-noreturn) 24 | #endif 25 | 26 | RAPIDJSON_NAMESPACE_BEGIN 27 | 28 | //! Represents an in-memory input byte stream. 29 | /*! 30 | This class is mainly for being wrapped by EncodedInputStream or AutoUTFInputStream. 31 | 32 | It is similar to FileReadBuffer but the source is an in-memory buffer instead of a file. 33 | 34 | Differences between MemoryStream and StringStream: 35 | 1. StringStream has encoding but MemoryStream is a byte stream. 36 | 2. MemoryStream needs size of the source buffer and the buffer don't need to be null terminated. StringStream assume null-terminated string as source. 37 | 3. MemoryStream supports Peek4() for encoding detection. StringStream is specified with an encoding so it should not have Peek4(). 38 | \note implements Stream concept 39 | */ 40 | struct MemoryStream { 41 | typedef char Ch; // byte 42 | 43 | MemoryStream(const Ch *src, size_t size) : src_(src), begin_(src), end_(src + size), size_(size) {} 44 | 45 | Ch Peek() const { return RAPIDJSON_UNLIKELY(src_ == end_) ? '\0' : *src_; } 46 | Ch Take() { return RAPIDJSON_UNLIKELY(src_ == end_) ? '\0' : *src_++; } 47 | size_t Tell() const { return static_cast(src_ - begin_); } 48 | 49 | Ch* PutBegin() { RAPIDJSON_ASSERT(false); return 0; } 50 | void Put(Ch) { RAPIDJSON_ASSERT(false); } 51 | void Flush() { RAPIDJSON_ASSERT(false); } 52 | size_t PutEnd(Ch*) { RAPIDJSON_ASSERT(false); return 0; } 53 | 54 | // For encoding detection only. 55 | const Ch* Peek4() const { 56 | return Tell() + 4 <= size_ ? src_ : 0; 57 | } 58 | 59 | const Ch* src_; //!< Current read position. 60 | const Ch* begin_; //!< Original head of the string. 61 | const Ch* end_; //!< End of stream. 62 | size_t size_; //!< Size of the stream. 63 | }; 64 | 65 | RAPIDJSON_NAMESPACE_END 66 | 67 | #ifdef __clang__ 68 | RAPIDJSON_DIAG_POP 69 | #endif 70 | 71 | #endif // RAPIDJSON_MEMORYBUFFER_H_ 72 | -------------------------------------------------------------------------------- /include/tools/rapidjson/msinttypes/inttypes.h: -------------------------------------------------------------------------------- 1 | // ISO C9x compliant inttypes.h for Microsoft Visual Studio 2 | // Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124 3 | // 4 | // Copyright (c) 2006-2013 Alexander Chemeris 5 | // 6 | // Redistribution and use in source and binary forms, with or without 7 | // modification, are permitted provided that the following conditions are met: 8 | // 9 | // 1. Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // 12 | // 2. Redistributions in binary form must reproduce the above copyright 13 | // notice, this list of conditions and the following disclaimer in the 14 | // documentation and/or other materials provided with the distribution. 15 | // 16 | // 3. Neither the name of the product nor the names of its contributors may 17 | // be used to endorse or promote products derived from this software 18 | // without specific prior written permission. 19 | // 20 | // THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED 21 | // WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF 22 | // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO 23 | // EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 24 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 25 | // PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 26 | // OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 27 | // WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 28 | // OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 29 | // ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | // 31 | /////////////////////////////////////////////////////////////////////////////// 32 | 33 | // The above software in this distribution may have been modified by 34 | // THL A29 Limited ("Tencent Modifications"). 35 | // All Tencent Modifications are Copyright (C) 2015 THL A29 Limited. 36 | 37 | #ifndef _MSC_VER // [ 38 | #error "Use this header only with Microsoft Visual C++ compilers!" 39 | #endif // _MSC_VER ] 40 | 41 | #ifndef _MSC_INTTYPES_H_ // [ 42 | #define _MSC_INTTYPES_H_ 43 | 44 | #if _MSC_VER > 1000 45 | #pragma once 46 | #endif 47 | 48 | #include "stdint.h" 49 | 50 | // miloyip: VC supports inttypes.h since VC2013 51 | #if _MSC_VER >= 1800 52 | #include 53 | #else 54 | 55 | // 7.8 Format conversion of integer types 56 | 57 | typedef struct { 58 | intmax_t quot; 59 | intmax_t rem; 60 | } imaxdiv_t; 61 | 62 | // 7.8.1 Macros for format specifiers 63 | 64 | #if !defined(__cplusplus) || defined(__STDC_FORMAT_MACROS) // [ See footnote 185 at page 198 65 | 66 | // The fprintf macros for signed integers are: 67 | #define PRId8 "d" 68 | #define PRIi8 "i" 69 | #define PRIdLEAST8 "d" 70 | #define PRIiLEAST8 "i" 71 | #define PRIdFAST8 "d" 72 | #define PRIiFAST8 "i" 73 | 74 | #define PRId16 "hd" 75 | #define PRIi16 "hi" 76 | #define PRIdLEAST16 "hd" 77 | #define PRIiLEAST16 "hi" 78 | #define PRIdFAST16 "hd" 79 | #define PRIiFAST16 "hi" 80 | 81 | #define PRId32 "I32d" 82 | #define PRIi32 "I32i" 83 | #define PRIdLEAST32 "I32d" 84 | #define PRIiLEAST32 "I32i" 85 | #define PRIdFAST32 "I32d" 86 | #define PRIiFAST32 "I32i" 87 | 88 | #define PRId64 "I64d" 89 | #define PRIi64 "I64i" 90 | #define PRIdLEAST64 "I64d" 91 | #define PRIiLEAST64 "I64i" 92 | #define PRIdFAST64 "I64d" 93 | #define PRIiFAST64 "I64i" 94 | 95 | #define PRIdMAX "I64d" 96 | #define PRIiMAX "I64i" 97 | 98 | #define PRIdPTR "Id" 99 | #define PRIiPTR "Ii" 100 | 101 | // The fprintf macros for unsigned integers are: 102 | #define PRIo8 "o" 103 | #define PRIu8 "u" 104 | #define PRIx8 "x" 105 | #define PRIX8 "X" 106 | #define PRIoLEAST8 "o" 107 | #define PRIuLEAST8 "u" 108 | #define PRIxLEAST8 "x" 109 | #define PRIXLEAST8 "X" 110 | #define PRIoFAST8 "o" 111 | #define PRIuFAST8 "u" 112 | #define PRIxFAST8 "x" 113 | #define PRIXFAST8 "X" 114 | 115 | #define PRIo16 "ho" 116 | #define PRIu16 "hu" 117 | #define PRIx16 "hx" 118 | #define PRIX16 "hX" 119 | #define PRIoLEAST16 "ho" 120 | #define PRIuLEAST16 "hu" 121 | #define PRIxLEAST16 "hx" 122 | #define PRIXLEAST16 "hX" 123 | #define PRIoFAST16 "ho" 124 | #define PRIuFAST16 "hu" 125 | #define PRIxFAST16 "hx" 126 | #define PRIXFAST16 "hX" 127 | 128 | #define PRIo32 "I32o" 129 | #define PRIu32 "I32u" 130 | #define PRIx32 "I32x" 131 | #define PRIX32 "I32X" 132 | #define PRIoLEAST32 "I32o" 133 | #define PRIuLEAST32 "I32u" 134 | #define PRIxLEAST32 "I32x" 135 | #define PRIXLEAST32 "I32X" 136 | #define PRIoFAST32 "I32o" 137 | #define PRIuFAST32 "I32u" 138 | #define PRIxFAST32 "I32x" 139 | #define PRIXFAST32 "I32X" 140 | 141 | #define PRIo64 "I64o" 142 | #define PRIu64 "I64u" 143 | #define PRIx64 "I64x" 144 | #define PRIX64 "I64X" 145 | #define PRIoLEAST64 "I64o" 146 | #define PRIuLEAST64 "I64u" 147 | #define PRIxLEAST64 "I64x" 148 | #define PRIXLEAST64 "I64X" 149 | #define PRIoFAST64 "I64o" 150 | #define PRIuFAST64 "I64u" 151 | #define PRIxFAST64 "I64x" 152 | #define PRIXFAST64 "I64X" 153 | 154 | #define PRIoMAX "I64o" 155 | #define PRIuMAX "I64u" 156 | #define PRIxMAX "I64x" 157 | #define PRIXMAX "I64X" 158 | 159 | #define PRIoPTR "Io" 160 | #define PRIuPTR "Iu" 161 | #define PRIxPTR "Ix" 162 | #define PRIXPTR "IX" 163 | 164 | // The fscanf macros for signed integers are: 165 | #define SCNd8 "d" 166 | #define SCNi8 "i" 167 | #define SCNdLEAST8 "d" 168 | #define SCNiLEAST8 "i" 169 | #define SCNdFAST8 "d" 170 | #define SCNiFAST8 "i" 171 | 172 | #define SCNd16 "hd" 173 | #define SCNi16 "hi" 174 | #define SCNdLEAST16 "hd" 175 | #define SCNiLEAST16 "hi" 176 | #define SCNdFAST16 "hd" 177 | #define SCNiFAST16 "hi" 178 | 179 | #define SCNd32 "ld" 180 | #define SCNi32 "li" 181 | #define SCNdLEAST32 "ld" 182 | #define SCNiLEAST32 "li" 183 | #define SCNdFAST32 "ld" 184 | #define SCNiFAST32 "li" 185 | 186 | #define SCNd64 "I64d" 187 | #define SCNi64 "I64i" 188 | #define SCNdLEAST64 "I64d" 189 | #define SCNiLEAST64 "I64i" 190 | #define SCNdFAST64 "I64d" 191 | #define SCNiFAST64 "I64i" 192 | 193 | #define SCNdMAX "I64d" 194 | #define SCNiMAX "I64i" 195 | 196 | #ifdef _WIN64 // [ 197 | # define SCNdPTR "I64d" 198 | # define SCNiPTR "I64i" 199 | #else // _WIN64 ][ 200 | # define SCNdPTR "ld" 201 | # define SCNiPTR "li" 202 | #endif // _WIN64 ] 203 | 204 | // The fscanf macros for unsigned integers are: 205 | #define SCNo8 "o" 206 | #define SCNu8 "u" 207 | #define SCNx8 "x" 208 | #define SCNX8 "X" 209 | #define SCNoLEAST8 "o" 210 | #define SCNuLEAST8 "u" 211 | #define SCNxLEAST8 "x" 212 | #define SCNXLEAST8 "X" 213 | #define SCNoFAST8 "o" 214 | #define SCNuFAST8 "u" 215 | #define SCNxFAST8 "x" 216 | #define SCNXFAST8 "X" 217 | 218 | #define SCNo16 "ho" 219 | #define SCNu16 "hu" 220 | #define SCNx16 "hx" 221 | #define SCNX16 "hX" 222 | #define SCNoLEAST16 "ho" 223 | #define SCNuLEAST16 "hu" 224 | #define SCNxLEAST16 "hx" 225 | #define SCNXLEAST16 "hX" 226 | #define SCNoFAST16 "ho" 227 | #define SCNuFAST16 "hu" 228 | #define SCNxFAST16 "hx" 229 | #define SCNXFAST16 "hX" 230 | 231 | #define SCNo32 "lo" 232 | #define SCNu32 "lu" 233 | #define SCNx32 "lx" 234 | #define SCNX32 "lX" 235 | #define SCNoLEAST32 "lo" 236 | #define SCNuLEAST32 "lu" 237 | #define SCNxLEAST32 "lx" 238 | #define SCNXLEAST32 "lX" 239 | #define SCNoFAST32 "lo" 240 | #define SCNuFAST32 "lu" 241 | #define SCNxFAST32 "lx" 242 | #define SCNXFAST32 "lX" 243 | 244 | #define SCNo64 "I64o" 245 | #define SCNu64 "I64u" 246 | #define SCNx64 "I64x" 247 | #define SCNX64 "I64X" 248 | #define SCNoLEAST64 "I64o" 249 | #define SCNuLEAST64 "I64u" 250 | #define SCNxLEAST64 "I64x" 251 | #define SCNXLEAST64 "I64X" 252 | #define SCNoFAST64 "I64o" 253 | #define SCNuFAST64 "I64u" 254 | #define SCNxFAST64 "I64x" 255 | #define SCNXFAST64 "I64X" 256 | 257 | #define SCNoMAX "I64o" 258 | #define SCNuMAX "I64u" 259 | #define SCNxMAX "I64x" 260 | #define SCNXMAX "I64X" 261 | 262 | #ifdef _WIN64 // [ 263 | # define SCNoPTR "I64o" 264 | # define SCNuPTR "I64u" 265 | # define SCNxPTR "I64x" 266 | # define SCNXPTR "I64X" 267 | #else // _WIN64 ][ 268 | # define SCNoPTR "lo" 269 | # define SCNuPTR "lu" 270 | # define SCNxPTR "lx" 271 | # define SCNXPTR "lX" 272 | #endif // _WIN64 ] 273 | 274 | #endif // __STDC_FORMAT_MACROS ] 275 | 276 | // 7.8.2 Functions for greatest-width integer types 277 | 278 | // 7.8.2.1 The imaxabs function 279 | #define imaxabs _abs64 280 | 281 | // 7.8.2.2 The imaxdiv function 282 | 283 | // This is modified version of div() function from Microsoft's div.c found 284 | // in %MSVC.NET%\crt\src\div.c 285 | #ifdef STATIC_IMAXDIV // [ 286 | static 287 | #else // STATIC_IMAXDIV ][ 288 | _inline 289 | #endif // STATIC_IMAXDIV ] 290 | imaxdiv_t __cdecl imaxdiv(intmax_t numer, intmax_t denom) 291 | { 292 | imaxdiv_t result; 293 | 294 | result.quot = numer / denom; 295 | result.rem = numer % denom; 296 | 297 | if (numer < 0 && result.rem > 0) { 298 | // did division wrong; must fix up 299 | ++result.quot; 300 | result.rem -= denom; 301 | } 302 | 303 | return result; 304 | } 305 | 306 | // 7.8.2.3 The strtoimax and strtoumax functions 307 | #define strtoimax _strtoi64 308 | #define strtoumax _strtoui64 309 | 310 | // 7.8.2.4 The wcstoimax and wcstoumax functions 311 | #define wcstoimax _wcstoi64 312 | #define wcstoumax _wcstoui64 313 | 314 | #endif // _MSC_VER >= 1800 315 | 316 | #endif // _MSC_INTTYPES_H_ ] 317 | -------------------------------------------------------------------------------- /include/tools/rapidjson/msinttypes/stdint.h: -------------------------------------------------------------------------------- 1 | // ISO C9x compliant stdint.h for Microsoft Visual Studio 2 | // Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124 3 | // 4 | // Copyright (c) 2006-2013 Alexander Chemeris 5 | // 6 | // Redistribution and use in source and binary forms, with or without 7 | // modification, are permitted provided that the following conditions are met: 8 | // 9 | // 1. Redistributions of source code must retain the above copyright notice, 10 | // this list of conditions and the following disclaimer. 11 | // 12 | // 2. Redistributions in binary form must reproduce the above copyright 13 | // notice, this list of conditions and the following disclaimer in the 14 | // documentation and/or other materials provided with the distribution. 15 | // 16 | // 3. Neither the name of the product nor the names of its contributors may 17 | // be used to endorse or promote products derived from this software 18 | // without specific prior written permission. 19 | // 20 | // THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED 21 | // WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF 22 | // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO 23 | // EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 24 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 25 | // PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 26 | // OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 27 | // WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 28 | // OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 29 | // ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | // 31 | /////////////////////////////////////////////////////////////////////////////// 32 | 33 | // The above software in this distribution may have been modified by 34 | // THL A29 Limited ("Tencent Modifications"). 35 | // All Tencent Modifications are Copyright (C) 2015 THL A29 Limited. 36 | 37 | #ifndef _MSC_VER // [ 38 | #error "Use this header only with Microsoft Visual C++ compilers!" 39 | #endif // _MSC_VER ] 40 | 41 | #ifndef _MSC_STDINT_H_ // [ 42 | #define _MSC_STDINT_H_ 43 | 44 | #if _MSC_VER > 1000 45 | #pragma once 46 | #endif 47 | 48 | // miloyip: Originally Visual Studio 2010 uses its own stdint.h. However it generates warning with INT64_C(), so change to use this file for vs2010. 49 | #if _MSC_VER >= 1600 // [ 50 | #include 51 | 52 | #if !defined(__cplusplus) || defined(__STDC_CONSTANT_MACROS) // [ See footnote 224 at page 260 53 | 54 | #undef INT8_C 55 | #undef INT16_C 56 | #undef INT32_C 57 | #undef INT64_C 58 | #undef UINT8_C 59 | #undef UINT16_C 60 | #undef UINT32_C 61 | #undef UINT64_C 62 | 63 | // 7.18.4.1 Macros for minimum-width integer constants 64 | 65 | #define INT8_C(val) val##i8 66 | #define INT16_C(val) val##i16 67 | #define INT32_C(val) val##i32 68 | #define INT64_C(val) val##i64 69 | 70 | #define UINT8_C(val) val##ui8 71 | #define UINT16_C(val) val##ui16 72 | #define UINT32_C(val) val##ui32 73 | #define UINT64_C(val) val##ui64 74 | 75 | // 7.18.4.2 Macros for greatest-width integer constants 76 | // These #ifndef's are needed to prevent collisions with . 77 | // Check out Issue 9 for the details. 78 | #ifndef INTMAX_C // [ 79 | # define INTMAX_C INT64_C 80 | #endif // INTMAX_C ] 81 | #ifndef UINTMAX_C // [ 82 | # define UINTMAX_C UINT64_C 83 | #endif // UINTMAX_C ] 84 | 85 | #endif // __STDC_CONSTANT_MACROS ] 86 | 87 | #else // ] _MSC_VER >= 1700 [ 88 | 89 | #include 90 | 91 | // For Visual Studio 6 in C++ mode and for many Visual Studio versions when 92 | // compiling for ARM we have to wrap include with 'extern "C++" {}' 93 | // or compiler would give many errors like this: 94 | // error C2733: second C linkage of overloaded function 'wmemchr' not allowed 95 | #if defined(__cplusplus) && !defined(_M_ARM) 96 | extern "C" { 97 | #endif 98 | # include 99 | #if defined(__cplusplus) && !defined(_M_ARM) 100 | } 101 | #endif 102 | 103 | // Define _W64 macros to mark types changing their size, like intptr_t. 104 | #ifndef _W64 105 | # if !defined(__midl) && (defined(_X86_) || defined(_M_IX86)) && _MSC_VER >= 1300 106 | # define _W64 __w64 107 | # else 108 | # define _W64 109 | # endif 110 | #endif 111 | 112 | 113 | // 7.18.1 Integer types 114 | 115 | // 7.18.1.1 Exact-width integer types 116 | 117 | // Visual Studio 6 and Embedded Visual C++ 4 doesn't 118 | // realize that, e.g. char has the same size as __int8 119 | // so we give up on __intX for them. 120 | #if (_MSC_VER < 1300) 121 | typedef signed char int8_t; 122 | typedef signed short int16_t; 123 | typedef signed int int32_t; 124 | typedef unsigned char uint8_t; 125 | typedef unsigned short uint16_t; 126 | typedef unsigned int uint32_t; 127 | #else 128 | typedef signed __int8 int8_t; 129 | typedef signed __int16 int16_t; 130 | typedef signed __int32 int32_t; 131 | typedef unsigned __int8 uint8_t; 132 | typedef unsigned __int16 uint16_t; 133 | typedef unsigned __int32 uint32_t; 134 | #endif 135 | typedef signed __int64 int64_t; 136 | typedef unsigned __int64 uint64_t; 137 | 138 | 139 | // 7.18.1.2 Minimum-width integer types 140 | typedef int8_t int_least8_t; 141 | typedef int16_t int_least16_t; 142 | typedef int32_t int_least32_t; 143 | typedef int64_t int_least64_t; 144 | typedef uint8_t uint_least8_t; 145 | typedef uint16_t uint_least16_t; 146 | typedef uint32_t uint_least32_t; 147 | typedef uint64_t uint_least64_t; 148 | 149 | // 7.18.1.3 Fastest minimum-width integer types 150 | typedef int8_t int_fast8_t; 151 | typedef int16_t int_fast16_t; 152 | typedef int32_t int_fast32_t; 153 | typedef int64_t int_fast64_t; 154 | typedef uint8_t uint_fast8_t; 155 | typedef uint16_t uint_fast16_t; 156 | typedef uint32_t uint_fast32_t; 157 | typedef uint64_t uint_fast64_t; 158 | 159 | // 7.18.1.4 Integer types capable of holding object pointers 160 | #ifdef _WIN64 // [ 161 | typedef signed __int64 intptr_t; 162 | typedef unsigned __int64 uintptr_t; 163 | #else // _WIN64 ][ 164 | typedef _W64 signed int intptr_t; 165 | typedef _W64 unsigned int uintptr_t; 166 | #endif // _WIN64 ] 167 | 168 | // 7.18.1.5 Greatest-width integer types 169 | typedef int64_t intmax_t; 170 | typedef uint64_t uintmax_t; 171 | 172 | 173 | // 7.18.2 Limits of specified-width integer types 174 | 175 | #if !defined(__cplusplus) || defined(__STDC_LIMIT_MACROS) // [ See footnote 220 at page 257 and footnote 221 at page 259 176 | 177 | // 7.18.2.1 Limits of exact-width integer types 178 | #define INT8_MIN ((int8_t)_I8_MIN) 179 | #define INT8_MAX _I8_MAX 180 | #define INT16_MIN ((int16_t)_I16_MIN) 181 | #define INT16_MAX _I16_MAX 182 | #define INT32_MIN ((int32_t)_I32_MIN) 183 | #define INT32_MAX _I32_MAX 184 | #define INT64_MIN ((int64_t)_I64_MIN) 185 | #define INT64_MAX _I64_MAX 186 | #define UINT8_MAX _UI8_MAX 187 | #define UINT16_MAX _UI16_MAX 188 | #define UINT32_MAX _UI32_MAX 189 | #define UINT64_MAX _UI64_MAX 190 | 191 | // 7.18.2.2 Limits of minimum-width integer types 192 | #define INT_LEAST8_MIN INT8_MIN 193 | #define INT_LEAST8_MAX INT8_MAX 194 | #define INT_LEAST16_MIN INT16_MIN 195 | #define INT_LEAST16_MAX INT16_MAX 196 | #define INT_LEAST32_MIN INT32_MIN 197 | #define INT_LEAST32_MAX INT32_MAX 198 | #define INT_LEAST64_MIN INT64_MIN 199 | #define INT_LEAST64_MAX INT64_MAX 200 | #define UINT_LEAST8_MAX UINT8_MAX 201 | #define UINT_LEAST16_MAX UINT16_MAX 202 | #define UINT_LEAST32_MAX UINT32_MAX 203 | #define UINT_LEAST64_MAX UINT64_MAX 204 | 205 | // 7.18.2.3 Limits of fastest minimum-width integer types 206 | #define INT_FAST8_MIN INT8_MIN 207 | #define INT_FAST8_MAX INT8_MAX 208 | #define INT_FAST16_MIN INT16_MIN 209 | #define INT_FAST16_MAX INT16_MAX 210 | #define INT_FAST32_MIN INT32_MIN 211 | #define INT_FAST32_MAX INT32_MAX 212 | #define INT_FAST64_MIN INT64_MIN 213 | #define INT_FAST64_MAX INT64_MAX 214 | #define UINT_FAST8_MAX UINT8_MAX 215 | #define UINT_FAST16_MAX UINT16_MAX 216 | #define UINT_FAST32_MAX UINT32_MAX 217 | #define UINT_FAST64_MAX UINT64_MAX 218 | 219 | // 7.18.2.4 Limits of integer types capable of holding object pointers 220 | #ifdef _WIN64 // [ 221 | # define INTPTR_MIN INT64_MIN 222 | # define INTPTR_MAX INT64_MAX 223 | # define UINTPTR_MAX UINT64_MAX 224 | #else // _WIN64 ][ 225 | # define INTPTR_MIN INT32_MIN 226 | # define INTPTR_MAX INT32_MAX 227 | # define UINTPTR_MAX UINT32_MAX 228 | #endif // _WIN64 ] 229 | 230 | // 7.18.2.5 Limits of greatest-width integer types 231 | #define INTMAX_MIN INT64_MIN 232 | #define INTMAX_MAX INT64_MAX 233 | #define UINTMAX_MAX UINT64_MAX 234 | 235 | // 7.18.3 Limits of other integer types 236 | 237 | #ifdef _WIN64 // [ 238 | # define PTRDIFF_MIN _I64_MIN 239 | # define PTRDIFF_MAX _I64_MAX 240 | #else // _WIN64 ][ 241 | # define PTRDIFF_MIN _I32_MIN 242 | # define PTRDIFF_MAX _I32_MAX 243 | #endif // _WIN64 ] 244 | 245 | #define SIG_ATOMIC_MIN INT_MIN 246 | #define SIG_ATOMIC_MAX INT_MAX 247 | 248 | #ifndef SIZE_MAX // [ 249 | # ifdef _WIN64 // [ 250 | # define SIZE_MAX _UI64_MAX 251 | # else // _WIN64 ][ 252 | # define SIZE_MAX _UI32_MAX 253 | # endif // _WIN64 ] 254 | #endif // SIZE_MAX ] 255 | 256 | // WCHAR_MIN and WCHAR_MAX are also defined in 257 | #ifndef WCHAR_MIN // [ 258 | # define WCHAR_MIN 0 259 | #endif // WCHAR_MIN ] 260 | #ifndef WCHAR_MAX // [ 261 | # define WCHAR_MAX _UI16_MAX 262 | #endif // WCHAR_MAX ] 263 | 264 | #define WINT_MIN 0 265 | #define WINT_MAX _UI16_MAX 266 | 267 | #endif // __STDC_LIMIT_MACROS ] 268 | 269 | 270 | // 7.18.4 Limits of other integer types 271 | 272 | #if !defined(__cplusplus) || defined(__STDC_CONSTANT_MACROS) // [ See footnote 224 at page 260 273 | 274 | // 7.18.4.1 Macros for minimum-width integer constants 275 | 276 | #define INT8_C(val) val##i8 277 | #define INT16_C(val) val##i16 278 | #define INT32_C(val) val##i32 279 | #define INT64_C(val) val##i64 280 | 281 | #define UINT8_C(val) val##ui8 282 | #define UINT16_C(val) val##ui16 283 | #define UINT32_C(val) val##ui32 284 | #define UINT64_C(val) val##ui64 285 | 286 | // 7.18.4.2 Macros for greatest-width integer constants 287 | // These #ifndef's are needed to prevent collisions with . 288 | // Check out Issue 9 for the details. 289 | #ifndef INTMAX_C // [ 290 | # define INTMAX_C INT64_C 291 | #endif // INTMAX_C ] 292 | #ifndef UINTMAX_C // [ 293 | # define UINTMAX_C UINT64_C 294 | #endif // UINTMAX_C ] 295 | 296 | #endif // __STDC_CONSTANT_MACROS ] 297 | 298 | #endif // _MSC_VER >= 1600 ] 299 | 300 | #endif // _MSC_STDINT_H_ ] 301 | -------------------------------------------------------------------------------- /include/tools/rapidjson/ostreamwrapper.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_OSTREAMWRAPPER_H_ 16 | #define RAPIDJSON_OSTREAMWRAPPER_H_ 17 | 18 | #include "stream.h" 19 | #include 20 | 21 | #ifdef __clang__ 22 | RAPIDJSON_DIAG_PUSH 23 | RAPIDJSON_DIAG_OFF(padded) 24 | #endif 25 | 26 | RAPIDJSON_NAMESPACE_BEGIN 27 | 28 | //! Wrapper of \c std::basic_ostream into RapidJSON's Stream concept. 29 | /*! 30 | The classes can be wrapped including but not limited to: 31 | 32 | - \c std::ostringstream 33 | - \c std::stringstream 34 | - \c std::wpstringstream 35 | - \c std::wstringstream 36 | - \c std::ifstream 37 | - \c std::fstream 38 | - \c std::wofstream 39 | - \c std::wfstream 40 | 41 | \tparam StreamType Class derived from \c std::basic_ostream. 42 | */ 43 | 44 | template 45 | class BasicOStreamWrapper { 46 | public: 47 | typedef typename StreamType::char_type Ch; 48 | BasicOStreamWrapper(StreamType& stream) : stream_(stream) {} 49 | 50 | void Put(Ch c) { 51 | stream_.put(c); 52 | } 53 | 54 | void Flush() { 55 | stream_.flush(); 56 | } 57 | 58 | // Not implemented 59 | char Peek() const { RAPIDJSON_ASSERT(false); return 0; } 60 | char Take() { RAPIDJSON_ASSERT(false); return 0; } 61 | size_t Tell() const { RAPIDJSON_ASSERT(false); return 0; } 62 | char* PutBegin() { RAPIDJSON_ASSERT(false); return 0; } 63 | size_t PutEnd(char*) { RAPIDJSON_ASSERT(false); return 0; } 64 | 65 | private: 66 | BasicOStreamWrapper(const BasicOStreamWrapper&); 67 | BasicOStreamWrapper& operator=(const BasicOStreamWrapper&); 68 | 69 | StreamType& stream_; 70 | }; 71 | 72 | typedef BasicOStreamWrapper OStreamWrapper; 73 | typedef BasicOStreamWrapper WOStreamWrapper; 74 | 75 | #ifdef __clang__ 76 | RAPIDJSON_DIAG_POP 77 | #endif 78 | 79 | RAPIDJSON_NAMESPACE_END 80 | 81 | #endif // RAPIDJSON_OSTREAMWRAPPER_H_ 82 | -------------------------------------------------------------------------------- /include/tools/rapidjson/prettywriter.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_PRETTYWRITER_H_ 16 | #define RAPIDJSON_PRETTYWRITER_H_ 17 | 18 | #include "writer.h" 19 | 20 | #ifdef __GNUC__ 21 | RAPIDJSON_DIAG_PUSH 22 | RAPIDJSON_DIAG_OFF(effc++) 23 | #endif 24 | 25 | #if defined(__clang__) 26 | RAPIDJSON_DIAG_PUSH 27 | RAPIDJSON_DIAG_OFF(c++98-compat) 28 | #endif 29 | 30 | RAPIDJSON_NAMESPACE_BEGIN 31 | 32 | //! Combination of PrettyWriter format flags. 33 | /*! \see PrettyWriter::SetFormatOptions 34 | */ 35 | enum PrettyFormatOptions { 36 | kFormatDefault = 0, //!< Default pretty formatting. 37 | kFormatSingleLineArray = 1 //!< Format arrays on a single line. 38 | }; 39 | 40 | //! Writer with indentation and spacing. 41 | /*! 42 | \tparam OutputStream Type of output os. 43 | \tparam SourceEncoding Encoding of source string. 44 | \tparam TargetEncoding Encoding of output stream. 45 | \tparam StackAllocator Type of allocator for allocating memory of stack. 46 | */ 47 | template, typename TargetEncoding = UTF8<>, typename StackAllocator = CrtAllocator, unsigned writeFlags = kWriteDefaultFlags> 48 | class PrettyWriter : public Writer { 49 | public: 50 | typedef Writer Base; 51 | typedef typename Base::Ch Ch; 52 | 53 | //! Constructor 54 | /*! \param os Output stream. 55 | \param allocator User supplied allocator. If it is null, it will create a private one. 56 | \param levelDepth Initial capacity of stack. 57 | */ 58 | explicit PrettyWriter(OutputStream& os, StackAllocator* allocator = 0, size_t levelDepth = Base::kDefaultLevelDepth) : 59 | Base(os, allocator, levelDepth), indentChar_(' '), indentCharCount_(4), formatOptions_(kFormatDefault) {} 60 | 61 | 62 | explicit PrettyWriter(StackAllocator* allocator = 0, size_t levelDepth = Base::kDefaultLevelDepth) : 63 | Base(allocator, levelDepth), indentChar_(' '), indentCharCount_(4) {} 64 | 65 | #if RAPIDJSON_HAS_CXX11_RVALUE_REFS 66 | PrettyWriter(PrettyWriter&& rhs) : 67 | Base(std::forward(rhs)), indentChar_(rhs.indentChar_), indentCharCount_(rhs.indentCharCount_), formatOptions_(rhs.formatOptions_) {} 68 | #endif 69 | 70 | //! Set custom indentation. 71 | /*! \param indentChar Character for indentation. Must be whitespace character (' ', '\\t', '\\n', '\\r'). 72 | \param indentCharCount Number of indent characters for each indentation level. 73 | \note The default indentation is 4 spaces. 74 | */ 75 | PrettyWriter& SetIndent(Ch indentChar, unsigned indentCharCount) { 76 | RAPIDJSON_ASSERT(indentChar == ' ' || indentChar == '\t' || indentChar == '\n' || indentChar == '\r'); 77 | indentChar_ = indentChar; 78 | indentCharCount_ = indentCharCount; 79 | return *this; 80 | } 81 | 82 | //! Set pretty writer formatting options. 83 | /*! \param options Formatting options. 84 | */ 85 | PrettyWriter& SetFormatOptions(PrettyFormatOptions options) { 86 | formatOptions_ = options; 87 | return *this; 88 | } 89 | 90 | /*! @name Implementation of Handler 91 | \see Handler 92 | */ 93 | //@{ 94 | 95 | bool Null() { PrettyPrefix(kNullType); return Base::EndValue(Base::WriteNull()); } 96 | bool Bool(bool b) { PrettyPrefix(b ? kTrueType : kFalseType); return Base::EndValue(Base::WriteBool(b)); } 97 | bool Int(int i) { PrettyPrefix(kNumberType); return Base::EndValue(Base::WriteInt(i)); } 98 | bool Uint(unsigned u) { PrettyPrefix(kNumberType); return Base::EndValue(Base::WriteUint(u)); } 99 | bool Int64(int64_t i64) { PrettyPrefix(kNumberType); return Base::EndValue(Base::WriteInt64(i64)); } 100 | bool Uint64(uint64_t u64) { PrettyPrefix(kNumberType); return Base::EndValue(Base::WriteUint64(u64)); } 101 | bool Double(double d) { PrettyPrefix(kNumberType); return Base::EndValue(Base::WriteDouble(d)); } 102 | 103 | bool RawNumber(const Ch* str, SizeType length, bool copy = false) { 104 | RAPIDJSON_ASSERT(str != 0); 105 | (void)copy; 106 | PrettyPrefix(kNumberType); 107 | return Base::EndValue(Base::WriteString(str, length)); 108 | } 109 | 110 | bool String(const Ch* str, SizeType length, bool copy = false) { 111 | RAPIDJSON_ASSERT(str != 0); 112 | (void)copy; 113 | PrettyPrefix(kStringType); 114 | return Base::EndValue(Base::WriteString(str, length)); 115 | } 116 | 117 | #if RAPIDJSON_HAS_STDSTRING 118 | bool String(const std::basic_string& str) { 119 | return String(str.data(), SizeType(str.size())); 120 | } 121 | #endif 122 | 123 | bool StartObject() { 124 | PrettyPrefix(kObjectType); 125 | new (Base::level_stack_.template Push()) typename Base::Level(false); 126 | return Base::WriteStartObject(); 127 | } 128 | 129 | bool Key(const Ch* str, SizeType length, bool copy = false) { return String(str, length, copy); } 130 | 131 | #if RAPIDJSON_HAS_STDSTRING 132 | bool Key(const std::basic_string& str) { 133 | return Key(str.data(), SizeType(str.size())); 134 | } 135 | #endif 136 | 137 | bool EndObject(SizeType memberCount = 0) { 138 | (void)memberCount; 139 | RAPIDJSON_ASSERT(Base::level_stack_.GetSize() >= sizeof(typename Base::Level)); // not inside an Object 140 | RAPIDJSON_ASSERT(!Base::level_stack_.template Top()->inArray); // currently inside an Array, not Object 141 | RAPIDJSON_ASSERT(0 == Base::level_stack_.template Top()->valueCount % 2); // Object has a Key without a Value 142 | 143 | bool empty = Base::level_stack_.template Pop(1)->valueCount == 0; 144 | 145 | if (!empty) { 146 | Base::os_->Put('\n'); 147 | WriteIndent(); 148 | } 149 | bool ret = Base::EndValue(Base::WriteEndObject()); 150 | (void)ret; 151 | RAPIDJSON_ASSERT(ret == true); 152 | if (Base::level_stack_.Empty()) // end of json text 153 | Base::Flush(); 154 | return true; 155 | } 156 | 157 | bool StartArray() { 158 | PrettyPrefix(kArrayType); 159 | new (Base::level_stack_.template Push()) typename Base::Level(true); 160 | return Base::WriteStartArray(); 161 | } 162 | 163 | bool EndArray(SizeType memberCount = 0) { 164 | (void)memberCount; 165 | RAPIDJSON_ASSERT(Base::level_stack_.GetSize() >= sizeof(typename Base::Level)); 166 | RAPIDJSON_ASSERT(Base::level_stack_.template Top()->inArray); 167 | bool empty = Base::level_stack_.template Pop(1)->valueCount == 0; 168 | 169 | if (!empty && !(formatOptions_ & kFormatSingleLineArray)) { 170 | Base::os_->Put('\n'); 171 | WriteIndent(); 172 | } 173 | bool ret = Base::EndValue(Base::WriteEndArray()); 174 | (void)ret; 175 | RAPIDJSON_ASSERT(ret == true); 176 | if (Base::level_stack_.Empty()) // end of json text 177 | Base::Flush(); 178 | return true; 179 | } 180 | 181 | //@} 182 | 183 | /*! @name Convenience extensions */ 184 | //@{ 185 | 186 | //! Simpler but slower overload. 187 | bool String(const Ch* str) { return String(str, internal::StrLen(str)); } 188 | bool Key(const Ch* str) { return Key(str, internal::StrLen(str)); } 189 | 190 | //@} 191 | 192 | //! Write a raw JSON value. 193 | /*! 194 | For user to write a stringified JSON as a value. 195 | 196 | \param json A well-formed JSON value. It should not contain null character within [0, length - 1] range. 197 | \param length Length of the json. 198 | \param type Type of the root of json. 199 | \note When using PrettyWriter::RawValue(), the result json may not be indented correctly. 200 | */ 201 | bool RawValue(const Ch* json, size_t length, Type type) { 202 | RAPIDJSON_ASSERT(json != 0); 203 | PrettyPrefix(type); 204 | return Base::EndValue(Base::WriteRawValue(json, length)); 205 | } 206 | 207 | protected: 208 | void PrettyPrefix(Type type) { 209 | (void)type; 210 | if (Base::level_stack_.GetSize() != 0) { // this value is not at root 211 | typename Base::Level* level = Base::level_stack_.template Top(); 212 | 213 | if (level->inArray) { 214 | if (level->valueCount > 0) { 215 | Base::os_->Put(','); // add comma if it is not the first element in array 216 | if (formatOptions_ & kFormatSingleLineArray) 217 | Base::os_->Put(' '); 218 | } 219 | 220 | if (!(formatOptions_ & kFormatSingleLineArray)) { 221 | Base::os_->Put('\n'); 222 | WriteIndent(); 223 | } 224 | } 225 | else { // in object 226 | if (level->valueCount > 0) { 227 | if (level->valueCount % 2 == 0) { 228 | Base::os_->Put(','); 229 | Base::os_->Put('\n'); 230 | } 231 | else { 232 | Base::os_->Put(':'); 233 | Base::os_->Put(' '); 234 | } 235 | } 236 | else 237 | Base::os_->Put('\n'); 238 | 239 | if (level->valueCount % 2 == 0) 240 | WriteIndent(); 241 | } 242 | if (!level->inArray && level->valueCount % 2 == 0) 243 | RAPIDJSON_ASSERT(type == kStringType); // if it's in object, then even number should be a name 244 | level->valueCount++; 245 | } 246 | else { 247 | RAPIDJSON_ASSERT(!Base::hasRoot_); // Should only has one and only one root. 248 | Base::hasRoot_ = true; 249 | } 250 | } 251 | 252 | void WriteIndent() { 253 | size_t count = (Base::level_stack_.GetSize() / sizeof(typename Base::Level)) * indentCharCount_; 254 | PutN(*Base::os_, static_cast(indentChar_), count); 255 | } 256 | 257 | Ch indentChar_; 258 | unsigned indentCharCount_; 259 | PrettyFormatOptions formatOptions_; 260 | 261 | private: 262 | // Prohibit copy constructor & assignment operator. 263 | PrettyWriter(const PrettyWriter&); 264 | PrettyWriter& operator=(const PrettyWriter&); 265 | }; 266 | 267 | RAPIDJSON_NAMESPACE_END 268 | 269 | #if defined(__clang__) 270 | RAPIDJSON_DIAG_POP 271 | #endif 272 | 273 | #ifdef __GNUC__ 274 | RAPIDJSON_DIAG_POP 275 | #endif 276 | 277 | #endif // RAPIDJSON_RAPIDJSON_H_ 278 | -------------------------------------------------------------------------------- /include/tools/rapidjson/stream.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #include "rapidjson.h" 16 | 17 | #ifndef RAPIDJSON_STREAM_H_ 18 | #define RAPIDJSON_STREAM_H_ 19 | 20 | #include "encodings.h" 21 | 22 | RAPIDJSON_NAMESPACE_BEGIN 23 | 24 | /////////////////////////////////////////////////////////////////////////////// 25 | // Stream 26 | 27 | /*! \class rapidjson::Stream 28 | \brief Concept for reading and writing characters. 29 | 30 | For read-only stream, no need to implement PutBegin(), Put(), Flush() and PutEnd(). 31 | 32 | For write-only stream, only need to implement Put() and Flush(). 33 | 34 | \code 35 | concept Stream { 36 | typename Ch; //!< Character type of the stream. 37 | 38 | //! Read the current character from stream without moving the read cursor. 39 | Ch Peek() const; 40 | 41 | //! Read the current character from stream and moving the read cursor to next character. 42 | Ch Take(); 43 | 44 | //! Get the current read cursor. 45 | //! \return Number of characters read from start. 46 | size_t Tell(); 47 | 48 | //! Begin writing operation at the current read pointer. 49 | //! \return The begin writer pointer. 50 | Ch* PutBegin(); 51 | 52 | //! Write a character. 53 | void Put(Ch c); 54 | 55 | //! Flush the buffer. 56 | void Flush(); 57 | 58 | //! End the writing operation. 59 | //! \param begin The begin write pointer returned by PutBegin(). 60 | //! \return Number of characters written. 61 | size_t PutEnd(Ch* begin); 62 | } 63 | \endcode 64 | */ 65 | 66 | //! Provides additional information for stream. 67 | /*! 68 | By using traits pattern, this type provides a default configuration for stream. 69 | For custom stream, this type can be specialized for other configuration. 70 | See TEST(Reader, CustomStringStream) in readertest.cpp for example. 71 | */ 72 | template 73 | struct StreamTraits { 74 | //! Whether to make local copy of stream for optimization during parsing. 75 | /*! 76 | By default, for safety, streams do not use local copy optimization. 77 | Stream that can be copied fast should specialize this, like StreamTraits. 78 | */ 79 | enum { copyOptimization = 0 }; 80 | }; 81 | 82 | //! Reserve n characters for writing to a stream. 83 | template 84 | inline void PutReserve(Stream& stream, size_t count) { 85 | (void)stream; 86 | (void)count; 87 | } 88 | 89 | //! Write character to a stream, presuming buffer is reserved. 90 | template 91 | inline void PutUnsafe(Stream& stream, typename Stream::Ch c) { 92 | stream.Put(c); 93 | } 94 | 95 | //! Put N copies of a character to a stream. 96 | template 97 | inline void PutN(Stream& stream, Ch c, size_t n) { 98 | PutReserve(stream, n); 99 | for (size_t i = 0; i < n; i++) 100 | PutUnsafe(stream, c); 101 | } 102 | 103 | /////////////////////////////////////////////////////////////////////////////// 104 | // GenericStreamWrapper 105 | 106 | //! A Stream Wrapper 107 | /*! \tThis string stream is a wrapper for any stream by just forwarding any 108 | \treceived message to the origin stream. 109 | \note implements Stream concept 110 | */ 111 | 112 | #if defined(_MSC_VER) && _MSC_VER <= 1800 113 | RAPIDJSON_DIAG_PUSH 114 | RAPIDJSON_DIAG_OFF(4702) // unreachable code 115 | RAPIDJSON_DIAG_OFF(4512) // assignment operator could not be generated 116 | #endif 117 | 118 | template > 119 | class GenericStreamWrapper { 120 | public: 121 | typedef typename Encoding::Ch Ch; 122 | GenericStreamWrapper(InputStream& is): is_(is) {} 123 | 124 | Ch Peek() const { return is_.Peek(); } 125 | Ch Take() { return is_.Take(); } 126 | size_t Tell() { return is_.Tell(); } 127 | Ch* PutBegin() { return is_.PutBegin(); } 128 | void Put(Ch ch) { is_.Put(ch); } 129 | void Flush() { is_.Flush(); } 130 | size_t PutEnd(Ch* ch) { return is_.PutEnd(ch); } 131 | 132 | // wrapper for MemoryStream 133 | const Ch* Peek4() const { return is_.Peek4(); } 134 | 135 | // wrapper for AutoUTFInputStream 136 | UTFType GetType() const { return is_.GetType(); } 137 | bool HasBOM() const { return is_.HasBOM(); } 138 | 139 | protected: 140 | InputStream& is_; 141 | }; 142 | 143 | #if defined(_MSC_VER) && _MSC_VER <= 1800 144 | RAPIDJSON_DIAG_POP 145 | #endif 146 | 147 | /////////////////////////////////////////////////////////////////////////////// 148 | // StringStream 149 | 150 | //! Read-only string stream. 151 | /*! \note implements Stream concept 152 | */ 153 | template 154 | struct GenericStringStream { 155 | typedef typename Encoding::Ch Ch; 156 | 157 | GenericStringStream(const Ch *src) : src_(src), head_(src) {} 158 | 159 | Ch Peek() const { return *src_; } 160 | Ch Take() { return *src_++; } 161 | size_t Tell() const { return static_cast(src_ - head_); } 162 | 163 | Ch* PutBegin() { RAPIDJSON_ASSERT(false); return 0; } 164 | void Put(Ch) { RAPIDJSON_ASSERT(false); } 165 | void Flush() { RAPIDJSON_ASSERT(false); } 166 | size_t PutEnd(Ch*) { RAPIDJSON_ASSERT(false); return 0; } 167 | 168 | const Ch* src_; //!< Current read position. 169 | const Ch* head_; //!< Original head of the string. 170 | }; 171 | 172 | template 173 | struct StreamTraits > { 174 | enum { copyOptimization = 1 }; 175 | }; 176 | 177 | //! String stream with UTF8 encoding. 178 | typedef GenericStringStream > StringStream; 179 | 180 | /////////////////////////////////////////////////////////////////////////////// 181 | // InsituStringStream 182 | 183 | //! A read-write string stream. 184 | /*! This string stream is particularly designed for in-situ parsing. 185 | \note implements Stream concept 186 | */ 187 | template 188 | struct GenericInsituStringStream { 189 | typedef typename Encoding::Ch Ch; 190 | 191 | GenericInsituStringStream(Ch *src) : src_(src), dst_(0), head_(src) {} 192 | 193 | // Read 194 | Ch Peek() { return *src_; } 195 | Ch Take() { return *src_++; } 196 | size_t Tell() { return static_cast(src_ - head_); } 197 | 198 | // Write 199 | void Put(Ch c) { RAPIDJSON_ASSERT(dst_ != 0); *dst_++ = c; } 200 | 201 | Ch* PutBegin() { return dst_ = src_; } 202 | size_t PutEnd(Ch* begin) { return static_cast(dst_ - begin); } 203 | void Flush() {} 204 | 205 | Ch* Push(size_t count) { Ch* begin = dst_; dst_ += count; return begin; } 206 | void Pop(size_t count) { dst_ -= count; } 207 | 208 | Ch* src_; 209 | Ch* dst_; 210 | Ch* head_; 211 | }; 212 | 213 | template 214 | struct StreamTraits > { 215 | enum { copyOptimization = 1 }; 216 | }; 217 | 218 | //! Insitu string stream with UTF8 encoding. 219 | typedef GenericInsituStringStream > InsituStringStream; 220 | 221 | RAPIDJSON_NAMESPACE_END 222 | 223 | #endif // RAPIDJSON_STREAM_H_ 224 | -------------------------------------------------------------------------------- /include/tools/rapidjson/stringbuffer.h: -------------------------------------------------------------------------------- 1 | // Tencent is pleased to support the open source community by making RapidJSON available. 2 | // 3 | // Copyright (C) 2015 THL A29 Limited, a Tencent company, and Milo Yip. All rights reserved. 4 | // 5 | // Licensed under the MIT License (the "License"); you may not use this file except 6 | // in compliance with the License. You may obtain a copy of the License at 7 | // 8 | // http://opensource.org/licenses/MIT 9 | // 10 | // Unless required by applicable law or agreed to in writing, software distributed 11 | // under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR 12 | // CONDITIONS OF ANY KIND, either express or implied. See the License for the 13 | // specific language governing permissions and limitations under the License. 14 | 15 | #ifndef RAPIDJSON_STRINGBUFFER_H_ 16 | #define RAPIDJSON_STRINGBUFFER_H_ 17 | 18 | #include "stream.h" 19 | #include "internal/stack.h" 20 | 21 | #if RAPIDJSON_HAS_CXX11_RVALUE_REFS 22 | #include // std::move 23 | #endif 24 | 25 | #include "internal/stack.h" 26 | 27 | #if defined(__clang__) 28 | RAPIDJSON_DIAG_PUSH 29 | RAPIDJSON_DIAG_OFF(c++98-compat) 30 | #endif 31 | 32 | RAPIDJSON_NAMESPACE_BEGIN 33 | 34 | //! Represents an in-memory output stream. 35 | /*! 36 | \tparam Encoding Encoding of the stream. 37 | \tparam Allocator type for allocating memory buffer. 38 | \note implements Stream concept 39 | */ 40 | template 41 | class GenericStringBuffer { 42 | public: 43 | typedef typename Encoding::Ch Ch; 44 | 45 | GenericStringBuffer(Allocator* allocator = 0, size_t capacity = kDefaultCapacity) : stack_(allocator, capacity) {} 46 | 47 | #if RAPIDJSON_HAS_CXX11_RVALUE_REFS 48 | GenericStringBuffer(GenericStringBuffer&& rhs) : stack_(std::move(rhs.stack_)) {} 49 | GenericStringBuffer& operator=(GenericStringBuffer&& rhs) { 50 | if (&rhs != this) 51 | stack_ = std::move(rhs.stack_); 52 | return *this; 53 | } 54 | #endif 55 | 56 | void Put(Ch c) { *stack_.template Push() = c; } 57 | void PutUnsafe(Ch c) { *stack_.template PushUnsafe() = c; } 58 | void Flush() {} 59 | 60 | void Clear() { stack_.Clear(); } 61 | void ShrinkToFit() { 62 | // Push and pop a null terminator. This is safe. 63 | *stack_.template Push() = '\0'; 64 | stack_.ShrinkToFit(); 65 | stack_.template Pop(1); 66 | } 67 | 68 | void Reserve(size_t count) { stack_.template Reserve(count); } 69 | Ch* Push(size_t count) { return stack_.template Push(count); } 70 | Ch* PushUnsafe(size_t count) { return stack_.template PushUnsafe(count); } 71 | void Pop(size_t count) { stack_.template Pop(count); } 72 | 73 | const Ch* GetString() const { 74 | // Push and pop a null terminator. This is safe. 75 | *stack_.template Push() = '\0'; 76 | stack_.template Pop(1); 77 | 78 | return stack_.template Bottom(); 79 | } 80 | 81 | //! Get the size of string in bytes in the string buffer. 82 | size_t GetSize() const { return stack_.GetSize(); } 83 | 84 | //! Get the length of string in Ch in the string buffer. 85 | size_t GetLength() const { return stack_.GetSize() / sizeof(Ch); } 86 | 87 | static const size_t kDefaultCapacity = 256; 88 | mutable internal::Stack stack_; 89 | 90 | private: 91 | // Prohibit copy constructor & assignment operator. 92 | GenericStringBuffer(const GenericStringBuffer&); 93 | GenericStringBuffer& operator=(const GenericStringBuffer&); 94 | }; 95 | 96 | //! String buffer with UTF8 encoding 97 | typedef GenericStringBuffer > StringBuffer; 98 | 99 | template 100 | inline void PutReserve(GenericStringBuffer& stream, size_t count) { 101 | stream.Reserve(count); 102 | } 103 | 104 | template 105 | inline void PutUnsafe(GenericStringBuffer& stream, typename Encoding::Ch c) { 106 | stream.PutUnsafe(c); 107 | } 108 | 109 | //! Implement specialized version of PutN() with memset() for better performance. 110 | template<> 111 | inline void PutN(GenericStringBuffer >& stream, char c, size_t n) { 112 | std::memset(stream.stack_.Push(n), c, n * sizeof(c)); 113 | } 114 | 115 | RAPIDJSON_NAMESPACE_END 116 | 117 | #if defined(__clang__) 118 | RAPIDJSON_DIAG_POP 119 | #endif 120 | 121 | #endif // RAPIDJSON_STRINGBUFFER_H_ 122 | -------------------------------------------------------------------------------- /include/tools/tools_eigen_math.hpp: -------------------------------------------------------------------------------- 1 | // Author: Jiarong Lin ziv.lin.ljr@gmail.com 2 | 3 | #ifndef __EIGEN_MATH_HPP__ 4 | #define __EIGEN_MATH_HPP__ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | namespace Eigen_math 11 | { 12 | template 13 | static T vector_project_on_vector( const T &vec_a, const T &vec_b ) 14 | { 15 | return vec_a.dot( vec_b ) * vec_b / ( vec_b.norm() * vec_b.norm() ); 16 | } 17 | 18 | template 19 | static T vector_project_on_unit_vector( const T &vec_a, const T &vec_b ) 20 | { 21 | return vec_a.dot( vec_b ) * vec_b; 22 | } 23 | 24 | template 25 | T vector_angle( const Eigen::Matrix &vec_a, const Eigen::Matrix &vec_b, int if_force_sharp_angle = 0 ) 26 | { 27 | T vec_a_norm = vec_a.norm(); 28 | T vec_b_norm = vec_b.norm(); 29 | if ( vec_a_norm == 0 || vec_b_norm == 0 ) // zero vector is pararrel to any vector. 30 | { 31 | return 0.0; 32 | } 33 | else 34 | { 35 | if ( if_force_sharp_angle ) 36 | { 37 | // return acos( abs( vec_a.dot( vec_b ) )*0.9999 / ( vec_a_norm * vec_b_norm ) ); 38 | return acos( abs( vec_a.dot( vec_b ) ) / ( vec_a_norm * vec_b_norm ) ); 39 | } 40 | else 41 | { 42 | // return acos( (vec_a.dot(vec_b))*0.9999 / (vec_a_norm*vec_b_norm)); 43 | return acos( ( vec_a.dot( vec_b ) ) / ( vec_a_norm * vec_b_norm ) ); 44 | } 45 | } 46 | } 47 | } // namespace Eigen_math 48 | 49 | #endif 50 | -------------------------------------------------------------------------------- /include/tools/tools_json.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __JSON_TOOLS_H__ 2 | #define __JSON_TOOLS_H__ 3 | 4 | #include "rapidjson/rapidjson.h" 5 | 6 | #include "rapidjson/document.h" 7 | #include "rapidjson/filereadstream.h" 8 | #include "rapidjson/prettywriter.h" 9 | 10 | namespace Common_tools 11 | { 12 | template < typename T > 13 | T *get_json_array( const rapidjson::Document::Array &json_array ) 14 | { 15 | T *res_mat = new T[ json_array.Size() ]; 16 | for ( size_t i = 0; i < json_array.Size(); i++ ) 17 | { 18 | res_mat[ i ] = ( T ) json_array[ i ].GetDouble(); 19 | } 20 | return res_mat; 21 | }; 22 | 23 | template < typename T, typename TT > 24 | void save_mat_to_jason_writter( T &writer, const std::string &name, const TT &eigen_mat ) 25 | { 26 | writer.Key( name.c_str() ); // output a key, 27 | writer.StartArray(); // Between StartArray()/EndArray(), 28 | for ( size_t i = 0; i < ( size_t )( eigen_mat.cols() * eigen_mat.rows() ); i++ ) 29 | writer.Double( eigen_mat( i ) ); 30 | writer.EndArray(); 31 | } 32 | } // namespace Common_tools 33 | 34 | #endif -------------------------------------------------------------------------------- /include/tools/tools_logger.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __LOGGER_HPP__ 2 | #define __LOGGER_HPP__ 3 | #include "os_compatible.hpp" 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include //need for such like printf(...) 11 | #include 12 | #include 13 | #include 14 | 15 | // #define FILE_LOGGER_VERSION "V1.0" 16 | // #define FILE_LOGGER_VERSION_INFO "First version" 17 | 18 | //#define FILE_LOGGER_VERSION "V1.1" 19 | //#define FILE_LOGGER_VERSION_INFO "Add macro, make logger more easy to call" 20 | 21 | //#define FILE_LOGGER_VERSION "V1.2" 22 | //#define FILE_LOGGER_VERSION_INFO "Compatible with windows." 23 | 24 | //#define FILE_LOGGER_VERSION "V1.3" 25 | //#define FILE_LOGGER_VERSION_INFO "Support verbose" 26 | 27 | // #define FILE_LOGGER_VERSION "V1.4" 28 | // #define FILE_LOGGER_VERSION_INFO "Add macro code block, enable turn off the printf quickly" 29 | 30 | #define FILE_LOGGER_VERSION "V1.5" 31 | #define FILE_LOGGER_VERSION_INFO "Add variable restore block, enable turn off/on screen prinf in local block." 32 | 33 | #define printf_line printf( " %s %d \r\n", __FILE__, __LINE__ ); 34 | 35 | #define LOG_FILE_LINE( x ) \ 36 | *( ( x ).get_ostream() ) << __FILE__ << " " << __LINE__ << endl; \ 37 | ( x ).get_ostream()->flush(); 38 | 39 | #define LOG_FILE_LINE_AB( a, b ) \ 40 | *( ( a ).get_ostream( b ) ) << __FILE__ << " " << __LINE__ << endl; \ 41 | ( a ).get_ostream()->flush(); 42 | 43 | #define LOG_FUNCTION_LINE( x ) \ 44 | *( ( x ).get_ostream() ) << __FUNCTION__ << " " << __LINE__ << endl; \ 45 | ( x ).get_ostream()->flush(); 46 | 47 | #define LOG_FUNCTION_LINE_AB( a, b ) \ 48 | *( ( a ).get_ostream( b ) ) << __FUNCTION__ << " " << __LINE__ << endl; \ 49 | ( x ).get_ostream()->flush(); 50 | 51 | #define ADD_SCREEN_PRINTF_OUT_METHOD \ 52 | int m_if_verbose_screen_printf = 1; \ 53 | char * m_sceen_output_cstr = new char[ 10000 ](); \ 54 | std::string m_sceen_output_string = std::string( m_sceen_output_cstr ); \ 55 | std::stringstream m_sceen_output_stringstream = std::stringstream( m_sceen_output_string ); \ 56 | inline void screen_printf( const char *fmt, ... ) \ 57 | { \ 58 | if ( m_if_verbose_screen_printf ) \ 59 | return; \ 60 | va_list ap; \ 61 | va_start( ap, fmt ); \ 62 | if ( Common_tools::vasprintf( &m_sceen_output_cstr, fmt, ap ) == 0 ) \ 63 | { \ 64 | return; \ 65 | } \ 66 | std::printf( "%s", m_sceen_output_cstr ); \ 67 | } \ 68 | std::ostream *sreen_outstream() \ 69 | { \ 70 | if ( m_if_verbose_screen_printf ) \ 71 | { \ 72 | return &m_sceen_output_stringstream; \ 73 | } \ 74 | else \ 75 | { \ 76 | return &std::cout; \ 77 | } \ 78 | } 79 | 80 | #define screen_out ( *sreen_outstream() ) 81 | #define ENABLE_SCREEN_PRINTF Common_tools::Variable_restore_point< int > val_restore( &m_if_verbose_screen_printf, 0 ); 82 | #define DISABLE_SCREEN_PRINTF Common_tools::Variable_restore_point< int > val_restore( &m_if_verbose_screen_printf, 1 ); 83 | 84 | namespace Common_tools // Commond tools 85 | { 86 | using namespace std; 87 | 88 | template < typename T > 89 | struct Variable_restore_point 90 | { 91 | T *m_targer_variable; 92 | T m_initial_value; 93 | 94 | Variable_restore_point( T *variable_ptr ) 95 | { 96 | m_targer_variable = variable_ptr; 97 | m_initial_value = *m_targer_variable; 98 | } 99 | 100 | Variable_restore_point( T *variable_ptr, const T temp_val ) 101 | { 102 | m_targer_variable = variable_ptr; 103 | m_initial_value = *m_targer_variable; 104 | *m_targer_variable = temp_val; 105 | } 106 | 107 | ~Variable_restore_point() 108 | { 109 | *m_targer_variable = m_initial_value; 110 | } 111 | }; 112 | 113 | class File_logger 114 | { 115 | public: 116 | std::map< string, std::ostream * > m_map_file_os; 117 | char m_temp_char[ 10000 ]; 118 | string m_temp_string; 119 | std::stringstream m_temp_stringstream; 120 | string m_save_dir_name = string( "./" ); 121 | std::mutex m_mutex_log; 122 | int m_if_verbose = 0; 123 | void release() 124 | { 125 | for ( auto it = m_map_file_os.begin(); it != m_map_file_os.end(); it++ ) 126 | { 127 | //cout << "File logger relese ostream, name = [" << it->first << "]"; 128 | it->second->flush(); 129 | ( it->second ) = NULL; 130 | delete it->second; 131 | //cout << " Done!" <( "screen", &std::cout ) ); 152 | m_temp_string.reserve( 1e4 ); 153 | m_temp_stringstream = std::stringstream( m_temp_string ); 154 | } 155 | 156 | string version() 157 | { 158 | std::stringstream ss; 159 | ss << "===== This is version of File_logger =====" << endl; 160 | ss << "Version : " << FILE_LOGGER_VERSION << endl; 161 | ss << "Version info : " << FILE_LOGGER_VERSION_INFO << endl; 162 | ss << "Complie date : " << __DATE__ << " " << __TIME__ << endl; 163 | ss << "===== End =====" << endl; 164 | return string( ss.str() ); 165 | } 166 | 167 | void init( std::string _file_name, std::string prefix_name = string( "log" ), int mode = std::ios::out ) 168 | { 169 | std::ofstream *ofs = new std::ofstream(); 170 | sprintf( m_temp_char, "%s/%s_%s", m_save_dir_name.c_str(), prefix_name.c_str(), _file_name.c_str() ); 171 | ofs->open( m_temp_char, ios::out ); 172 | 173 | if ( ofs->is_open() ) 174 | { 175 | cout << "Open " << _file_name << " successful." << endl; 176 | m_map_file_os.insert( std::pair< string, std::ostream * >( prefix_name, ofs ) ); 177 | } 178 | else 179 | { 180 | cout << "Fail to open " << _file_name << endl; 181 | m_map_file_os.insert( std::pair< string, std::ostream * >( prefix_name, &std::cout ) ); 182 | } 183 | }; 184 | 185 | std::ostream *get_ostream( std::string prefix_name = string( "log" ) ) 186 | { 187 | if ( m_if_verbose ) 188 | return &m_temp_stringstream; 189 | auto it = m_map_file_os.find( prefix_name ); 190 | 191 | if ( it != m_map_file_os.end() ) 192 | { 193 | return ( it->second ); 194 | } 195 | else // if no exit, create a new one. 196 | { 197 | init( "tempadd.txt", prefix_name ); 198 | return get_ostream( prefix_name ); 199 | } 200 | } 201 | 202 | int printf( const char *fmt, ... ) 203 | { 204 | if ( m_if_verbose ) 205 | return 0; 206 | std::unique_lock< std::mutex > lock( m_mutex_log ); 207 | #ifdef _WIN32 208 | va_list ap; 209 | char * result = 0; 210 | va_start( ap, fmt ); 211 | if ( vasprintf( &result, fmt, ap ) == 0 ) 212 | { 213 | return 0; 214 | } 215 | //cout << "Fmt = " << fmt <flush(); 221 | return m_temp_string.length(); 222 | //return 0; 223 | #else 224 | va_list ap; 225 | char * result = 0; 226 | va_start( ap, fmt ); 227 | if ( vasprintf( &result, fmt, ap ) == 0 ) 228 | { 229 | return 0; 230 | } 231 | //cout << "Fmt = " << fmt <flush(); 237 | return m_temp_string.length(); 238 | #endif 239 | } 240 | }; 241 | }; // namespace Common_tools 242 | #endif 243 | -------------------------------------------------------------------------------- /include/tools/tools_random.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __TOOLS_RANDOM_HPP__ 2 | #define __TOOLS_RANDOM_HPP__ 3 | // A tools that can generate ture random variable, with modern c++ approach 4 | // Author: Jiarong Lin 5 | // In the develop of this tools, I refer to : 6 | // [1]. https://www.fluentcpp.com/2019/05/24/how-to-fill-a-cpp-collection-with-random-values/ 7 | // [2]. https://www.zhihu.com/question/3999110/answer/84257121 8 | 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | 15 | namespace Common_tools 16 | { 17 | template < typename T > 18 | struct Random_generator_float 19 | { 20 | std::random_device random_device; 21 | std::mt19937 m_random_engine; 22 | std::uniform_real_distribution< T > m_dist; 23 | std::normal_distribution< T > m_dist_normal; 24 | Random_generator_float(): m_random_engine( std::random_device{}() ) 25 | {}; 26 | ~Random_generator_float(){}; 27 | 28 | T rand_uniform( T low = 0.0, T hight = 1.0 ) 29 | { 30 | m_dist = std::uniform_real_distribution< T >( low, hight ); 31 | return m_dist( m_random_engine ); 32 | } 33 | 34 | T rand_normal( T mean = 0.0, T std = 100.0 ) 35 | { 36 | m_dist_normal = std::normal_distribution< T >( mean, std ); 37 | return m_dist_normal( m_random_engine ); 38 | } 39 | 40 | T *rand_array_uniform( T low = 0.0, T hight = 1.0, size_t numbers= 100 ) 41 | { 42 | T *res = new T[ numbers ]; 43 | m_dist = std::uniform_real_distribution< T >( low, hight ); 44 | for ( size_t i = 0; i < numbers; i++ ) 45 | { 46 | res[ i ] = m_dist( m_random_engine ); 47 | } 48 | return res; 49 | } 50 | }; 51 | 52 | template < typename T > 53 | struct Random_generator_int 54 | { 55 | std::random_device random_device; 56 | std::mt19937 m_random_engine; 57 | std::uniform_int_distribution< T > m_dist; 58 | Random_generator_int(): m_random_engine( std::random_device{}() ) 59 | {}; 60 | ~Random_generator_int(){}; 61 | 62 | T rand_uniform( T low = 0, T hight = 100 ) 63 | { 64 | m_dist = std::uniform_int_distribution(low, hight); 65 | return m_dist( m_random_engine ); 66 | } 67 | 68 | T *rand_array_uniform( T low = 0.0, T hight = 1.0, size_t numbers = 100 ) 69 | { 70 | T *res = new T[ numbers ]; 71 | m_dist = std::uniform_int_distribution< T >( low, hight ); 72 | for ( size_t i = 0; i < numbers; i++ ) 73 | { 74 | res[ i ] = m_dist( m_random_engine ); 75 | } 76 | return res; 77 | } 78 | 79 | T* rand_array_norepeat( T low, T high, T k) 80 | { 81 | T n = high - low; 82 | T * res_array = new T[ k ]; 83 | std::vector< int > foo; 84 | foo.resize( n ); 85 | for ( T i = 1; i <= n; ++i ) 86 | foo[ i ] = i + low; 87 | std::shuffle( foo.begin(), foo.end(), m_random_engine ); 88 | for ( T i = 0; i < k; ++i ) 89 | { 90 | res_array[ i ] = foo[ i ]; 91 | // std::cout << foo[ i ] << " "; 92 | } 93 | return res_array; 94 | } 95 | }; 96 | 97 | } 98 | 99 | #endif -------------------------------------------------------------------------------- /include/tools/tools_timer.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __TIME_TICKER_HPP__ 2 | #define __TIME_TICKER_HPP__ 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | namespace Common_tools // Commond tools 11 | { 12 | 13 | static std::chrono::time_point< std::chrono::system_clock > timer_now() 14 | { 15 | return std::chrono::system_clock::now(); 16 | } 17 | 18 | static double timer_tic() 19 | { 20 | //std::time_t t = std::chrono::system_clock::to_time_t( timer_now() ); 21 | auto t = std::chrono::system_clock::to_time_t( timer_now() ); 22 | return double( t ); 23 | } 24 | 25 | class Timer 26 | { 27 | public: 28 | typedef std::map< std::string, std::chrono::time_point< std::chrono::system_clock > > Map_string_timepoint; 29 | typedef std::map< std::string, std::chrono::time_point< std::chrono::system_clock > >::iterator Map_string_timepoint_it; 30 | // typedef std::map Map_string_timepoint; 31 | private: 32 | Map_string_timepoint m_map_str_timepoint; 33 | char m_temp_char[4096]; 34 | int m_if_with_threadid = 1; 35 | public: 36 | 37 | Map_string_timepoint_it find_timepoint( const std::string &str ) 38 | { 39 | Map_string_timepoint_it it = m_map_str_timepoint.find( str ); 40 | if ( it == m_map_str_timepoint.end() ) 41 | { 42 | m_map_str_timepoint.insert( std::make_pair( str, timer_now() ) ); 43 | return m_map_str_timepoint.find( str ); 44 | } 45 | else 46 | { 47 | return it; 48 | } 49 | } 50 | 51 | Timer() 52 | { 53 | ( find_timepoint( std::string( " " ) ) )->second = timer_now(); 54 | } 55 | 56 | std::string get_thread_id_str() 57 | { 58 | if(m_if_with_threadid) 59 | { 60 | std::stringstream ss; 61 | ss << std::this_thread::get_id(); 62 | //cout << "Id =" << std::this_thread::get_id() << endl; 63 | return ss.str(); 64 | } 65 | else 66 | { 67 | return std::to_string(0); 68 | } 69 | } 70 | 71 | 72 | uint64_t get_thread_id() 73 | { 74 | return std::stoull(get_thread_id_str()); 75 | } 76 | 77 | 78 | void tic( std::string str = std::string( " " ) ) 79 | { 80 | find_timepoint( str.append( get_thread_id_str() ) )->second = timer_now(); 81 | } 82 | 83 | double toc( std::string str = std::string( " " ), int if_retick = 1 ) 84 | { 85 | 86 | Map_string_timepoint_it it = find_timepoint( str.append( get_thread_id_str() ) ) ; 87 | 88 | std::chrono::duration time_diff = timer_now() - it->second; 89 | if ( if_retick ) 90 | { 91 | it->second = timer_now(); 92 | } 93 | return time_diff.count() * 1000; 94 | ; 95 | } 96 | 97 | std::string toc_string( std::string str = std::string( " " ), int if_retick = 1 ) 98 | { 99 | 100 | sprintf( m_temp_char, "[Timer](%s): %s cost time = %.2f ms ", get_thread_id_str().c_str(), str.c_str(), toc( str, if_retick ) ); 101 | return std::string( m_temp_char ); 102 | } 103 | }; 104 | 105 | } // namespace Common_tools 106 | 107 | #endif 108 | -------------------------------------------------------------------------------- /launch/livox.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /launch/rosbag.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /launch/rosbag_largescale.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /launch/rosbag_loop.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /launch/rosbag_loop_simple.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /launch/rosbag_mid100.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /launch/rosbag_realtime.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | loam_livox 4 | 0.0.0 5 | 6 | 7 | This is an advanced implentation of LOAM. 8 | LOAM is described in the following paper: 9 | J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time. 10 | Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014. 11 | 12 | 13 | LinJiarong 14 | 15 | BSD 16 | 17 | Ji Zhang 18 | 19 | catkin 20 | geometry_msgs 21 | nav_msgs 22 | roscpp 23 | rospy 24 | std_msgs 25 | rosbag 26 | sensor_msgs 27 | tf 28 | image_transport 29 | 30 | geometry_msgs 31 | nav_msgs 32 | sensor_msgs 33 | roscpp 34 | rospy 35 | std_msgs 36 | rosbag 37 | tf 38 | image_transport 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /pics/CYT_01.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/CYT_01.png -------------------------------------------------------------------------------- /pics/CYT_02.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/CYT_02.png -------------------------------------------------------------------------------- /pics/HKUST_01.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/HKUST_01.png -------------------------------------------------------------------------------- /pics/HKUST_02.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/HKUST_02.png -------------------------------------------------------------------------------- /pics/HKU_ZYM_01.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/HKU_ZYM_01.png -------------------------------------------------------------------------------- /pics/HKU_ZYM_02.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/HKU_ZYM_02.png -------------------------------------------------------------------------------- /pics/for_mid100/mid_100_demo.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/for_mid100/mid_100_demo.gif -------------------------------------------------------------------------------- /pics/for_mid100/modify_the_launch_files.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/for_mid100/modify_the_launch_files.png -------------------------------------------------------------------------------- /pics/for_mid100/remap_topics.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/for_mid100/remap_topics.png -------------------------------------------------------------------------------- /pics/for_mid100/rostopic.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/for_mid100/rostopic.png -------------------------------------------------------------------------------- /pics/handheld.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/handheld.png -------------------------------------------------------------------------------- /pics/hkust_stair.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/hkust_stair.gif -------------------------------------------------------------------------------- /pics/loop_4in1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/loop_4in1.png -------------------------------------------------------------------------------- /pics/loop_hku_main.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/loop_hku_main.png -------------------------------------------------------------------------------- /pics/loop_hku_zym.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/loop_hku_zym.png -------------------------------------------------------------------------------- /pics/loop_simple.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/loop_simple.png -------------------------------------------------------------------------------- /pics/system_low_cost.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/system_low_cost.png -------------------------------------------------------------------------------- /pics/video_lc.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/video_lc.png -------------------------------------------------------------------------------- /pics/video_loam.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/video_loam.png -------------------------------------------------------------------------------- /pics/zym_rotate.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/loam_livox/10778e4a4e22aa67913a20ba2249c67a67d83ef1/pics/zym_rotate.gif -------------------------------------------------------------------------------- /rviz_cfg/.bashrc: -------------------------------------------------------------------------------- 1 | # ~/.bashrc: executed by bash(1) for non-login shells. 2 | # see /usr/share/doc/bash/examples/startup-files (in the package bash-doc) 3 | # for examples 4 | 5 | # If not running interactively, don't do anything 6 | case $- in 7 | *i*) ;; 8 | *) return;; 9 | esac 10 | 11 | # don't put duplicate lines or lines starting with space in the history. 12 | # See bash(1) for more options 13 | HISTCONTROL=ignoreboth 14 | 15 | # append to the history file, don't overwrite it 16 | shopt -s histappend 17 | 18 | # for setting history length see HISTSIZE and HISTFILESIZE in bash(1) 19 | HISTSIZE=1000 20 | HISTFILESIZE=2000 21 | 22 | # check the window size after each command and, if necessary, 23 | # update the values of LINES and COLUMNS. 24 | shopt -s checkwinsize 25 | 26 | # If set, the pattern "**" used in a pathname expansion context will 27 | # match all files and zero or more directories and subdirectories. 28 | #shopt -s globstar 29 | 30 | # make less more friendly for non-text input files, see lesspipe(1) 31 | [ -x /usr/bin/lesspipe ] && eval "$(SHELL=/bin/sh lesspipe)" 32 | 33 | # set variable identifying the chroot you work in (used in the prompt below) 34 | if [ -z "${debian_chroot:-}" ] && [ -r /etc/debian_chroot ]; then 35 | debian_chroot=$(cat /etc/debian_chroot) 36 | fi 37 | 38 | # set a fancy prompt (non-color, unless we know we "want" color) 39 | case "$TERM" in 40 | xterm-color|*-256color) color_prompt=yes;; 41 | esac 42 | 43 | # uncomment for a colored prompt, if the terminal has the capability; turned 44 | # off by default to not distract the user: the focus in a terminal window 45 | # should be on the output of commands, not on the prompt 46 | #force_color_prompt=yes 47 | 48 | if [ -n "$force_color_prompt" ]; then 49 | if [ -x /usr/bin/tput ] && tput setaf 1 >&/dev/null; then 50 | # We have color support; assume it's compliant with Ecma-48 51 | # (ISO/IEC-6429). (Lack of such support is extremely rare, and such 52 | # a case would tend to support setf rather than setaf.) 53 | color_prompt=yes 54 | else 55 | color_prompt= 56 | fi 57 | fi 58 | 59 | if [ "$color_prompt" = yes ]; then 60 | PS1='${debian_chroot:+($debian_chroot)}\[\033[01;32m\]\u@\h\[\033[00m\]:\[\033[01;34m\]\w\[\033[00m\]\$ ' 61 | else 62 | PS1='${debian_chroot:+($debian_chroot)}\u@\h:\w\$ ' 63 | fi 64 | unset color_prompt force_color_prompt 65 | 66 | # If this is an xterm set the title to user@host:dir 67 | case "$TERM" in 68 | xterm*|rxvt*) 69 | PS1="\[\e]0;${debian_chroot:+($debian_chroot)}\u@\h: \w\a\]$PS1" 70 | ;; 71 | *) 72 | ;; 73 | esac 74 | 75 | # enable color support of ls and also add handy aliases 76 | if [ -x /usr/bin/dircolors ]; then 77 | test -r ~/.dircolors && eval "$(dircolors -b ~/.dircolors)" || eval "$(dircolors -b)" 78 | alias ls='ls --color=auto' 79 | #alias dir='dir --color=auto' 80 | #alias vdir='vdir --color=auto' 81 | 82 | alias grep='grep --color=auto' 83 | alias fgrep='fgrep --color=auto' 84 | alias egrep='egrep --color=auto' 85 | fi 86 | 87 | # colored GCC warnings and errors 88 | #export GCC_COLORS='error=01;31:warning=01;35:note=01;36:caret=01;32:locus=01:quote=01' 89 | 90 | # some more ls aliases 91 | alias ll='ls -alF' 92 | alias la='ls -A' 93 | alias l='ls -CF' 94 | 95 | # Add an "alert" alias for long running commands. Use like so: 96 | # sleep 10; alert 97 | alias alert='notify-send --urgency=low -i "$([ $? = 0 ] && echo terminal || echo error)" "$(history|tail -n1|sed -e '\''s/^\s*[0-9]\+\s*//;s/[;&|]\s*alert$//'\'')"' 98 | 99 | # Alias definitions. 100 | # You may want to put all your additions into a separate file like 101 | # ~/.bash_aliases, instead of adding them here directly. 102 | # See /usr/share/doc/bash-doc/examples in the bash-doc package. 103 | 104 | if [ -f ~/.bash_aliases ]; then 105 | . ~/.bash_aliases 106 | fi 107 | 108 | # enable programmable completion features (you don't need to enable 109 | # this, if it's already enabled in /etc/bash.bashrc and /etc/profile 110 | # sources /etc/bash.bashrc). 111 | if ! shopt -oq posix; then 112 | if [ -f /usr/share/bash-completion/bash_completion ]; then 113 | . /usr/share/bash-completion/bash_completion 114 | elif [ -f /etc/bash_completion ]; then 115 | . /etc/bash_completion 116 | fi 117 | fi 118 | export PATH=$PATH:~/App/sublime_text_3/ 119 | alias gst="git status" 120 | alias gl="git log" 121 | alias lls="ll -s" 122 | alias source_bash="source ~/.bashrc" 123 | # alias python3="export PYTHONPATH=/usr/lib/python3/dist-packages:$PYTHONPATH && python3" 124 | alias git_pull_mine="git pull --rebase -s recursive -X ours" 125 | alias edit_bash="vim ~/.bashrc" 126 | alias smg="/home/ziv/App/smartgit/bin/smartgit.sh" 127 | alias vel_16='roslaunch velodyne_pointcloud VLP16_points.launch' 128 | alias livox='roslaunch display_lidar_points livox_nodis.launch bd_list:="0TFDFCE00504141&0TFDFCE00504071"' 129 | alias livox_viewer='/home/ziv/App/Livox_viewer_For_Linux16.04/livox_viewer.sh' 130 | alias view_vel='~/Downloads/VeloView-3.5.0-Linux-64bit/bin/VeloView' 131 | alias cd_ws='cd /home/ziv/catkin_ws/src/livox_odom' 132 | alias chinese_in='fcitx restart' 133 | alias livox_bag='rosbag record /livox/lidar' 134 | # added by Anaconda3 installer 135 | #export PATH="$PATH:/home/ziv/anaconda3/bin" 136 | # add pycharm path 137 | export PATH="/home/ziv/App/smartgit/bin:/home/ziv/App/pycharm-community-2018.1.4/bin:$PATH" 138 | export LD_LIBRARY_PATH=/usr/local/cuda-8.0.82/lib64:/usr/local/lib:/usr/lib/OpenNI2/Drivers/:/home/ziv/anaconda3/pkgs/vtk-8.0.1-0/lib/:$LD_LIBRARY_PATH 139 | export PATH=/usr/local/cuda-8.0.82/bin:/home/ziv/opt/cmake-3.14.0-rc4-Linux-x86_64/bin:$PATH 140 | export DJIROS_APPID='1005202' 141 | export DJIROS_ENCKEY='e7666379497e235364d54c3ecdf1370cbfa009f72e15f6a64451f38e1e5b83ba' 142 | export PCL_ROOT='/home/ziv/opt/pcl-pcl-1.8.0' 143 | #export PYTHONPATH=file:///usr/lib/python3/dist-packages/:/usr/local/lib/python3.5/dist-packages/:/opt/ros/kinetic/lib/python2.7/dist-packages/:/usr/local/lib/python2.7/dist-packages:$PYTHONPATH 144 | #export PYTHONPATH=$PYTHONPATH:/home/ziv/anaconda3/lib/python3.6/site-packages/ 145 | #export PYTHONPATH=/home/ziv/anaconda3/lib/python3.6/site-packages/ 146 | #echo ${PYTHONPATH} 147 | source /opt/ros/kinetic/setup.bash 148 | source /home/ziv/catkin_ws/devel/setup.bash 149 | -------------------------------------------------------------------------------- /source/eigen_math.hpp: -------------------------------------------------------------------------------- 1 | // Author: Lin Jiarong ziv.lin.ljr@gmail.com 2 | 3 | #ifndef __EIGEN_MATH_HPP__ 4 | #define __EIGEN_MATH_HPP__ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | namespace Eigen_math 11 | { 12 | template 13 | static T vector_project_on_vector( const T &vec_a, const T &vec_b ) 14 | { 15 | return vec_a.dot( vec_b ) * vec_b / ( vec_b.norm() * vec_b.norm() ); 16 | } 17 | 18 | template 19 | static T vector_project_on_unit_vector( const T &vec_a, const T &vec_b ) 20 | { 21 | return vec_a.dot( vec_b ) * vec_b; 22 | } 23 | 24 | template 25 | T vector_angle( const Eigen::Matrix &vec_a, const Eigen::Matrix &vec_b, int if_force_sharp_angle = 0 ) 26 | { 27 | T vec_a_norm = vec_a.norm(); 28 | T vec_b_norm = vec_b.norm(); 29 | if ( vec_a_norm == 0 || vec_b_norm == 0 ) // zero vector is pararrel to any vector. 30 | { 31 | return 0.0; 32 | } 33 | else 34 | { 35 | if ( if_force_sharp_angle ) 36 | { 37 | // return acos( abs( vec_a.dot( vec_b ) )*0.9999 / ( vec_a_norm * vec_b_norm ) ); 38 | return acos( abs( vec_a.dot( vec_b ) ) / ( vec_a_norm * vec_b_norm ) ); 39 | } 40 | else 41 | { 42 | // return acos( (vec_a.dot(vec_b))*0.9999 / (vec_a_norm*vec_b_norm)); 43 | return acos( ( vec_a.dot( vec_b ) ) / ( vec_a_norm * vec_b_norm ) ); 44 | } 45 | } 46 | } 47 | } // namespace Eigen_math 48 | 49 | #endif 50 | -------------------------------------------------------------------------------- /source/laser_feature_extractor.cpp: -------------------------------------------------------------------------------- 1 | // This is the Lidar Odometry And Mapping (LOAM) for solid-state lidar (for example: livox lidar), 2 | // which suffer form motion blur due the continously scan pattern and low range of fov. 3 | 4 | // Developer: Jiarong Lin ziv.lin.ljr@gmail.com 5 | 6 | // J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time. 7 | // Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014. 8 | 9 | // Copyright 2013, Ji Zhang, Carnegie Mellon University 10 | // Further contributions copyright (c) 2016, Southwest Research Institute 11 | // All rights reserved. 12 | // 13 | // Redistribution and use in source and binary forms, with or without 14 | // modification, are permitted provided that the following conditions are met: 15 | // 16 | // 1. Redistributions of source code must retain the above copyright notice, 17 | // this list of conditions and the following disclaimer. 18 | // 2. Redistributions in binary form must reproduce the above copyright notice, 19 | // this list of conditions and the following disclaimer in the documentation 20 | // and/or other materials provided with the distribution. 21 | // 3. Neither the name of the copyright holder nor the names of its 22 | // contributors may be used to endorse or promote products derived from this 23 | // software without specific prior written permission. 24 | // 25 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 26 | // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 27 | // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 28 | // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 29 | // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 30 | // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 31 | // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 32 | // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 33 | // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 34 | // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 35 | // POSSIBILITY OF SUCH DAMAGE. 36 | 37 | #include "laser_feature_extractor.hpp" 38 | 39 | int main( int argc, char **argv ) 40 | { 41 | ros::init( argc, argv, "scanRegistration" ); 42 | Laser_feature laser_feature; 43 | 44 | ros::spin(); 45 | 46 | return 0; 47 | } -------------------------------------------------------------------------------- /source/laser_mapping.cpp: -------------------------------------------------------------------------------- 1 | // This is the Lidar Odometry And Mapping (LOAM) for solid-state lidar (for example: livox lidar), 2 | // which suffer form motion blur due the continously scan pattern and low range of fov. 3 | 4 | // Developer: Jiarong Lin ziv.lin.ljr@gmail.com 5 | 6 | // J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time. 7 | // Robotics: Science and Systems Conference (RSS). Berkeley, CA, July 2014. 8 | 9 | // Copyright 2013, Ji Zhang, Carnegie Mellon University 10 | // Further contributions copyright (c) 2016, Southwest Research Institute 11 | // All rights reserved. 12 | // 13 | // Redistribution and use in source and binary forms, with or without 14 | // modification, are permitted provided that the following conditions are met: 15 | // 16 | // 1. Redistributions of source code must retain the above copyright notice, 17 | // this list of conditions and the following disclaimer. 18 | // 2. Redistributions in binary form must reproduce the above copyright notice, 19 | // this list of conditions and the following disclaimer in the documentation 20 | // and/or other materials provided with the distribution. 21 | // 3. Neither the name of the copyright holder nor the names of its 22 | // contributors may be used to endorse or promote products derived from this 23 | // software without specific prior written permission. 24 | // 25 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 26 | // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 27 | // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 28 | // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 29 | // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 30 | // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 31 | // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 32 | // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 33 | // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 34 | // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 35 | // POSSIBILITY OF SUCH DAMAGE. 36 | 37 | #include "laser_mapping.hpp" 38 | 39 | int main( int argc, char **argv ) 40 | { 41 | ros::init( argc, argv, "laserMapping" ); 42 | 43 | Laser_mapping laser_mapping; 44 | 45 | std::thread mapping_process{ &Laser_mapping::process, &laser_mapping }; 46 | 47 | ros::spin(); 48 | return 0; 49 | } 50 | // kate: indent-mode cstyle; indent-width 4; replace-tabs on; 51 | -------------------------------------------------------------------------------- /source/read_camera.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | int main( int argc, char **argv ) 9 | { 10 | std::cout << "Hello, this is read_camera" << std::endl; 11 | std::cout << "Build date " << __DATE__ << std::endl; 12 | std::cout << "Build time " << __TIME__ << std::endl; 13 | 14 | ros::init( argc, argv, "laserMapping" ); 15 | ros::NodeHandle nh; 16 | image_transport::ImageTransport it(nh); 17 | image_transport::Publisher pub = it.advertise("image", 1); 18 | 19 | cv::VideoCapture cap( 0 ); // open the default camera 20 | if ( !cap.isOpened() ) // check if we succeeded 21 | { 22 | ROS_ERROR("Open Camera error! exit node"); 23 | return -1; 24 | } 25 | cap.set(CV_CAP_PROP_SETTINGS, 1); //opens camera properties dialog 26 | 27 | cap.set( CV_CAP_PROP_FRAME_WIDTH, 320 ); 28 | cap.set( CV_CAP_PROP_FRAME_HEIGHT, 240 ); 29 | std::cout << "MJPG: " << cap.set( cv::CAP_PROP_FOURCC, cv::VideoWriter::fourcc( 'M', 'J', 'P', 'G' ) ) << std::endl; 30 | std::cout << "~~~ Read camera OK ~~~" << std::endl; 31 | cv::Mat frame; 32 | sensor_msgs::ImagePtr msg; 33 | for ( ;; ) 34 | { 35 | cap >> frame; // get a new frame from camera 36 | cv::flip(frame, frame, 0); 37 | cv::flip(frame, frame, 1); 38 | msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", frame).toImageMsg(); 39 | pub.publish(msg); 40 | msg->header.stamp = ros::Time::now(); 41 | msg->header.frame_id = std::string("world"); 42 | ros::spinOnce(); 43 | std::this_thread::sleep_for(std::chrono::milliseconds(33)); 44 | } 45 | 46 | return 0; 47 | } 48 | --------------------------------------------------------------------------------