├── .gitignore ├── CMakeLists.txt ├── LICENSES ├── README.md ├── config └── config.yaml ├── figs ├── multi_frame_integration.png └── result.gif ├── include ├── common │ ├── assignment.h │ ├── config.h │ ├── frame.h │ └── time.h ├── tracker │ ├── Hungarian.h │ └── tracker.h └── yaml-cpp │ ├── anchor.h │ ├── binary.h │ ├── contrib │ ├── anchordict.h │ └── graphbuilder.h │ ├── depthguard.h │ ├── dll.h │ ├── emitfromevents.h │ ├── emitter.h │ ├── emitterdef.h │ ├── emittermanip.h │ ├── emitterstyle.h │ ├── eventhandler.h │ ├── exceptions.h │ ├── mark.h │ ├── node │ ├── convert.h │ ├── detail │ │ ├── impl.h │ │ ├── iterator.h │ │ ├── iterator_fwd.h │ │ ├── memory.h │ │ ├── node.h │ │ ├── node_data.h │ │ ├── node_iterator.h │ │ └── node_ref.h │ ├── emit.h │ ├── impl.h │ ├── iterator.h │ ├── node.h │ ├── parse.h │ ├── ptr.h │ └── type.h │ ├── noexcept.h │ ├── null.h │ ├── ostream_wrapper.h │ ├── parser.h │ ├── stlemitter.h │ ├── traits.h │ └── yaml.h ├── launch └── start.launch ├── libs └── yaml │ ├── libgmock.a │ ├── libgmock_main.a │ ├── libgtest.a │ ├── libgtest_main.a │ ├── libyaml-cpp.a │ ├── libyaml-cpp.so │ ├── libyaml-cpp.so.0.6 │ └── libyaml-cpp.so.0.6.0 ├── package.xml ├── rviz_cfg └── vis.rviz └── src ├── assignment ├── Hungarian.cpp ├── assignment.cpp ├── config.cpp ├── frame.cpp ├── main.cpp └── tracker.cpp └── main_ros.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | .vscode/* 2 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(object_undistort) 3 | 4 | set(CMAKE_BUILD_TYPE "Release") 5 | set(CMAKE_CXX_STANDARD 17) 6 | SET(CMAKE_CXX_COMPILER /usr/bin/g++) 7 | 8 | find_package(PCL 1.8 REQUIRED) 9 | find_package(OpenCV REQUIRED) 10 | find_package(yaml-cpp REQUIRED) 11 | find_package(Ceres REQUIRED) 12 | 13 | include_directories(${YAML_CPP_INCLUDE_DIR}) 14 | 15 | include_directories(${PCL_INCLUDE_DIRS}) 16 | link_directories(${PCL_LIBRARY_DIRS}) 17 | add_definitions(${PCL_DEFINITIONS}) 18 | 19 | include_directories(${CMAKE_HOME_DIRECTORY}/include/) 20 | 21 | find_package(catkin REQUIRED COMPONENTS 22 | cv_bridge 23 | roscpp 24 | rosmsg 25 | rospy 26 | sensor_msgs 27 | pcl_ros 28 | message_generation 29 | ) 30 | 31 | generate_messages( 32 | DEPENDENCIES 33 | std_msgs 34 | sensor_msgs 35 | geometry_msgs 36 | ) 37 | 38 | catkin_package( 39 | INCLUDE_DIRS include 40 | LIBRARIES object_undistort 41 | CATKIN_DEPENDS roscpp rosmsg rospy 42 | DEPENDS system_lib 43 | ) 44 | 45 | include_directories( 46 | include 47 | ${catkin_INCLUDE_DIRS} 48 | ${CERES_INCLUDE_DIRS} 49 | ) 50 | 51 | add_executable(main_ros 52 | src/main_ros.cpp 53 | src/assignment/main.cpp 54 | src/assignment/assignment.cpp 55 | src/assignment/frame.cpp 56 | src/assignment/config.cpp 57 | src/assignment/tracker.cpp 58 | src/assignment/Hungarian.cpp 59 | ) 60 | target_link_libraries(main_ros 61 | ${catkin_LIBRARIES} 62 | ${PYTHON_LIBRARIES} 63 | ${CERES_LIBRARIES} 64 | ${PCL_LIBRARIES} 65 | ${OpenCV_LIBS} 66 | yaml-cpp 67 | ) 68 | -------------------------------------------------------------------------------- /LICENSES: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2021 yangwen 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | 23 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Lidar with Velocity 2 | 3 | #### A robust camera and Lidar fusion based velocity estimator to undistort the pointcloud. 4 | 5 | ​ This repository is a barebones implementation for our paper [Lidar with Velocity : Motion Distortion Correction of Point Clouds fromOscillating Scanning Lidars](https://arxiv.org/abs/2111.09497) . It's a fusion based method to handle the oscillating scan Lidar points distortion problem, and can also provide a accurate velocity of the objects. result 6 | 7 | ​ Here is a [Wiki](https://github.com/ISEE-Technology/lidar-with-velocity/wiki) to give a brief intro about the distortion from TOF Lidar and our proposed method. For more infomation, u can also check out the paper [arXiv](https://arxiv.org/abs/2111.09497). 8 | 9 | ## 1. Prerequisites 10 | 11 | **Ubuntu** and **ROS**. Tested on Ubuntu 18.04. ROS Melodic 12 | 13 | **Eigen 3.3.4** 14 | 15 | **Ceres Solver 1.14.0** 16 | 17 | **Opencv 3.2.0** 18 | 19 | ## 2. Build on ROS 20 | 21 | Clone the repository and catkin_make: 22 | 23 | cd ~/catkin_ws/src 24 | git clone https://github.com/ISEE-Technology/lidar-with-velocity 25 | cd ../ 26 | catkin_make 27 | source ~/catkin_ws/devel/setup.bash 28 | 29 | ## 3. Directly run 30 | 31 | First download the [dataset](https://drive.google.com/file/d/1fYQFvZhQXK_kazsPTJ1DrmPwMEdRw6qX/view?usp=sharing) and extract it. 32 | 33 | replace the "DATASET_PATH" in config/config.yaml with your extracted dataset path (notice the "/") 34 | 35 | Then follow the commands blow : 36 | 37 | roslaunch object_undistort start.launch 38 | 39 | there will be a Rviz window and a PCL Viewer window to show the results, press key "space" in the PCL Viewer window to process the next frame. 40 | -------------------------------------------------------------------------------- /config/config.yaml: -------------------------------------------------------------------------------- 1 | dataset_path: DATASET_PATH 2 | 3 | camera_intrinsic: [ 4 | 968.31466,0,813.0669, 5 | 0,965.046,287.335, 6 | 0,0,1 7 | ] 8 | 9 | camera_extrinsic: [ 10 | -0.000332209, -0.999917, -0.0128807, -0.025611, 11 | 0.00470448, 0.012879, -0.999906, 0.0377289, 12 | 0.999989, -0.000392775, 0.00469981, 0.137318, 13 | 0, 0, 0, 1 14 | ] 15 | 16 | lidar_lidar_extrinsic: [ 17 | 0, 0, 0, 0, 0, 0, 18 | 0.205121, 0.0335168, 0.0895346, -0.00760184, 0.0459168, -0.105951, 19 | 0.261006, -0.0978569, 0.0540669, -0.0031703, -0.00298965, -0.0901403, 20 | 0.0116515, 0.103358, 0.229466, 0.0069734, -0.0912874, -0.108668, 21 | 0.29819, 0.183213, 0.1946, -0.0116543, 0.0541184, -0.00368836, 22 | -179.746, 179.952, 179.641, -0.00704259, -0.0944232, 0.0163535 23 | ] 24 | 25 | lidar_to_apx_extrinsic: [ 26 | -0.999695, -0.0244322, 0.00348961, -1.2, 27 | 0.024432, -0.999701, -8.52842e-05, -0.2, 28 | 0.00349065,0.0, 0.999994, 0, 29 | 0,0,0,1 30 | ] 31 | 32 | camera_factor: 256.0 33 | imageRows: 568 34 | imageCols: 1520 35 | 36 | sparse_optical_flow_param: 37 | maxCorners: 5000 38 | qualityLevel: 0.0001 39 | minDistance: 5 40 | blockSize: 3 41 | Harris_k_value: 0.05 42 | -------------------------------------------------------------------------------- /figs/multi_frame_integration.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ISEE-Technology/lidar-with-velocity/ffc15d120d08099a40affe2d651800b4f66aceb1/figs/multi_frame_integration.png -------------------------------------------------------------------------------- /figs/result.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ISEE-Technology/lidar-with-velocity/ffc15d120d08099a40affe2d651800b4f66aceb1/figs/result.gif -------------------------------------------------------------------------------- /include/common/assignment.h: -------------------------------------------------------------------------------- 1 | //assignment.h 2 | #ifndef ASSIGNMENT_H 3 | #define ASSIGNMENT_H 4 | 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | #include 14 | #include 15 | 16 | 17 | #include "tracker/tracker.h" 18 | #include "common/frame.h" 19 | 20 | void nextFrame( 21 | const pcl::visualization::KeyboardEvent& event, 22 | void* nothing); 23 | std::vector getFilesList(std::string dirpath, bool is_recursive); 24 | bool imgSort(const imageWithTime& left, const imageWithTime& right); 25 | bool pcdSort(const pcdsWithTime& left, const pcdsWithTime& right); 26 | bool bboxSort(const frameBboxsWithTime& left, const frameBboxsWithTime& right); 27 | bool cubeSort(const frameCubesWithTime& left, const frameCubesWithTime& right); 28 | bool poseSort( 29 | const pair& left, 30 | const pair& right); 31 | bool pcSort(const pcl::PointCloud& left, 32 | const pcl::PointCloud& right); 33 | double GetIOU(Cube bb_test, Cube bb_gt); 34 | void expand_3d_cube( 35 | frameCubesWithTime & cubes_in 36 | ); 37 | 38 | 39 | class assignment 40 | { 41 | 42 | private: 43 | Config config_; 44 | 45 | public: 46 | assignment(int argc, char** argv); 47 | ~assignment(); 48 | 49 | bool run(int argc, char** argv, ros::NodeHandle & nh); 50 | int is_nextFrame_ = 0; 51 | }; 52 | 53 | 54 | #endif //ASSIGNMENT_H -------------------------------------------------------------------------------- /include/common/config.h: -------------------------------------------------------------------------------- 1 | //config.h 2 | #ifndef CONFIG_H 3 | #define CONFIG_H 4 | 5 | #include 6 | 7 | #include 8 | 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | #include "yaml-cpp/yaml.h" 15 | 16 | class Config 17 | { 18 | friend class assignment; 19 | friend class Frame; 20 | friend class fusion_tracker; 21 | 22 | private: 23 | double camera_factor_ = 256.0; 24 | int imageRows_ = 568; 25 | int imageCols_ = 1520; 26 | 27 | size_t integrator_threads_ = std::thread::hardware_concurrency(); 28 | 29 | size_t max_threads_; 30 | std::string dataset_path_; 31 | std::string pose_path_, raw_img_path_, pcd_path_, label_img_path_, bbox_path_, cube_path_; 32 | 33 | double maxCorners_, qualityLevel_, minDistance_, blockSize_, Harris_k_value_; 34 | 35 | Eigen::Matrix4d lidar_to_apx_extrinsic_, rtk_to_lidar_extrinsic_; 36 | Eigen::Matrix3d camera_intrinsic_; 37 | Eigen::Matrix4d camera_extrinsic_; 38 | std::vector lidar_lidar_ex_; 39 | 40 | public: 41 | Config(); 42 | ~Config(); 43 | 44 | 45 | bool readParam(ros::NodeHandle & nh); 46 | bool readData(); 47 | }; 48 | 49 | 50 | 51 | 52 | #endif //CONFIG_H 53 | -------------------------------------------------------------------------------- /include/common/frame.h: -------------------------------------------------------------------------------- 1 | //frame.h 2 | #ifndef FRAME_H 3 | #define FRAME_H 4 | 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | #include 24 | 25 | #include 26 | #include 27 | #include 28 | #include 29 | #include 30 | #include 31 | #include "tracker/Hungarian.h" 32 | 33 | #include "common/config.h" 34 | 35 | #define hubLidarNum 6 36 | 37 | struct obBBOX 38 | { 39 | std::string object_type_; 40 | double score_; 41 | int bbox_x1_; 42 | int bbox_x2_; 43 | int bbox_y1_; 44 | int bbox_y2_; 45 | 46 | obBBOX( 47 | std::string object_type, 48 | double score, 49 | int bbox_x1, 50 | int bbox_x2, 51 | int bbox_y1, 52 | int bbox_y2 53 | ): 54 | object_type_(object_type), 55 | score_(score), 56 | bbox_x1_(bbox_x1), 57 | bbox_x2_(bbox_x2), 58 | bbox_y1_(bbox_y1), 59 | bbox_y2_(bbox_y2) 60 | {} 61 | }; 62 | 63 | struct cube3d 64 | { 65 | std::string object_type_; 66 | double confidence_; 67 | Eigen::Matrix cube_vertexs_; 68 | 69 | cube3d( 70 | std::string object_type, 71 | double confidence, 72 | Eigen::Matrix cube_vertexs 73 | ) 74 | { 75 | object_type_ = object_type; 76 | confidence_ = confidence; 77 | cube_vertexs_ = cube_vertexs; 78 | } 79 | }; 80 | 81 | typedef struct alignedDet 82 | { 83 | std::string type_; 84 | float confidence2d_; 85 | float confidence3d_; 86 | Eigen::Matrix vertex3d_; 87 | cv::Rect vertex2d_; 88 | pcl::PointCloud cloud_; 89 | cv::Mat img_; 90 | Eigen::Matrix4d global_pose_; 91 | }alignedDet; 92 | 93 | typedef std::vector>> pcdWithTime; 94 | typedef std::vector frameBboxs; 95 | typedef std::vector frameCubes; 96 | 97 | typedef std::pair imageWithTime; 98 | typedef std::pair pcdsWithTime; 99 | typedef std::pair frameBboxsWithTime; 100 | typedef std::pair frameCubesWithTime; 101 | 102 | struct detection_object 103 | { 104 | int object_num_; 105 | frameBboxs detection_2d_; 106 | frameCubes detection_3d_; 107 | pcl::PointCloud cloud_background_; 108 | std::vector> cloud_objects_buffer_; 109 | pcl::PointCloud cloud_; 110 | 111 | detection_object(){} 112 | }; 113 | 114 | class Frame 115 | { 116 | private: 117 | Config global_config_; 118 | cv::Mat raw_img_; 119 | cv::Mat label_img_; 120 | cv::Mat depth_img_frame_; 121 | std::vector> pointclouds_; 122 | pcl::PointCloud frame_pointcloud_; 123 | frameBboxs objs_; 124 | frameCubes cubes_; 125 | // Cube 126 | 127 | // [0]->raw_img_time [1]->label_img_time [2]->pcds_time [3~7]->pcd_time 128 | uint64_t time_stamp_[9]; 129 | 130 | 131 | detection_object frame_detections_; 132 | 133 | public: 134 | Frame( 135 | imageWithTime& raw_img, 136 | imageWithTime& label_img, 137 | pcdsWithTime& pcd, 138 | frameBboxsWithTime& bbox, 139 | frameCubesWithTime& cube, 140 | Config config 141 | ); 142 | ~Frame(); 143 | 144 | bool verboseFrame(); 145 | 146 | cv::Mat PointCloudToDepth( 147 | pcl::PointCloud::Ptr cloud_in, Config global_config); 148 | 149 | cv::Mat PointCloudToDepthWithintensity( 150 | pcl::PointCloud::Ptr cloud_in, 151 | cv::Mat & intensity_map, 152 | Config global_config); 153 | 154 | pcl::PointCloud depth_to_pointcloud( 155 | cv::Mat& depthImageIn, 156 | Config global_config 157 | ); 158 | 159 | pcl::PointCloud::Ptr roi_depth_to_pointcloud( 160 | cv::Mat& depthImageIn, 161 | cv::Mat& intensity_map, 162 | int x_start, 163 | int y_start, 164 | int x_len, 165 | int y_len, 166 | Config global_config 167 | ); 168 | 169 | 170 | pcl::PointCloud::Ptr getFramePointcloud(); 171 | pcl::PointCloud::Ptr getBackgroundcloud(); 172 | std::vector> * getObjcloud(); 173 | pcl::PointCloud::Ptr getCloud(); 174 | 175 | void full_detection( 176 | pcdsWithTime * pcd_in 177 | ); 178 | void point_extraction( 179 | const pcl::PointCloud::Ptr cloud_, 180 | const frameCubes * cubes_, 181 | pcl::PointCloud * background_cloud, 182 | std::vector> * obj_cloud 183 | ); 184 | void detection_align( 185 | const std::vector> * obj_cloud_, 186 | const cv::Mat * rawimg_, 187 | const frameCubes * cubes_, 188 | const frameBboxs * objs_, 189 | const Eigen::Matrix4d * global_pose_, 190 | std::vector & aligned_detections 191 | ); 192 | 193 | // project the 3d detection result to 2d domain 194 | void detection3dProj2d( 195 | const cube3d * vertex3d, 196 | cv::Rect * output 197 | ); 198 | // 3d 2d detection IoU score 199 | float fusionIoU( 200 | const cv::Rect detection3d, 201 | const cv::Rect detection2d 202 | ); 203 | void findHungarianAssignment( 204 | std::vector> iouMatrix_, 205 | vector & results 206 | ); 207 | }; 208 | 209 | class VisHandel 210 | { 211 | private: 212 | ros::NodeHandle nh_; 213 | 214 | ros::Publisher raw_img_; 215 | ros::Publisher img_detection_; 216 | 217 | ros::Publisher raw_cloud_; 218 | ros::Publisher background_cloud_; 219 | ros::Publisher raw_obj_cloud_pub_; 220 | ros::Publisher undistorted_obj_cloud_pub_; 221 | 222 | ros::Publisher marker_3d_; 223 | ros::Publisher txt_marker_3d_; 224 | ros::Publisher obj_velocity_txt_; 225 | ros::Publisher obj_velocity_arrow_; 226 | 227 | public: 228 | VisHandel(ros::NodeHandle nh); 229 | ~VisHandel(); 230 | 231 | void txt_marker_3d_publisher( 232 | const std::vector & detection_in 233 | ); 234 | 235 | void raw_cloud_publisher(sensor_msgs::PointCloud2 cloud_in); 236 | void raw_obj_cloud_publisher(sensor_msgs::PointCloud2 cloud_in); 237 | void undistorted_obj_cloud_publisher(sensor_msgs::PointCloud2 cloud_in); 238 | void background_cloud_publisher(sensor_msgs::PointCloud2 cloud_in); 239 | 240 | void raw_img_publisher(cv::Mat img_in); 241 | void label_img_publisher(cv::Mat img_in); 242 | 243 | void obj_vel_arrow_publisher(visualization_msgs::Marker arrow_in); 244 | void obj_vel_txt_publisher(visualization_msgs::MarkerArray txt_in); 245 | }; 246 | 247 | #endif //FRAME_H -------------------------------------------------------------------------------- /include/common/time.h: -------------------------------------------------------------------------------- 1 | //timer.h 2 | #ifndef W_TIMER_H 3 | #define W_TIMER_H 4 | 5 | #include 6 | #include 7 | #include 8 | 9 | class Timer { 10 | public: 11 | 12 | Timer():_name("Time elapsed:") { 13 | restart(); 14 | } 15 | 16 | explicit Timer(const std::string &name):_name(name + ":") { 17 | restart(); 18 | } 19 | 20 | /** 21 | * 启动计时 22 | */ 23 | inline void restart() { 24 | _start_time = std::chrono::steady_clock::now(); 25 | } 26 | 27 | /** 28 | * 结束计时 29 | * @return 返回ms数 30 | */ 31 | inline double elapsed(bool restart = false) { 32 | _end_time = std::chrono::steady_clock::now(); 33 | std::chrono::duration diff = _end_time-_start_time; 34 | if(restart) 35 | this->restart(); 36 | return diff.count()*1000; 37 | } 38 | 39 | /** 40 | * 打印时间并重启计时器 41 | * @param tip 提示 42 | */ 43 | void rlog(const std::string &tip){ 44 | log(true,tip,true,false); 45 | } 46 | 47 | /** 48 | * 打印时间 49 | * @param reset 输出之后是否重启计时器,true重启,false不重启 50 | * @param unit_ms true是ms,false是s 51 | * @param tip 输出提示 52 | * @param kill 输出之后是否退出程序,true退出,false不退出 53 | */ 54 | void log(bool reset = false, const std::string &tip = "", 55 | bool unit_ms = true, bool kill = false 56 | ) { 57 | if (unit_ms) { 58 | if (tip.length() > 0) 59 | std::cout << tip+":" << elapsed() << "ms" << std::endl; 60 | else 61 | std::cout << _name << elapsed() << "ms" << std::endl; 62 | } else { 63 | if (tip.length() > 0) 64 | std::cout << tip+":" << elapsed() / 1000.0 << "s" << std::endl; 65 | else 66 | std::cout << _name << elapsed() / 1000.0 << "s" << std::endl; 67 | } 68 | 69 | if (reset) 70 | this->restart(); 71 | 72 | if (kill) 73 | exit(5); 74 | } 75 | 76 | 77 | private: 78 | std::chrono::steady_clock::time_point _start_time; 79 | std::chrono::steady_clock::time_point _end_time; 80 | std::string _name; 81 | }; // timer 82 | 83 | #endif //W_TIMER_H -------------------------------------------------------------------------------- /include/tracker/Hungarian.h: -------------------------------------------------------------------------------- 1 | /////////////////////////////////////////////////////////////////////////////// 2 | // Hungarian.h: Header file for Class HungarianAlgorithm. 3 | // 4 | // This is a C++ wrapper with slight modification of a hungarian algorithm implementation by Markus Buehren. 5 | // The original implementation is a few mex-functions for use in MATLAB, found here: 6 | // http://www.mathworks.com/matlabcentral/fileexchange/6543-functions-for-the-rectangular-assignment-problem 7 | // 8 | // Both this code and the orignal code are published under the BSD license. 9 | // by Cong Ma, 2016 10 | // 11 | 12 | #include 13 | #include 14 | 15 | using namespace std; 16 | 17 | 18 | class HungarianAlgorithm { 19 | public: 20 | HungarianAlgorithm(); 21 | 22 | ~HungarianAlgorithm(); 23 | 24 | double Solve(vector> &DistMatrix, vector &Assignment); 25 | 26 | private: 27 | void assignmentoptimal(int *assignment, double *cost, double *distMatrix, int nOfRows, int nOfColumns); 28 | 29 | void buildassignmentvector(int *assignment, bool *starMatrix, int nOfRows, int nOfColumns); 30 | 31 | void computeassignmentcost(int *assignment, double *cost, double *distMatrix, int nOfRows); 32 | 33 | void step2a(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, 34 | bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim); 35 | 36 | void step2b(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, 37 | bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim); 38 | 39 | void step3(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, 40 | bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim); 41 | 42 | void step4(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, 43 | bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim, int row, int col); 44 | 45 | void step5(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, 46 | bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim); 47 | }; 48 | -------------------------------------------------------------------------------- /include/tracker/tracker.h: -------------------------------------------------------------------------------- 1 | /////////////////////////////////////////////////////////////////////////////// 2 | // KalmanTracker.h: KalmanTracker Class Declaration 3 | 4 | #ifndef KALMAN_H 5 | #define KALMAN_H 6 | 7 | #include "opencv2/video/tracking.hpp" 8 | #include "opencv2/highgui/highgui.hpp" 9 | #include "common/frame.h" 10 | // #include "common/assignment.h" 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | #include 24 | #include 25 | #include 26 | 27 | #include 28 | 29 | #include "common/time.h" 30 | 31 | 32 | using namespace std; 33 | using namespace cv; 34 | 35 | #define StateType Cube 36 | 37 | typedef struct Cube 38 | { 39 | double centerx_; 40 | double centery_; 41 | double centerz_; 42 | double yaw_; 43 | double long_; 44 | double width_; 45 | double depth_; 46 | double corner1_[3]; 47 | double corner2_[3]; 48 | pcl::PointCloud::Ptr obj_pointcloud_; 49 | cv::Mat frame_pic_; 50 | uint64_t pcds_time_; 51 | cv::Rect bbox_; 52 | Eigen::Matrix4d pose_; 53 | }; 54 | 55 | 56 | class kfTracker 57 | { 58 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 59 | public: 60 | kfTracker() 61 | { 62 | init_kf(alignedDet()); 63 | m_time_since_update = 0; 64 | m_hits = 0; 65 | m_hit_streak = 0; 66 | m_age = 0; 67 | m_id = kf_count; 68 | estimated_vel_.setZero(); 69 | } 70 | kfTracker( 71 | alignedDet detection_in 72 | ) 73 | { 74 | init_kf(detection_in); 75 | m_time_since_update = 0; 76 | m_hits = 0; 77 | m_hit_streak = 0; 78 | m_age = 0; 79 | m_id = kf_count; 80 | estimated_vel_.setZero(); 81 | 82 | } 83 | ~kfTracker() 84 | { 85 | measurement_history_.clear(); 86 | } 87 | alignedDet predict(); 88 | void update( 89 | alignedDet detection_in, 90 | const Eigen::Vector3d & vel_, 91 | const Eigen::Matrix3d & vel_cov_ 92 | ); 93 | void get_kf_vel( 94 | Eigen::Vector3d & vel_ 95 | ); 96 | void update_estimated_vel(); 97 | 98 | static int kf_count; 99 | int m_time_since_update; 100 | int m_hits; 101 | int m_hit_streak; 102 | int m_age; 103 | int m_id; 104 | 105 | int rgb3[3]; 106 | alignedDet detection_cur_; 107 | alignedDet detection_last_; 108 | alignedDet detection_last_2_; 109 | 110 | Eigen::Vector3d estimated_vel_; 111 | Eigen::Matrix3d estimated_vel_cov_; 112 | std::vector log_; 113 | 114 | cv::KalmanFilter kf_; 115 | 116 | private: 117 | cv::Mat measurement_; 118 | std::vector measurement_history_; 119 | 120 | void init_kf(alignedDet detection_in); 121 | std::vector getState( 122 | alignedDet detection_in 123 | ); 124 | 125 | }; 126 | 127 | class fusion_tracker 128 | { 129 | private: 130 | vector last_detection_; 131 | vector cur_detection_; 132 | cv::Mat last_img_; 133 | cv::Mat cur_img_; 134 | vector prev_pts_; 135 | cv::Mat prev_gray_; 136 | 137 | int total_frames_; 138 | int frame_count_; 139 | vector predictedBoxes_; 140 | unsigned int trkNum_; 141 | unsigned int detNum_; 142 | vector> iouMatrix_; 143 | vector HungariaAssignment_; 144 | set unmatchedTrajectories_; 145 | set unmatchedDetections_; 146 | set allItems_; 147 | set matchedItems_; 148 | vector matchedPairs_; 149 | double iouThreshold_; 150 | public: 151 | fusion_tracker(); 152 | ~fusion_tracker(); 153 | 154 | void tracking( 155 | const std::vector & detections_in, 156 | const cv::Mat & img_in, 157 | const Config & config_, 158 | boost::shared_ptr viewer, 159 | visualization_msgs::MarkerArray & obj_vel_txt_markerarray, 160 | VisHandel * vis_ 161 | ); 162 | void alignedDet2rotaterect( 163 | const alignedDet & detection_in, 164 | cv::RotatedRect & out_rect 165 | ); 166 | double GetIOU( 167 | const alignedDet & bb_test, 168 | const alignedDet & bb_gt 169 | ); 170 | void optical_estimator( 171 | const cv::Mat & prev_, 172 | const cv::Mat & cur_, 173 | const std::vector & prev_detection, 174 | const std::vector & cur_detection, 175 | const Config & config_, 176 | std::vector & obj_means, 177 | std::vector & obj_covariances 178 | ); 179 | void points_estimator( 180 | boost::shared_ptr viewer, 181 | const alignedDet & prev_detection, 182 | const alignedDet & cur_detection, 183 | Eigen::Vector3d & optimal_vel, 184 | Eigen::Matrix3d & optimal_vel_cov, 185 | const Eigen::Vector2d & pix_vel, 186 | const Eigen::Matrix2d & pix_vel_cov, 187 | kfTracker * tracker, 188 | Eigen::Vector3d & fused_vel, 189 | Eigen::Matrix3d & fused_vel_cov, 190 | const Config & config_ 191 | ); 192 | void vel_fusion( 193 | const alignedDet cur_detection, 194 | const alignedDet prev_detection, 195 | const Eigen::Vector3d points_vel, 196 | const Eigen::Matrix3d points_vel_cov, 197 | const Eigen::Vector2d pix_vel, 198 | const Eigen::Matrix2d pix_vel_cov, 199 | Eigen::Vector3d & fusion_vel, 200 | Eigen::Matrix3d & fusion_vel_cov, 201 | const Config & config_ 202 | ); 203 | vector trackers_; 204 | void points_opti( 205 | boost::shared_ptr viewer, 206 | const Eigen::Vector3d & optimal_direction, 207 | Eigen::Vector3d & target_centroid, 208 | const pcl::PointCloud & cloud, 209 | Eigen::Vector3d & points_vel, 210 | Eigen::Matrix3d & points_vel_cov, 211 | double octree_size 212 | ); 213 | 214 | void get_bbox_length( 215 | const Eigen::Matrix & bbox_vertices, 216 | Eigen::Vector3d & out_dir 217 | ); 218 | }; 219 | 220 | void cloud_undistortion( 221 | int track_id, 222 | const kfTracker & tracker, 223 | const alignedDet detection_in, 224 | const Eigen::Vector3d vel_, 225 | pcl::PointCloud::Ptr clouds_buffer, 226 | pcl::PointCloud::Ptr raw_clouds_buffer, 227 | visualization_msgs::MarkerArray & txt_buffer 228 | ); 229 | #endif -------------------------------------------------------------------------------- /include/yaml-cpp/anchor.h: -------------------------------------------------------------------------------- 1 | #ifndef ANCHOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define ANCHOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | 12 | namespace YAML { 13 | using anchor_t = std::size_t; 14 | const anchor_t NullAnchor = 0; 15 | } 16 | 17 | #endif // ANCHOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 18 | -------------------------------------------------------------------------------- /include/yaml-cpp/binary.h: -------------------------------------------------------------------------------- 1 | #ifndef BASE64_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define BASE64_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | 13 | #include "yaml-cpp/dll.h" 14 | 15 | namespace YAML { 16 | YAML_CPP_API std::string EncodeBase64(const unsigned char *data, 17 | std::size_t size); 18 | YAML_CPP_API std::vector DecodeBase64(const std::string &input); 19 | 20 | class YAML_CPP_API Binary { 21 | public: 22 | Binary(const unsigned char *data_, std::size_t size_) 23 | : m_data{}, m_unownedData(data_), m_unownedSize(size_) {} 24 | Binary() : Binary(nullptr, 0) {} 25 | Binary(const Binary &) = default; 26 | Binary(Binary &&) = default; 27 | Binary &operator=(const Binary &) = default; 28 | Binary &operator=(Binary &&) = default; 29 | 30 | bool owned() const { return !m_unownedData; } 31 | std::size_t size() const { return owned() ? m_data.size() : m_unownedSize; } 32 | const unsigned char *data() const { 33 | return owned() ? &m_data[0] : m_unownedData; 34 | } 35 | 36 | void swap(std::vector &rhs) { 37 | if (m_unownedData) { 38 | m_data.swap(rhs); 39 | rhs.clear(); 40 | rhs.resize(m_unownedSize); 41 | std::copy(m_unownedData, m_unownedData + m_unownedSize, rhs.begin()); 42 | m_unownedData = nullptr; 43 | m_unownedSize = 0; 44 | } else { 45 | m_data.swap(rhs); 46 | } 47 | } 48 | 49 | bool operator==(const Binary &rhs) const { 50 | const std::size_t s = size(); 51 | if (s != rhs.size()) 52 | return false; 53 | const unsigned char *d1 = data(); 54 | const unsigned char *d2 = rhs.data(); 55 | for (std::size_t i = 0; i < s; i++) { 56 | if (*d1++ != *d2++) 57 | return false; 58 | } 59 | return true; 60 | } 61 | 62 | bool operator!=(const Binary &rhs) const { return !(*this == rhs); } 63 | 64 | private: 65 | std::vector m_data; 66 | const unsigned char *m_unownedData; 67 | std::size_t m_unownedSize; 68 | }; 69 | } // namespace YAML 70 | 71 | #endif // BASE64_H_62B23520_7C8E_11DE_8A39_0800200C9A66 72 | -------------------------------------------------------------------------------- /include/yaml-cpp/contrib/anchordict.h: -------------------------------------------------------------------------------- 1 | #ifndef ANCHORDICT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define ANCHORDICT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | 12 | #include "../anchor.h" 13 | 14 | namespace YAML { 15 | /** 16 | * An object that stores and retrieves values correlating to {@link anchor_t} 17 | * values. 18 | * 19 | *

Efficient implementation that can make assumptions about how 20 | * {@code anchor_t} values are assigned by the {@link Parser} class. 21 | */ 22 | template 23 | class AnchorDict { 24 | public: 25 | AnchorDict() : m_data{} {} 26 | void Register(anchor_t anchor, T value) { 27 | if (anchor > m_data.size()) { 28 | m_data.resize(anchor); 29 | } 30 | m_data[anchor - 1] = value; 31 | } 32 | 33 | T Get(anchor_t anchor) const { return m_data[anchor - 1]; } 34 | 35 | private: 36 | std::vector m_data; 37 | }; 38 | } // namespace YAML 39 | 40 | #endif // ANCHORDICT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 41 | -------------------------------------------------------------------------------- /include/yaml-cpp/contrib/graphbuilder.h: -------------------------------------------------------------------------------- 1 | #ifndef GRAPHBUILDER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define GRAPHBUILDER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/mark.h" 11 | #include 12 | 13 | namespace YAML { 14 | class Parser; 15 | 16 | // GraphBuilderInterface 17 | // . Abstraction of node creation 18 | // . pParentNode is always nullptr or the return value of one of the NewXXX() 19 | // functions. 20 | class GraphBuilderInterface { 21 | public: 22 | virtual ~GraphBuilderInterface() = 0; 23 | 24 | // Create and return a new node with a null value. 25 | virtual void *NewNull(const Mark &mark, void *pParentNode) = 0; 26 | 27 | // Create and return a new node with the given tag and value. 28 | virtual void *NewScalar(const Mark &mark, const std::string &tag, 29 | void *pParentNode, const std::string &value) = 0; 30 | 31 | // Create and return a new sequence node 32 | virtual void *NewSequence(const Mark &mark, const std::string &tag, 33 | void *pParentNode) = 0; 34 | 35 | // Add pNode to pSequence. pNode was created with one of the NewXxx() 36 | // functions and pSequence with NewSequence(). 37 | virtual void AppendToSequence(void *pSequence, void *pNode) = 0; 38 | 39 | // Note that no moew entries will be added to pSequence 40 | virtual void SequenceComplete(void *pSequence) { (void)pSequence; } 41 | 42 | // Create and return a new map node 43 | virtual void *NewMap(const Mark &mark, const std::string &tag, 44 | void *pParentNode) = 0; 45 | 46 | // Add the pKeyNode => pValueNode mapping to pMap. pKeyNode and pValueNode 47 | // were created with one of the NewXxx() methods and pMap with NewMap(). 48 | virtual void AssignInMap(void *pMap, void *pKeyNode, void *pValueNode) = 0; 49 | 50 | // Note that no more assignments will be made in pMap 51 | virtual void MapComplete(void *pMap) { (void)pMap; } 52 | 53 | // Return the node that should be used in place of an alias referencing 54 | // pNode (pNode by default) 55 | virtual void *AnchorReference(const Mark &mark, void *pNode) { 56 | (void)mark; 57 | return pNode; 58 | } 59 | }; 60 | 61 | // Typesafe wrapper for GraphBuilderInterface. Assumes that Impl defines 62 | // Node, Sequence, and Map types. Sequence and Map must derive from Node 63 | // (unless Node is defined as void). Impl must also implement function with 64 | // all of the same names as the virtual functions in GraphBuilderInterface 65 | // -- including the ones with default implementations -- but with the 66 | // prototypes changed to accept an explicit Node*, Sequence*, or Map* where 67 | // appropriate. 68 | template 69 | class GraphBuilder : public GraphBuilderInterface { 70 | public: 71 | typedef typename Impl::Node Node; 72 | typedef typename Impl::Sequence Sequence; 73 | typedef typename Impl::Map Map; 74 | 75 | GraphBuilder(Impl &impl) : m_impl(impl) { 76 | Map *pMap = nullptr; 77 | Sequence *pSeq = nullptr; 78 | Node *pNode = nullptr; 79 | 80 | // Type consistency checks 81 | pNode = pMap; 82 | pNode = pSeq; 83 | } 84 | 85 | GraphBuilderInterface &AsBuilderInterface() { return *this; } 86 | 87 | virtual void *NewNull(const Mark &mark, void *pParentNode) { 88 | return CheckType(m_impl.NewNull(mark, AsNode(pParentNode))); 89 | } 90 | 91 | virtual void *NewScalar(const Mark &mark, const std::string &tag, 92 | void *pParentNode, const std::string &value) { 93 | return CheckType( 94 | m_impl.NewScalar(mark, tag, AsNode(pParentNode), value)); 95 | } 96 | 97 | virtual void *NewSequence(const Mark &mark, const std::string &tag, 98 | void *pParentNode) { 99 | return CheckType( 100 | m_impl.NewSequence(mark, tag, AsNode(pParentNode))); 101 | } 102 | virtual void AppendToSequence(void *pSequence, void *pNode) { 103 | m_impl.AppendToSequence(AsSequence(pSequence), AsNode(pNode)); 104 | } 105 | virtual void SequenceComplete(void *pSequence) { 106 | m_impl.SequenceComplete(AsSequence(pSequence)); 107 | } 108 | 109 | virtual void *NewMap(const Mark &mark, const std::string &tag, 110 | void *pParentNode) { 111 | return CheckType(m_impl.NewMap(mark, tag, AsNode(pParentNode))); 112 | } 113 | virtual void AssignInMap(void *pMap, void *pKeyNode, void *pValueNode) { 114 | m_impl.AssignInMap(AsMap(pMap), AsNode(pKeyNode), AsNode(pValueNode)); 115 | } 116 | virtual void MapComplete(void *pMap) { m_impl.MapComplete(AsMap(pMap)); } 117 | 118 | virtual void *AnchorReference(const Mark &mark, void *pNode) { 119 | return CheckType(m_impl.AnchorReference(mark, AsNode(pNode))); 120 | } 121 | 122 | private: 123 | Impl &m_impl; 124 | 125 | // Static check for pointer to T 126 | template 127 | static T *CheckType(U *p) { 128 | return p; 129 | } 130 | 131 | static Node *AsNode(void *pNode) { return static_cast(pNode); } 132 | static Sequence *AsSequence(void *pSeq) { 133 | return static_cast(pSeq); 134 | } 135 | static Map *AsMap(void *pMap) { return static_cast(pMap); } 136 | }; 137 | 138 | void *BuildGraphOfNextDocument(Parser &parser, 139 | GraphBuilderInterface &graphBuilder); 140 | 141 | template 142 | typename Impl::Node *BuildGraphOfNextDocument(Parser &parser, Impl &impl) { 143 | GraphBuilder graphBuilder(impl); 144 | return static_cast( 145 | BuildGraphOfNextDocument(parser, graphBuilder)); 146 | } 147 | } 148 | 149 | #endif // GRAPHBUILDER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 150 | -------------------------------------------------------------------------------- /include/yaml-cpp/depthguard.h: -------------------------------------------------------------------------------- 1 | #ifndef DEPTH_GUARD_H_00000000000000000000000000000000000000000000000000000000 2 | #define DEPTH_GUARD_H_00000000000000000000000000000000000000000000000000000000 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "exceptions.h" 11 | 12 | namespace YAML { 13 | 14 | /** 15 | * @brief The DeepRecursion class 16 | * An exception class which is thrown by DepthGuard. Ideally it should be 17 | * a member of DepthGuard. However, DepthGuard is a templated class which means 18 | * that any catch points would then need to know the template parameters. It is 19 | * simpler for clients to not have to know at the catch point what was the 20 | * maximum depth. 21 | */ 22 | class DeepRecursion : public ParserException { 23 | public: 24 | virtual ~DeepRecursion() = default; 25 | 26 | DeepRecursion(int depth, const Mark& mark_, const std::string& msg_); 27 | 28 | // Returns the recursion depth when the exception was thrown 29 | int depth() const { 30 | return m_depth; 31 | } 32 | 33 | private: 34 | int m_depth = 0; 35 | }; 36 | 37 | /** 38 | * @brief The DepthGuard class 39 | * DepthGuard takes a reference to an integer. It increments the integer upon 40 | * construction of DepthGuard and decrements the integer upon destruction. 41 | * 42 | * If the integer would be incremented past max_depth, then an exception is 43 | * thrown. This is ideally geared toward guarding against deep recursion. 44 | * 45 | * @param max_depth 46 | * compile-time configurable maximum depth. 47 | */ 48 | template 49 | class DepthGuard final { 50 | public: 51 | DepthGuard(int & depth_, const Mark& mark_, const std::string& msg_) : m_depth(depth_) { 52 | ++m_depth; 53 | if ( max_depth <= m_depth ) { 54 | throw DeepRecursion{m_depth, mark_, msg_}; 55 | } 56 | } 57 | 58 | DepthGuard(const DepthGuard & copy_ctor) = delete; 59 | DepthGuard(DepthGuard && move_ctor) = delete; 60 | DepthGuard & operator=(const DepthGuard & copy_assign) = delete; 61 | DepthGuard & operator=(DepthGuard && move_assign) = delete; 62 | 63 | ~DepthGuard() { 64 | --m_depth; 65 | } 66 | 67 | int current_depth() const { 68 | return m_depth; 69 | } 70 | 71 | private: 72 | int & m_depth; 73 | }; 74 | 75 | } // namespace YAML 76 | 77 | #endif // DEPTH_GUARD_H_00000000000000000000000000000000000000000000000000000000 78 | -------------------------------------------------------------------------------- /include/yaml-cpp/dll.h: -------------------------------------------------------------------------------- 1 | #ifndef DLL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define DLL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | // The following ifdef block is the standard way of creating macros which make 11 | // exporting from a DLL simpler. All files within this DLL are compiled with the 12 | // yaml_cpp_EXPORTS symbol defined on the command line. This symbol should not 13 | // be defined on any project that uses this DLL. This way any other project 14 | // whose source files include this file see YAML_CPP_API functions as being 15 | // imported from a DLL, whereas this DLL sees symbols defined with this macro as 16 | // being exported. 17 | #undef YAML_CPP_API 18 | 19 | #ifdef YAML_CPP_DLL // Using or Building YAML-CPP DLL (definition defined 20 | // manually) 21 | #ifdef yaml_cpp_EXPORTS // Building YAML-CPP DLL (definition created by CMake 22 | // or defined manually) 23 | // #pragma message( "Defining YAML_CPP_API for DLL export" ) 24 | #define YAML_CPP_API __declspec(dllexport) 25 | #else // yaml_cpp_EXPORTS 26 | // #pragma message( "Defining YAML_CPP_API for DLL import" ) 27 | #define YAML_CPP_API __declspec(dllimport) 28 | #endif // yaml_cpp_EXPORTS 29 | #else // YAML_CPP_DLL 30 | #define YAML_CPP_API 31 | #endif // YAML_CPP_DLL 32 | 33 | #endif // DLL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 34 | -------------------------------------------------------------------------------- /include/yaml-cpp/emitfromevents.h: -------------------------------------------------------------------------------- 1 | #ifndef EMITFROMEVENTS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define EMITFROMEVENTS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | 12 | #include "yaml-cpp/anchor.h" 13 | #include "yaml-cpp/emitterstyle.h" 14 | #include "yaml-cpp/eventhandler.h" 15 | 16 | namespace YAML { 17 | struct Mark; 18 | } // namespace YAML 19 | 20 | namespace YAML { 21 | class Emitter; 22 | 23 | class EmitFromEvents : public EventHandler { 24 | public: 25 | EmitFromEvents(Emitter& emitter); 26 | 27 | void OnDocumentStart(const Mark& mark) override; 28 | void OnDocumentEnd() override; 29 | 30 | void OnNull(const Mark& mark, anchor_t anchor) override; 31 | void OnAlias(const Mark& mark, anchor_t anchor) override; 32 | void OnScalar(const Mark& mark, const std::string& tag, 33 | anchor_t anchor, const std::string& value) override; 34 | 35 | void OnSequenceStart(const Mark& mark, const std::string& tag, 36 | anchor_t anchor, EmitterStyle::value style) override; 37 | void OnSequenceEnd() override; 38 | 39 | void OnMapStart(const Mark& mark, const std::string& tag, 40 | anchor_t anchor, EmitterStyle::value style) override; 41 | void OnMapEnd() override; 42 | 43 | private: 44 | void BeginNode(); 45 | void EmitProps(const std::string& tag, anchor_t anchor); 46 | 47 | private: 48 | Emitter& m_emitter; 49 | 50 | struct State { 51 | enum value { WaitingForSequenceEntry, WaitingForKey, WaitingForValue }; 52 | }; 53 | std::stack m_stateStack; 54 | }; 55 | } 56 | 57 | #endif // EMITFROMEVENTS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 58 | -------------------------------------------------------------------------------- /include/yaml-cpp/emitter.h: -------------------------------------------------------------------------------- 1 | #ifndef EMITTER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define EMITTER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | 18 | #include "yaml-cpp/binary.h" 19 | #include "yaml-cpp/dll.h" 20 | #include "yaml-cpp/emitterdef.h" 21 | #include "yaml-cpp/emittermanip.h" 22 | #include "yaml-cpp/null.h" 23 | #include "yaml-cpp/ostream_wrapper.h" 24 | 25 | namespace YAML { 26 | class Binary; 27 | struct _Null; 28 | } // namespace YAML 29 | 30 | namespace YAML { 31 | class EmitterState; 32 | 33 | class YAML_CPP_API Emitter { 34 | public: 35 | Emitter(); 36 | explicit Emitter(std::ostream& stream); 37 | Emitter(const Emitter&) = delete; 38 | Emitter& operator=(const Emitter&) = delete; 39 | ~Emitter(); 40 | 41 | // output 42 | const char* c_str() const; 43 | std::size_t size() const; 44 | 45 | // state checking 46 | bool good() const; 47 | const std::string GetLastError() const; 48 | 49 | // global setters 50 | bool SetOutputCharset(EMITTER_MANIP value); 51 | bool SetStringFormat(EMITTER_MANIP value); 52 | bool SetBoolFormat(EMITTER_MANIP value); 53 | bool SetNullFormat(EMITTER_MANIP value); 54 | bool SetIntBase(EMITTER_MANIP value); 55 | bool SetSeqFormat(EMITTER_MANIP value); 56 | bool SetMapFormat(EMITTER_MANIP value); 57 | bool SetIndent(std::size_t n); 58 | bool SetPreCommentIndent(std::size_t n); 59 | bool SetPostCommentIndent(std::size_t n); 60 | bool SetFloatPrecision(std::size_t n); 61 | bool SetDoublePrecision(std::size_t n); 62 | void RestoreGlobalModifiedSettings(); 63 | 64 | // local setters 65 | Emitter& SetLocalValue(EMITTER_MANIP value); 66 | Emitter& SetLocalIndent(const _Indent& indent); 67 | Emitter& SetLocalPrecision(const _Precision& precision); 68 | 69 | // overloads of write 70 | Emitter& Write(const std::string& str); 71 | Emitter& Write(bool b); 72 | Emitter& Write(char ch); 73 | Emitter& Write(const _Alias& alias); 74 | Emitter& Write(const _Anchor& anchor); 75 | Emitter& Write(const _Tag& tag); 76 | Emitter& Write(const _Comment& comment); 77 | Emitter& Write(const _Null& n); 78 | Emitter& Write(const Binary& binary); 79 | 80 | template 81 | Emitter& WriteIntegralType(T value); 82 | 83 | template 84 | Emitter& WriteStreamable(T value); 85 | 86 | private: 87 | template 88 | void SetStreamablePrecision(std::stringstream&) {} 89 | std::size_t GetFloatPrecision() const; 90 | std::size_t GetDoublePrecision() const; 91 | 92 | void PrepareIntegralStream(std::stringstream& stream) const; 93 | void StartedScalar(); 94 | 95 | private: 96 | void EmitBeginDoc(); 97 | void EmitEndDoc(); 98 | void EmitBeginSeq(); 99 | void EmitEndSeq(); 100 | void EmitBeginMap(); 101 | void EmitEndMap(); 102 | void EmitNewline(); 103 | void EmitKindTag(); 104 | void EmitTag(bool verbatim, const _Tag& tag); 105 | 106 | void PrepareNode(EmitterNodeType::value child); 107 | void PrepareTopNode(EmitterNodeType::value child); 108 | void FlowSeqPrepareNode(EmitterNodeType::value child); 109 | void BlockSeqPrepareNode(EmitterNodeType::value child); 110 | 111 | void FlowMapPrepareNode(EmitterNodeType::value child); 112 | 113 | void FlowMapPrepareLongKey(EmitterNodeType::value child); 114 | void FlowMapPrepareLongKeyValue(EmitterNodeType::value child); 115 | void FlowMapPrepareSimpleKey(EmitterNodeType::value child); 116 | void FlowMapPrepareSimpleKeyValue(EmitterNodeType::value child); 117 | 118 | void BlockMapPrepareNode(EmitterNodeType::value child); 119 | 120 | void BlockMapPrepareLongKey(EmitterNodeType::value child); 121 | void BlockMapPrepareLongKeyValue(EmitterNodeType::value child); 122 | void BlockMapPrepareSimpleKey(EmitterNodeType::value child); 123 | void BlockMapPrepareSimpleKeyValue(EmitterNodeType::value child); 124 | 125 | void SpaceOrIndentTo(bool requireSpace, std::size_t indent); 126 | 127 | const char* ComputeFullBoolName(bool b) const; 128 | const char* ComputeNullName() const; 129 | bool CanEmitNewline() const; 130 | 131 | private: 132 | std::unique_ptr m_pState; 133 | ostream_wrapper m_stream; 134 | }; 135 | 136 | template 137 | inline Emitter& Emitter::WriteIntegralType(T value) { 138 | if (!good()) 139 | return *this; 140 | 141 | PrepareNode(EmitterNodeType::Scalar); 142 | 143 | std::stringstream stream; 144 | PrepareIntegralStream(stream); 145 | stream << value; 146 | m_stream << stream.str(); 147 | 148 | StartedScalar(); 149 | 150 | return *this; 151 | } 152 | 153 | template 154 | inline Emitter& Emitter::WriteStreamable(T value) { 155 | if (!good()) 156 | return *this; 157 | 158 | PrepareNode(EmitterNodeType::Scalar); 159 | 160 | std::stringstream stream; 161 | SetStreamablePrecision(stream); 162 | 163 | bool special = false; 164 | if (std::is_floating_point::value) { 165 | if ((std::numeric_limits::has_quiet_NaN || 166 | std::numeric_limits::has_signaling_NaN) && 167 | std::isnan(value)) { 168 | special = true; 169 | stream << ".nan"; 170 | } else if (std::numeric_limits::has_infinity && std::isinf(value)) { 171 | special = true; 172 | if (std::signbit(value)) { 173 | stream << "-.inf"; 174 | } else { 175 | stream << ".inf"; 176 | } 177 | } 178 | } 179 | 180 | if (!special) { 181 | stream << value; 182 | } 183 | m_stream << stream.str(); 184 | 185 | StartedScalar(); 186 | 187 | return *this; 188 | } 189 | 190 | template <> 191 | inline void Emitter::SetStreamablePrecision(std::stringstream& stream) { 192 | stream.precision(static_cast(GetFloatPrecision())); 193 | } 194 | 195 | template <> 196 | inline void Emitter::SetStreamablePrecision(std::stringstream& stream) { 197 | stream.precision(static_cast(GetDoublePrecision())); 198 | } 199 | 200 | // overloads of insertion 201 | inline Emitter& operator<<(Emitter& emitter, const std::string& v) { 202 | return emitter.Write(v); 203 | } 204 | inline Emitter& operator<<(Emitter& emitter, bool v) { 205 | return emitter.Write(v); 206 | } 207 | inline Emitter& operator<<(Emitter& emitter, char v) { 208 | return emitter.Write(v); 209 | } 210 | inline Emitter& operator<<(Emitter& emitter, unsigned char v) { 211 | return emitter.Write(static_cast(v)); 212 | } 213 | inline Emitter& operator<<(Emitter& emitter, const _Alias& v) { 214 | return emitter.Write(v); 215 | } 216 | inline Emitter& operator<<(Emitter& emitter, const _Anchor& v) { 217 | return emitter.Write(v); 218 | } 219 | inline Emitter& operator<<(Emitter& emitter, const _Tag& v) { 220 | return emitter.Write(v); 221 | } 222 | inline Emitter& operator<<(Emitter& emitter, const _Comment& v) { 223 | return emitter.Write(v); 224 | } 225 | inline Emitter& operator<<(Emitter& emitter, const _Null& v) { 226 | return emitter.Write(v); 227 | } 228 | inline Emitter& operator<<(Emitter& emitter, const Binary& b) { 229 | return emitter.Write(b); 230 | } 231 | 232 | inline Emitter& operator<<(Emitter& emitter, const char* v) { 233 | return emitter.Write(std::string(v)); 234 | } 235 | 236 | inline Emitter& operator<<(Emitter& emitter, int v) { 237 | return emitter.WriteIntegralType(v); 238 | } 239 | inline Emitter& operator<<(Emitter& emitter, unsigned int v) { 240 | return emitter.WriteIntegralType(v); 241 | } 242 | inline Emitter& operator<<(Emitter& emitter, short v) { 243 | return emitter.WriteIntegralType(v); 244 | } 245 | inline Emitter& operator<<(Emitter& emitter, unsigned short v) { 246 | return emitter.WriteIntegralType(v); 247 | } 248 | inline Emitter& operator<<(Emitter& emitter, long v) { 249 | return emitter.WriteIntegralType(v); 250 | } 251 | inline Emitter& operator<<(Emitter& emitter, unsigned long v) { 252 | return emitter.WriteIntegralType(v); 253 | } 254 | inline Emitter& operator<<(Emitter& emitter, long long v) { 255 | return emitter.WriteIntegralType(v); 256 | } 257 | inline Emitter& operator<<(Emitter& emitter, unsigned long long v) { 258 | return emitter.WriteIntegralType(v); 259 | } 260 | 261 | inline Emitter& operator<<(Emitter& emitter, float v) { 262 | return emitter.WriteStreamable(v); 263 | } 264 | inline Emitter& operator<<(Emitter& emitter, double v) { 265 | return emitter.WriteStreamable(v); 266 | } 267 | 268 | inline Emitter& operator<<(Emitter& emitter, EMITTER_MANIP value) { 269 | return emitter.SetLocalValue(value); 270 | } 271 | 272 | inline Emitter& operator<<(Emitter& emitter, _Indent indent) { 273 | return emitter.SetLocalIndent(indent); 274 | } 275 | 276 | inline Emitter& operator<<(Emitter& emitter, _Precision precision) { 277 | return emitter.SetLocalPrecision(precision); 278 | } 279 | } // namespace YAML 280 | 281 | #endif // EMITTER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 282 | -------------------------------------------------------------------------------- /include/yaml-cpp/emitterdef.h: -------------------------------------------------------------------------------- 1 | #ifndef EMITTERDEF_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define EMITTERDEF_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | namespace YAML { 11 | struct EmitterNodeType { 12 | enum value { NoType, Property, Scalar, FlowSeq, BlockSeq, FlowMap, BlockMap }; 13 | }; 14 | } 15 | 16 | #endif // EMITTERDEF_H_62B23520_7C8E_11DE_8A39_0800200C9A66 17 | -------------------------------------------------------------------------------- /include/yaml-cpp/emittermanip.h: -------------------------------------------------------------------------------- 1 | #ifndef EMITTERMANIP_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define EMITTERMANIP_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | 12 | namespace YAML { 13 | enum EMITTER_MANIP { 14 | // general manipulators 15 | Auto, 16 | TagByKind, 17 | Newline, 18 | 19 | // output character set 20 | EmitNonAscii, 21 | EscapeNonAscii, 22 | EscapeAsJson, 23 | 24 | // string manipulators 25 | // Auto, // duplicate 26 | SingleQuoted, 27 | DoubleQuoted, 28 | Literal, 29 | 30 | // null manipulators 31 | LowerNull, 32 | UpperNull, 33 | CamelNull, 34 | TildeNull, 35 | 36 | // bool manipulators 37 | YesNoBool, // yes, no 38 | TrueFalseBool, // true, false 39 | OnOffBool, // on, off 40 | UpperCase, // TRUE, N 41 | LowerCase, // f, yes 42 | CamelCase, // No, Off 43 | LongBool, // yes, On 44 | ShortBool, // y, t 45 | 46 | // int manipulators 47 | Dec, 48 | Hex, 49 | Oct, 50 | 51 | // document manipulators 52 | BeginDoc, 53 | EndDoc, 54 | 55 | // sequence manipulators 56 | BeginSeq, 57 | EndSeq, 58 | Flow, 59 | Block, 60 | 61 | // map manipulators 62 | BeginMap, 63 | EndMap, 64 | Key, 65 | Value, 66 | // Flow, // duplicate 67 | // Block, // duplicate 68 | // Auto, // duplicate 69 | LongKey 70 | }; 71 | 72 | struct _Indent { 73 | _Indent(int value_) : value(value_) {} 74 | int value; 75 | }; 76 | 77 | inline _Indent Indent(int value) { return _Indent(value); } 78 | 79 | struct _Alias { 80 | _Alias(const std::string& content_) : content(content_) {} 81 | std::string content; 82 | }; 83 | 84 | inline _Alias Alias(const std::string& content) { return _Alias(content); } 85 | 86 | struct _Anchor { 87 | _Anchor(const std::string& content_) : content(content_) {} 88 | std::string content; 89 | }; 90 | 91 | inline _Anchor Anchor(const std::string& content) { return _Anchor(content); } 92 | 93 | struct _Tag { 94 | struct Type { 95 | enum value { Verbatim, PrimaryHandle, NamedHandle }; 96 | }; 97 | 98 | explicit _Tag(const std::string& prefix_, const std::string& content_, 99 | Type::value type_) 100 | : prefix(prefix_), content(content_), type(type_) {} 101 | std::string prefix; 102 | std::string content; 103 | Type::value type; 104 | }; 105 | 106 | inline _Tag VerbatimTag(const std::string& content) { 107 | return _Tag("", content, _Tag::Type::Verbatim); 108 | } 109 | 110 | inline _Tag LocalTag(const std::string& content) { 111 | return _Tag("", content, _Tag::Type::PrimaryHandle); 112 | } 113 | 114 | inline _Tag LocalTag(const std::string& prefix, const std::string content) { 115 | return _Tag(prefix, content, _Tag::Type::NamedHandle); 116 | } 117 | 118 | inline _Tag SecondaryTag(const std::string& content) { 119 | return _Tag("", content, _Tag::Type::NamedHandle); 120 | } 121 | 122 | struct _Comment { 123 | _Comment(const std::string& content_) : content(content_) {} 124 | std::string content; 125 | }; 126 | 127 | inline _Comment Comment(const std::string& content) { return _Comment(content); } 128 | 129 | struct _Precision { 130 | _Precision(int floatPrecision_, int doublePrecision_) 131 | : floatPrecision(floatPrecision_), doublePrecision(doublePrecision_) {} 132 | 133 | int floatPrecision; 134 | int doublePrecision; 135 | }; 136 | 137 | inline _Precision FloatPrecision(int n) { return _Precision(n, -1); } 138 | 139 | inline _Precision DoublePrecision(int n) { return _Precision(-1, n); } 140 | 141 | inline _Precision Precision(int n) { return _Precision(n, n); } 142 | } 143 | 144 | #endif // EMITTERMANIP_H_62B23520_7C8E_11DE_8A39_0800200C9A66 145 | -------------------------------------------------------------------------------- /include/yaml-cpp/emitterstyle.h: -------------------------------------------------------------------------------- 1 | #ifndef EMITTERSTYLE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define EMITTERSTYLE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | namespace YAML { 11 | struct EmitterStyle { 12 | enum value { Default, Block, Flow }; 13 | }; 14 | } 15 | 16 | #endif // EMITTERSTYLE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 17 | -------------------------------------------------------------------------------- /include/yaml-cpp/eventhandler.h: -------------------------------------------------------------------------------- 1 | #ifndef EVENTHANDLER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define EVENTHANDLER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | 12 | #include "yaml-cpp/anchor.h" 13 | #include "yaml-cpp/emitterstyle.h" 14 | 15 | namespace YAML { 16 | struct Mark; 17 | 18 | class EventHandler { 19 | public: 20 | virtual ~EventHandler() = default; 21 | 22 | virtual void OnDocumentStart(const Mark& mark) = 0; 23 | virtual void OnDocumentEnd() = 0; 24 | 25 | virtual void OnNull(const Mark& mark, anchor_t anchor) = 0; 26 | virtual void OnAlias(const Mark& mark, anchor_t anchor) = 0; 27 | virtual void OnScalar(const Mark& mark, const std::string& tag, 28 | anchor_t anchor, const std::string& value) = 0; 29 | 30 | virtual void OnSequenceStart(const Mark& mark, const std::string& tag, 31 | anchor_t anchor, EmitterStyle::value style) = 0; 32 | virtual void OnSequenceEnd() = 0; 33 | 34 | virtual void OnMapStart(const Mark& mark, const std::string& tag, 35 | anchor_t anchor, EmitterStyle::value style) = 0; 36 | virtual void OnMapEnd() = 0; 37 | 38 | virtual void OnAnchor(const Mark& /*mark*/, 39 | const std::string& /*anchor_name*/) { 40 | // empty default implementation for compatibility 41 | } 42 | }; 43 | } // namespace YAML 44 | 45 | #endif // EVENTHANDLER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 46 | -------------------------------------------------------------------------------- /include/yaml-cpp/exceptions.h: -------------------------------------------------------------------------------- 1 | #ifndef EXCEPTIONS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define EXCEPTIONS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/mark.h" 11 | #include "yaml-cpp/noexcept.h" 12 | #include "yaml-cpp/traits.h" 13 | #include 14 | #include 15 | #include 16 | 17 | namespace YAML { 18 | // error messages 19 | namespace ErrorMsg { 20 | const char* const YAML_DIRECTIVE_ARGS = 21 | "YAML directives must have exactly one argument"; 22 | const char* const YAML_VERSION = "bad YAML version: "; 23 | const char* const YAML_MAJOR_VERSION = "YAML major version too large"; 24 | const char* const REPEATED_YAML_DIRECTIVE = "repeated YAML directive"; 25 | const char* const TAG_DIRECTIVE_ARGS = 26 | "TAG directives must have exactly two arguments"; 27 | const char* const REPEATED_TAG_DIRECTIVE = "repeated TAG directive"; 28 | const char* const CHAR_IN_TAG_HANDLE = 29 | "illegal character found while scanning tag handle"; 30 | const char* const TAG_WITH_NO_SUFFIX = "tag handle with no suffix"; 31 | const char* const END_OF_VERBATIM_TAG = "end of verbatim tag not found"; 32 | const char* const END_OF_MAP = "end of map not found"; 33 | const char* const END_OF_MAP_FLOW = "end of map flow not found"; 34 | const char* const END_OF_SEQ = "end of sequence not found"; 35 | const char* const END_OF_SEQ_FLOW = "end of sequence flow not found"; 36 | const char* const MULTIPLE_TAGS = 37 | "cannot assign multiple tags to the same node"; 38 | const char* const MULTIPLE_ANCHORS = 39 | "cannot assign multiple anchors to the same node"; 40 | const char* const MULTIPLE_ALIASES = 41 | "cannot assign multiple aliases to the same node"; 42 | const char* const ALIAS_CONTENT = 43 | "aliases can't have any content, *including* tags"; 44 | const char* const INVALID_HEX = "bad character found while scanning hex number"; 45 | const char* const INVALID_UNICODE = "invalid unicode: "; 46 | const char* const INVALID_ESCAPE = "unknown escape character: "; 47 | const char* const UNKNOWN_TOKEN = "unknown token"; 48 | const char* const DOC_IN_SCALAR = "illegal document indicator in scalar"; 49 | const char* const EOF_IN_SCALAR = "illegal EOF in scalar"; 50 | const char* const CHAR_IN_SCALAR = "illegal character in scalar"; 51 | const char* const TAB_IN_INDENTATION = 52 | "illegal tab when looking for indentation"; 53 | const char* const FLOW_END = "illegal flow end"; 54 | const char* const BLOCK_ENTRY = "illegal block entry"; 55 | const char* const MAP_KEY = "illegal map key"; 56 | const char* const MAP_VALUE = "illegal map value"; 57 | const char* const ALIAS_NOT_FOUND = "alias not found after *"; 58 | const char* const ANCHOR_NOT_FOUND = "anchor not found after &"; 59 | const char* const CHAR_IN_ALIAS = 60 | "illegal character found while scanning alias"; 61 | const char* const CHAR_IN_ANCHOR = 62 | "illegal character found while scanning anchor"; 63 | const char* const ZERO_INDENT_IN_BLOCK = 64 | "cannot set zero indentation for a block scalar"; 65 | const char* const CHAR_IN_BLOCK = "unexpected character in block scalar"; 66 | const char* const AMBIGUOUS_ANCHOR = 67 | "cannot assign the same alias to multiple nodes"; 68 | const char* const UNKNOWN_ANCHOR = "the referenced anchor is not defined"; 69 | 70 | const char* const INVALID_NODE = 71 | "invalid node; this may result from using a map iterator as a sequence " 72 | "iterator, or vice-versa"; 73 | const char* const INVALID_SCALAR = "invalid scalar"; 74 | const char* const KEY_NOT_FOUND = "key not found"; 75 | const char* const BAD_CONVERSION = "bad conversion"; 76 | const char* const BAD_DEREFERENCE = "bad dereference"; 77 | const char* const BAD_SUBSCRIPT = "operator[] call on a scalar"; 78 | const char* const BAD_PUSHBACK = "appending to a non-sequence"; 79 | const char* const BAD_INSERT = "inserting in a non-convertible-to-map"; 80 | 81 | const char* const UNMATCHED_GROUP_TAG = "unmatched group tag"; 82 | const char* const UNEXPECTED_END_SEQ = "unexpected end sequence token"; 83 | const char* const UNEXPECTED_END_MAP = "unexpected end map token"; 84 | const char* const SINGLE_QUOTED_CHAR = 85 | "invalid character in single-quoted string"; 86 | const char* const INVALID_ANCHOR = "invalid anchor"; 87 | const char* const INVALID_ALIAS = "invalid alias"; 88 | const char* const INVALID_TAG = "invalid tag"; 89 | const char* const BAD_FILE = "bad file"; 90 | 91 | template 92 | inline const std::string KEY_NOT_FOUND_WITH_KEY( 93 | const T&, typename disable_if>::type* = 0) { 94 | return KEY_NOT_FOUND; 95 | } 96 | 97 | inline const std::string KEY_NOT_FOUND_WITH_KEY(const std::string& key) { 98 | std::stringstream stream; 99 | stream << KEY_NOT_FOUND << ": " << key; 100 | return stream.str(); 101 | } 102 | 103 | inline const std::string KEY_NOT_FOUND_WITH_KEY(const char* key) { 104 | std::stringstream stream; 105 | stream << KEY_NOT_FOUND << ": " << key; 106 | return stream.str(); 107 | } 108 | 109 | template 110 | inline const std::string KEY_NOT_FOUND_WITH_KEY( 111 | const T& key, typename enable_if>::type* = 0) { 112 | std::stringstream stream; 113 | stream << KEY_NOT_FOUND << ": " << key; 114 | return stream.str(); 115 | } 116 | 117 | template 118 | inline const std::string BAD_SUBSCRIPT_WITH_KEY( 119 | const T&, typename disable_if>::type* = nullptr) { 120 | return BAD_SUBSCRIPT; 121 | } 122 | 123 | inline const std::string BAD_SUBSCRIPT_WITH_KEY(const std::string& key) { 124 | std::stringstream stream; 125 | stream << BAD_SUBSCRIPT << " (key: \"" << key << "\")"; 126 | return stream.str(); 127 | } 128 | 129 | inline const std::string BAD_SUBSCRIPT_WITH_KEY(const char* key) { 130 | std::stringstream stream; 131 | stream << BAD_SUBSCRIPT << " (key: \"" << key << "\")"; 132 | return stream.str(); 133 | } 134 | 135 | template 136 | inline const std::string BAD_SUBSCRIPT_WITH_KEY( 137 | const T& key, typename enable_if>::type* = nullptr) { 138 | std::stringstream stream; 139 | stream << BAD_SUBSCRIPT << " (key: \"" << key << "\")"; 140 | return stream.str(); 141 | } 142 | 143 | inline const std::string INVALID_NODE_WITH_KEY(const std::string& key) { 144 | std::stringstream stream; 145 | if (key.empty()) { 146 | return INVALID_NODE; 147 | } 148 | stream << "invalid node; first invalid key: \"" << key << "\""; 149 | return stream.str(); 150 | } 151 | } // namespace ErrorMsg 152 | 153 | class YAML_CPP_API Exception : public std::runtime_error { 154 | public: 155 | Exception(const Mark& mark_, const std::string& msg_) 156 | : std::runtime_error(build_what(mark_, msg_)), mark(mark_), msg(msg_) {} 157 | ~Exception() YAML_CPP_NOEXCEPT override; 158 | 159 | Exception(const Exception&) = default; 160 | 161 | Mark mark; 162 | std::string msg; 163 | 164 | private: 165 | static const std::string build_what(const Mark& mark, 166 | const std::string& msg) { 167 | if (mark.is_null()) { 168 | return msg; 169 | } 170 | 171 | std::stringstream output; 172 | output << "yaml-cpp: error at line " << mark.line + 1 << ", column " 173 | << mark.column + 1 << ": " << msg; 174 | return output.str(); 175 | } 176 | }; 177 | 178 | class YAML_CPP_API ParserException : public Exception { 179 | public: 180 | ParserException(const Mark& mark_, const std::string& msg_) 181 | : Exception(mark_, msg_) {} 182 | ParserException(const ParserException&) = default; 183 | ~ParserException() YAML_CPP_NOEXCEPT override; 184 | }; 185 | 186 | class YAML_CPP_API RepresentationException : public Exception { 187 | public: 188 | RepresentationException(const Mark& mark_, const std::string& msg_) 189 | : Exception(mark_, msg_) {} 190 | RepresentationException(const RepresentationException&) = default; 191 | ~RepresentationException() YAML_CPP_NOEXCEPT override; 192 | }; 193 | 194 | // representation exceptions 195 | class YAML_CPP_API InvalidScalar : public RepresentationException { 196 | public: 197 | InvalidScalar(const Mark& mark_) 198 | : RepresentationException(mark_, ErrorMsg::INVALID_SCALAR) {} 199 | InvalidScalar(const InvalidScalar&) = default; 200 | ~InvalidScalar() YAML_CPP_NOEXCEPT override; 201 | }; 202 | 203 | class YAML_CPP_API KeyNotFound : public RepresentationException { 204 | public: 205 | template 206 | KeyNotFound(const Mark& mark_, const T& key_) 207 | : RepresentationException(mark_, ErrorMsg::KEY_NOT_FOUND_WITH_KEY(key_)) { 208 | } 209 | KeyNotFound(const KeyNotFound&) = default; 210 | ~KeyNotFound() YAML_CPP_NOEXCEPT override; 211 | }; 212 | 213 | template 214 | class YAML_CPP_API TypedKeyNotFound : public KeyNotFound { 215 | public: 216 | TypedKeyNotFound(const Mark& mark_, const T& key_) 217 | : KeyNotFound(mark_, key_), key(key_) {} 218 | ~TypedKeyNotFound() YAML_CPP_NOEXCEPT override = default; 219 | 220 | T key; 221 | }; 222 | 223 | template 224 | inline TypedKeyNotFound MakeTypedKeyNotFound(const Mark& mark, 225 | const T& key) { 226 | return TypedKeyNotFound(mark, key); 227 | } 228 | 229 | class YAML_CPP_API InvalidNode : public RepresentationException { 230 | public: 231 | InvalidNode(const std::string& key) 232 | : RepresentationException(Mark::null_mark(), 233 | ErrorMsg::INVALID_NODE_WITH_KEY(key)) {} 234 | InvalidNode(const InvalidNode&) = default; 235 | ~InvalidNode() YAML_CPP_NOEXCEPT override; 236 | }; 237 | 238 | class YAML_CPP_API BadConversion : public RepresentationException { 239 | public: 240 | explicit BadConversion(const Mark& mark_) 241 | : RepresentationException(mark_, ErrorMsg::BAD_CONVERSION) {} 242 | BadConversion(const BadConversion&) = default; 243 | ~BadConversion() YAML_CPP_NOEXCEPT override; 244 | }; 245 | 246 | template 247 | class TypedBadConversion : public BadConversion { 248 | public: 249 | explicit TypedBadConversion(const Mark& mark_) : BadConversion(mark_) {} 250 | }; 251 | 252 | class YAML_CPP_API BadDereference : public RepresentationException { 253 | public: 254 | BadDereference() 255 | : RepresentationException(Mark::null_mark(), ErrorMsg::BAD_DEREFERENCE) {} 256 | BadDereference(const BadDereference&) = default; 257 | ~BadDereference() YAML_CPP_NOEXCEPT override; 258 | }; 259 | 260 | class YAML_CPP_API BadSubscript : public RepresentationException { 261 | public: 262 | template 263 | BadSubscript(const Mark& mark_, const Key& key) 264 | : RepresentationException(mark_, ErrorMsg::BAD_SUBSCRIPT_WITH_KEY(key)) {} 265 | BadSubscript(const BadSubscript&) = default; 266 | ~BadSubscript() YAML_CPP_NOEXCEPT override; 267 | }; 268 | 269 | class YAML_CPP_API BadPushback : public RepresentationException { 270 | public: 271 | BadPushback() 272 | : RepresentationException(Mark::null_mark(), ErrorMsg::BAD_PUSHBACK) {} 273 | BadPushback(const BadPushback&) = default; 274 | ~BadPushback() YAML_CPP_NOEXCEPT override; 275 | }; 276 | 277 | class YAML_CPP_API BadInsert : public RepresentationException { 278 | public: 279 | BadInsert() 280 | : RepresentationException(Mark::null_mark(), ErrorMsg::BAD_INSERT) {} 281 | BadInsert(const BadInsert&) = default; 282 | ~BadInsert() YAML_CPP_NOEXCEPT override; 283 | }; 284 | 285 | class YAML_CPP_API EmitterException : public Exception { 286 | public: 287 | EmitterException(const std::string& msg_) 288 | : Exception(Mark::null_mark(), msg_) {} 289 | EmitterException(const EmitterException&) = default; 290 | ~EmitterException() YAML_CPP_NOEXCEPT override; 291 | }; 292 | 293 | class YAML_CPP_API BadFile : public Exception { 294 | public: 295 | explicit BadFile(const std::string& filename) 296 | : Exception(Mark::null_mark(), 297 | std::string(ErrorMsg::BAD_FILE) + ": " + filename) {} 298 | BadFile(const BadFile&) = default; 299 | ~BadFile() YAML_CPP_NOEXCEPT override; 300 | }; 301 | } // namespace YAML 302 | 303 | #endif // EXCEPTIONS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 304 | -------------------------------------------------------------------------------- /include/yaml-cpp/mark.h: -------------------------------------------------------------------------------- 1 | #ifndef MARK_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define MARK_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | 12 | namespace YAML { 13 | struct YAML_CPP_API Mark { 14 | Mark() : pos(0), line(0), column(0) {} 15 | 16 | static const Mark null_mark() { return Mark(-1, -1, -1); } 17 | 18 | bool is_null() const { return pos == -1 && line == -1 && column == -1; } 19 | 20 | int pos; 21 | int line, column; 22 | 23 | private: 24 | Mark(int pos_, int line_, int column_) 25 | : pos(pos_), line(line_), column(column_) {} 26 | }; 27 | } 28 | 29 | #endif // MARK_H_62B23520_7C8E_11DE_8A39_0800200C9A66 30 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/convert.h: -------------------------------------------------------------------------------- 1 | #ifndef NODE_CONVERT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define NODE_CONVERT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | #include "yaml-cpp/binary.h" 20 | #include "yaml-cpp/node/impl.h" 21 | #include "yaml-cpp/node/iterator.h" 22 | #include "yaml-cpp/node/node.h" 23 | #include "yaml-cpp/node/type.h" 24 | #include "yaml-cpp/null.h" 25 | 26 | 27 | namespace YAML { 28 | class Binary; 29 | struct _Null; 30 | template 31 | struct convert; 32 | } // namespace YAML 33 | 34 | namespace YAML { 35 | namespace conversion { 36 | inline bool IsInfinity(const std::string& input) { 37 | return input == ".inf" || input == ".Inf" || input == ".INF" || 38 | input == "+.inf" || input == "+.Inf" || input == "+.INF"; 39 | } 40 | 41 | inline bool IsNegativeInfinity(const std::string& input) { 42 | return input == "-.inf" || input == "-.Inf" || input == "-.INF"; 43 | } 44 | 45 | inline bool IsNaN(const std::string& input) { 46 | return input == ".nan" || input == ".NaN" || input == ".NAN"; 47 | } 48 | } 49 | 50 | // Node 51 | template <> 52 | struct convert { 53 | static Node encode(const Node& rhs) { return rhs; } 54 | 55 | static bool decode(const Node& node, Node& rhs) { 56 | rhs.reset(node); 57 | return true; 58 | } 59 | }; 60 | 61 | // std::string 62 | template <> 63 | struct convert { 64 | static Node encode(const std::string& rhs) { return Node(rhs); } 65 | 66 | static bool decode(const Node& node, std::string& rhs) { 67 | if (!node.IsScalar()) 68 | return false; 69 | rhs = node.Scalar(); 70 | return true; 71 | } 72 | }; 73 | 74 | // C-strings can only be encoded 75 | template <> 76 | struct convert { 77 | static Node encode(const char* rhs) { return Node(rhs); } 78 | }; 79 | 80 | template <> 81 | struct convert { 82 | static Node encode(const char* rhs) { return Node(rhs); } 83 | }; 84 | 85 | template 86 | struct convert { 87 | static Node encode(const char* rhs) { return Node(rhs); } 88 | }; 89 | 90 | template <> 91 | struct convert<_Null> { 92 | static Node encode(const _Null& /* rhs */) { return Node(); } 93 | 94 | static bool decode(const Node& node, _Null& /* rhs */) { 95 | return node.IsNull(); 96 | } 97 | }; 98 | 99 | namespace conversion { 100 | template 101 | typename std::enable_if< std::is_floating_point::value, void>::type 102 | inner_encode(const T& rhs, std::stringstream& stream){ 103 | if (std::isnan(rhs)) { 104 | stream << ".nan"; 105 | } else if (std::isinf(rhs)) { 106 | if (std::signbit(rhs)) { 107 | stream << "-.inf"; 108 | } else { 109 | stream << ".inf"; 110 | } 111 | } else { 112 | stream << rhs; 113 | } 114 | } 115 | 116 | template 117 | typename std::enable_if::value, void>::type 118 | inner_encode(const T& rhs, std::stringstream& stream){ 119 | stream << rhs; 120 | } 121 | 122 | template 123 | typename std::enable_if<(std::is_same::value || 124 | std::is_same::value), bool>::type 125 | ConvertStreamTo(std::stringstream& stream, T& rhs) { 126 | int num; 127 | if ((stream >> std::noskipws >> num) && (stream >> std::ws).eof()) { 128 | if (num >= (std::numeric_limits::min)() && 129 | num <= (std::numeric_limits::max)()) { 130 | rhs = (T)num; 131 | return true; 132 | } 133 | } 134 | return false; 135 | } 136 | 137 | template 138 | typename std::enable_if::value || 139 | std::is_same::value), bool>::type 140 | ConvertStreamTo(std::stringstream& stream, T& rhs) { 141 | if ((stream >> std::noskipws >> rhs) && (stream >> std::ws).eof()) { 142 | return true; 143 | } 144 | return false; 145 | } 146 | } 147 | 148 | #define YAML_DEFINE_CONVERT_STREAMABLE(type, negative_op) \ 149 | template <> \ 150 | struct convert { \ 151 | \ 152 | static Node encode(const type& rhs) { \ 153 | std::stringstream stream; \ 154 | stream.precision(std::numeric_limits::max_digits10); \ 155 | conversion::inner_encode(rhs, stream); \ 156 | return Node(stream.str()); \ 157 | } \ 158 | \ 159 | static bool decode(const Node& node, type& rhs) { \ 160 | if (node.Type() != NodeType::Scalar) { \ 161 | return false; \ 162 | } \ 163 | const std::string& input = node.Scalar(); \ 164 | std::stringstream stream(input); \ 165 | stream.unsetf(std::ios::dec); \ 166 | if ((stream.peek() == '-') && std::is_unsigned::value) { \ 167 | return false; \ 168 | } \ 169 | if (conversion::ConvertStreamTo(stream, rhs)) { \ 170 | return true; \ 171 | } \ 172 | if (std::numeric_limits::has_infinity) { \ 173 | if (conversion::IsInfinity(input)) { \ 174 | rhs = std::numeric_limits::infinity(); \ 175 | return true; \ 176 | } else if (conversion::IsNegativeInfinity(input)) { \ 177 | rhs = negative_op std::numeric_limits::infinity(); \ 178 | return true; \ 179 | } \ 180 | } \ 181 | \ 182 | if (std::numeric_limits::has_quiet_NaN) { \ 183 | if (conversion::IsNaN(input)) { \ 184 | rhs = std::numeric_limits::quiet_NaN(); \ 185 | return true; \ 186 | } \ 187 | } \ 188 | \ 189 | return false; \ 190 | } \ 191 | } 192 | 193 | #define YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(type) \ 194 | YAML_DEFINE_CONVERT_STREAMABLE(type, -) 195 | 196 | #define YAML_DEFINE_CONVERT_STREAMABLE_UNSIGNED(type) \ 197 | YAML_DEFINE_CONVERT_STREAMABLE(type, +) 198 | 199 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(int); 200 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(short); 201 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(long); 202 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(long long); 203 | YAML_DEFINE_CONVERT_STREAMABLE_UNSIGNED(unsigned); 204 | YAML_DEFINE_CONVERT_STREAMABLE_UNSIGNED(unsigned short); 205 | YAML_DEFINE_CONVERT_STREAMABLE_UNSIGNED(unsigned long); 206 | YAML_DEFINE_CONVERT_STREAMABLE_UNSIGNED(unsigned long long); 207 | 208 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(char); 209 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(signed char); 210 | YAML_DEFINE_CONVERT_STREAMABLE_UNSIGNED(unsigned char); 211 | 212 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(float); 213 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(double); 214 | YAML_DEFINE_CONVERT_STREAMABLE_SIGNED(long double); 215 | 216 | #undef YAML_DEFINE_CONVERT_STREAMABLE_SIGNED 217 | #undef YAML_DEFINE_CONVERT_STREAMABLE_UNSIGNED 218 | #undef YAML_DEFINE_CONVERT_STREAMABLE 219 | 220 | // bool 221 | template <> 222 | struct convert { 223 | static Node encode(bool rhs) { return rhs ? Node("true") : Node("false"); } 224 | 225 | YAML_CPP_API static bool decode(const Node& node, bool& rhs); 226 | }; 227 | 228 | // std::map 229 | template 230 | struct convert> { 231 | static Node encode(const std::map& rhs) { 232 | Node node(NodeType::Map); 233 | for (const auto& element : rhs) 234 | node.force_insert(element.first, element.second); 235 | return node; 236 | } 237 | 238 | static bool decode(const Node& node, std::map& rhs) { 239 | if (!node.IsMap()) 240 | return false; 241 | 242 | rhs.clear(); 243 | for (const auto& element : node) 244 | #if defined(__GNUC__) && __GNUC__ < 4 245 | // workaround for GCC 3: 246 | rhs[element.first.template as()] = element.second.template as(); 247 | #else 248 | rhs[element.first.as()] = element.second.as(); 249 | #endif 250 | return true; 251 | } 252 | }; 253 | 254 | // std::vector 255 | template 256 | struct convert> { 257 | static Node encode(const std::vector& rhs) { 258 | Node node(NodeType::Sequence); 259 | for (const auto& element : rhs) 260 | node.push_back(element); 261 | return node; 262 | } 263 | 264 | static bool decode(const Node& node, std::vector& rhs) { 265 | if (!node.IsSequence()) 266 | return false; 267 | 268 | rhs.clear(); 269 | for (const auto& element : node) 270 | #if defined(__GNUC__) && __GNUC__ < 4 271 | // workaround for GCC 3: 272 | rhs.push_back(element.template as()); 273 | #else 274 | rhs.push_back(element.as()); 275 | #endif 276 | return true; 277 | } 278 | }; 279 | 280 | // std::list 281 | template 282 | struct convert> { 283 | static Node encode(const std::list& rhs) { 284 | Node node(NodeType::Sequence); 285 | for (const auto& element : rhs) 286 | node.push_back(element); 287 | return node; 288 | } 289 | 290 | static bool decode(const Node& node, std::list& rhs) { 291 | if (!node.IsSequence()) 292 | return false; 293 | 294 | rhs.clear(); 295 | for (const auto& element : node) 296 | #if defined(__GNUC__) && __GNUC__ < 4 297 | // workaround for GCC 3: 298 | rhs.push_back(element.template as()); 299 | #else 300 | rhs.push_back(element.as()); 301 | #endif 302 | return true; 303 | } 304 | }; 305 | 306 | // std::array 307 | template 308 | struct convert> { 309 | static Node encode(const std::array& rhs) { 310 | Node node(NodeType::Sequence); 311 | for (const auto& element : rhs) { 312 | node.push_back(element); 313 | } 314 | return node; 315 | } 316 | 317 | static bool decode(const Node& node, std::array& rhs) { 318 | if (!isNodeValid(node)) { 319 | return false; 320 | } 321 | 322 | for (auto i = 0u; i < node.size(); ++i) { 323 | #if defined(__GNUC__) && __GNUC__ < 4 324 | // workaround for GCC 3: 325 | rhs[i] = node[i].template as(); 326 | #else 327 | rhs[i] = node[i].as(); 328 | #endif 329 | } 330 | return true; 331 | } 332 | 333 | private: 334 | static bool isNodeValid(const Node& node) { 335 | return node.IsSequence() && node.size() == N; 336 | } 337 | }; 338 | 339 | // std::pair 340 | template 341 | struct convert> { 342 | static Node encode(const std::pair& rhs) { 343 | Node node(NodeType::Sequence); 344 | node.push_back(rhs.first); 345 | node.push_back(rhs.second); 346 | return node; 347 | } 348 | 349 | static bool decode(const Node& node, std::pair& rhs) { 350 | if (!node.IsSequence()) 351 | return false; 352 | if (node.size() != 2) 353 | return false; 354 | 355 | #if defined(__GNUC__) && __GNUC__ < 4 356 | // workaround for GCC 3: 357 | rhs.first = node[0].template as(); 358 | #else 359 | rhs.first = node[0].as(); 360 | #endif 361 | #if defined(__GNUC__) && __GNUC__ < 4 362 | // workaround for GCC 3: 363 | rhs.second = node[1].template as(); 364 | #else 365 | rhs.second = node[1].as(); 366 | #endif 367 | return true; 368 | } 369 | }; 370 | 371 | // binary 372 | template <> 373 | struct convert { 374 | static Node encode(const Binary& rhs) { 375 | return Node(EncodeBase64(rhs.data(), rhs.size())); 376 | } 377 | 378 | static bool decode(const Node& node, Binary& rhs) { 379 | if (!node.IsScalar()) 380 | return false; 381 | 382 | std::vector data = DecodeBase64(node.Scalar()); 383 | if (data.empty() && !node.Scalar().empty()) 384 | return false; 385 | 386 | rhs.swap(data); 387 | return true; 388 | } 389 | }; 390 | } 391 | 392 | #endif // NODE_CONVERT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 393 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/detail/impl.h: -------------------------------------------------------------------------------- 1 | #ifndef NODE_DETAIL_IMPL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define NODE_DETAIL_IMPL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/node/detail/node.h" 11 | #include "yaml-cpp/node/detail/node_data.h" 12 | 13 | #include 14 | #include 15 | 16 | namespace YAML { 17 | namespace detail { 18 | template 19 | struct get_idx { 20 | static node* get(const std::vector& /* sequence */, 21 | const Key& /* key */, shared_memory_holder /* pMemory */) { 22 | return nullptr; 23 | } 24 | }; 25 | 26 | template 27 | struct get_idx::value && 29 | !std::is_same::value>::type> { 30 | static node* get(const std::vector& sequence, const Key& key, 31 | shared_memory_holder /* pMemory */) { 32 | return key < sequence.size() ? sequence[key] : nullptr; 33 | } 34 | 35 | static node* get(std::vector& sequence, const Key& key, 36 | shared_memory_holder pMemory) { 37 | if (key > sequence.size() || (key > 0 && !sequence[key - 1]->is_defined())) 38 | return nullptr; 39 | if (key == sequence.size()) 40 | sequence.push_back(&pMemory->create_node()); 41 | return sequence[key]; 42 | } 43 | }; 44 | 45 | template 46 | struct get_idx::value>::type> { 47 | static node* get(const std::vector& sequence, const Key& key, 48 | shared_memory_holder pMemory) { 49 | return key >= 0 ? get_idx::get( 50 | sequence, static_cast(key), pMemory) 51 | : nullptr; 52 | } 53 | static node* get(std::vector& sequence, const Key& key, 54 | shared_memory_holder pMemory) { 55 | return key >= 0 ? get_idx::get( 56 | sequence, static_cast(key), pMemory) 57 | : nullptr; 58 | } 59 | }; 60 | 61 | template 62 | struct remove_idx { 63 | static bool remove(std::vector&, const Key&, std::size_t&) { 64 | return false; 65 | } 66 | }; 67 | 68 | template 69 | struct remove_idx< 70 | Key, typename std::enable_if::value && 71 | !std::is_same::value>::type> { 72 | 73 | static bool remove(std::vector& sequence, const Key& key, 74 | std::size_t& seqSize) { 75 | if (key >= sequence.size()) { 76 | return false; 77 | } else { 78 | sequence.erase(sequence.begin() + key); 79 | if (seqSize > key) { 80 | --seqSize; 81 | } 82 | return true; 83 | } 84 | } 85 | }; 86 | 87 | template 88 | struct remove_idx::value>::type> { 90 | 91 | static bool remove(std::vector& sequence, const Key& key, 92 | std::size_t& seqSize) { 93 | return key >= 0 ? remove_idx::remove( 94 | sequence, static_cast(key), seqSize) 95 | : false; 96 | } 97 | }; 98 | 99 | template 100 | inline bool node::equals(const T& rhs, shared_memory_holder pMemory) { 101 | T lhs; 102 | if (convert::decode(Node(*this, pMemory), lhs)) { 103 | return lhs == rhs; 104 | } 105 | return false; 106 | } 107 | 108 | inline bool node::equals(const char* rhs, shared_memory_holder pMemory) { 109 | std::string lhs; 110 | if (convert::decode(Node(*this, std::move(pMemory)), lhs)) { 111 | return lhs == rhs; 112 | } 113 | return false; 114 | } 115 | 116 | // indexing 117 | template 118 | inline node* node_data::get(const Key& key, 119 | shared_memory_holder pMemory) const { 120 | switch (m_type) { 121 | case NodeType::Map: 122 | break; 123 | case NodeType::Undefined: 124 | case NodeType::Null: 125 | return nullptr; 126 | case NodeType::Sequence: 127 | if (node* pNode = get_idx::get(m_sequence, key, pMemory)) 128 | return pNode; 129 | return nullptr; 130 | case NodeType::Scalar: 131 | throw BadSubscript(m_mark, key); 132 | } 133 | 134 | auto it = std::find_if(m_map.begin(), m_map.end(), [&](const kv_pair m) { 135 | return m.first->equals(key, pMemory); 136 | }); 137 | 138 | return it != m_map.end() ? it->second : nullptr; 139 | } 140 | 141 | template 142 | inline node& node_data::get(const Key& key, shared_memory_holder pMemory) { 143 | switch (m_type) { 144 | case NodeType::Map: 145 | break; 146 | case NodeType::Undefined: 147 | case NodeType::Null: 148 | case NodeType::Sequence: 149 | if (node* pNode = get_idx::get(m_sequence, key, pMemory)) { 150 | m_type = NodeType::Sequence; 151 | return *pNode; 152 | } 153 | 154 | convert_to_map(pMemory); 155 | break; 156 | case NodeType::Scalar: 157 | throw BadSubscript(m_mark, key); 158 | } 159 | 160 | auto it = std::find_if(m_map.begin(), m_map.end(), [&](const kv_pair m) { 161 | return m.first->equals(key, pMemory); 162 | }); 163 | 164 | if (it != m_map.end()) { 165 | return *it->second; 166 | } 167 | 168 | node& k = convert_to_node(key, pMemory); 169 | node& v = pMemory->create_node(); 170 | insert_map_pair(k, v); 171 | return v; 172 | } 173 | 174 | template 175 | inline bool node_data::remove(const Key& key, shared_memory_holder pMemory) { 176 | if (m_type == NodeType::Sequence) { 177 | return remove_idx::remove(m_sequence, key, m_seqSize); 178 | } 179 | 180 | if (m_type == NodeType::Map) { 181 | kv_pairs::iterator it = m_undefinedPairs.begin(); 182 | while (it != m_undefinedPairs.end()) { 183 | kv_pairs::iterator jt = std::next(it); 184 | if (it->first->equals(key, pMemory)) { 185 | m_undefinedPairs.erase(it); 186 | } 187 | it = jt; 188 | } 189 | 190 | auto iter = std::find_if(m_map.begin(), m_map.end(), [&](const kv_pair m) { 191 | return m.first->equals(key, pMemory); 192 | }); 193 | 194 | if (iter != m_map.end()) { 195 | m_map.erase(iter); 196 | return true; 197 | } 198 | } 199 | 200 | return false; 201 | } 202 | 203 | // map 204 | template 205 | inline void node_data::force_insert(const Key& key, const Value& value, 206 | shared_memory_holder pMemory) { 207 | switch (m_type) { 208 | case NodeType::Map: 209 | break; 210 | case NodeType::Undefined: 211 | case NodeType::Null: 212 | case NodeType::Sequence: 213 | convert_to_map(pMemory); 214 | break; 215 | case NodeType::Scalar: 216 | throw BadInsert(); 217 | } 218 | 219 | node& k = convert_to_node(key, pMemory); 220 | node& v = convert_to_node(value, pMemory); 221 | insert_map_pair(k, v); 222 | } 223 | 224 | template 225 | inline node& node_data::convert_to_node(const T& rhs, 226 | shared_memory_holder pMemory) { 227 | Node value = convert::encode(rhs); 228 | value.EnsureNodeExists(); 229 | pMemory->merge(*value.m_pMemory); 230 | return *value.m_pNode; 231 | } 232 | } 233 | } 234 | 235 | #endif // NODE_DETAIL_IMPL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 236 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/detail/iterator.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_DETAIL_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_DETAIL_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | #include "yaml-cpp/node/detail/node_iterator.h" 12 | #include "yaml-cpp/node/node.h" 13 | #include "yaml-cpp/node/ptr.h" 14 | #include 15 | #include 16 | 17 | 18 | namespace YAML { 19 | namespace detail { 20 | struct iterator_value; 21 | 22 | template 23 | class iterator_base { 24 | 25 | private: 26 | template 27 | friend class iterator_base; 28 | struct enabler {}; 29 | using base_type = node_iterator; 30 | 31 | struct proxy { 32 | explicit proxy(const V& x) : m_ref(x) {} 33 | V* operator->() { return std::addressof(m_ref); } 34 | operator V*() { return std::addressof(m_ref); } 35 | 36 | V m_ref; 37 | }; 38 | 39 | public: 40 | using iterator_category = std::forward_iterator_tag; 41 | using value_type = V; 42 | using difference_type = std::ptrdiff_t; 43 | using pointer = V*; 44 | using reference = V; 45 | 46 | public: 47 | iterator_base() : m_iterator(), m_pMemory() {} 48 | explicit iterator_base(base_type rhs, shared_memory_holder pMemory) 49 | : m_iterator(rhs), m_pMemory(pMemory) {} 50 | 51 | template 52 | iterator_base(const iterator_base& rhs, 53 | typename std::enable_if::value, 54 | enabler>::type = enabler()) 55 | : m_iterator(rhs.m_iterator), m_pMemory(rhs.m_pMemory) {} 56 | 57 | iterator_base& operator++() { 58 | ++m_iterator; 59 | return *this; 60 | } 61 | 62 | iterator_base operator++(int) { 63 | iterator_base iterator_pre(*this); 64 | ++(*this); 65 | return iterator_pre; 66 | } 67 | 68 | template 69 | bool operator==(const iterator_base& rhs) const { 70 | return m_iterator == rhs.m_iterator; 71 | } 72 | 73 | template 74 | bool operator!=(const iterator_base& rhs) const { 75 | return m_iterator != rhs.m_iterator; 76 | } 77 | 78 | value_type operator*() const { 79 | const typename base_type::value_type& v = *m_iterator; 80 | if (v.pNode) 81 | return value_type(Node(*v, m_pMemory)); 82 | if (v.first && v.second) 83 | return value_type(Node(*v.first, m_pMemory), Node(*v.second, m_pMemory)); 84 | return value_type(); 85 | } 86 | 87 | proxy operator->() const { return proxy(**this); } 88 | 89 | private: 90 | base_type m_iterator; 91 | shared_memory_holder m_pMemory; 92 | }; 93 | } // namespace detail 94 | } // namespace YAML 95 | 96 | #endif // VALUE_DETAIL_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 97 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/detail/iterator_fwd.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_DETAIL_ITERATOR_FWD_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_DETAIL_ITERATOR_FWD_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | #include 12 | #include 13 | #include 14 | 15 | namespace YAML { 16 | 17 | namespace detail { 18 | struct iterator_value; 19 | template 20 | class iterator_base; 21 | } 22 | 23 | using iterator = detail::iterator_base; 24 | using const_iterator = detail::iterator_base; 25 | } 26 | 27 | #endif // VALUE_DETAIL_ITERATOR_FWD_H_62B23520_7C8E_11DE_8A39_0800200C9A66 28 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/detail/memory.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_DETAIL_MEMORY_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_DETAIL_MEMORY_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | 12 | #include "yaml-cpp/dll.h" 13 | #include "yaml-cpp/node/ptr.h" 14 | 15 | namespace YAML { 16 | namespace detail { 17 | class node; 18 | } // namespace detail 19 | } // namespace YAML 20 | 21 | namespace YAML { 22 | namespace detail { 23 | class YAML_CPP_API memory { 24 | public: 25 | memory() : m_nodes{} {} 26 | node& create_node(); 27 | void merge(const memory& rhs); 28 | 29 | private: 30 | using Nodes = std::set; 31 | Nodes m_nodes; 32 | }; 33 | 34 | class YAML_CPP_API memory_holder { 35 | public: 36 | memory_holder() : m_pMemory(new memory) {} 37 | 38 | node& create_node() { return m_pMemory->create_node(); } 39 | void merge(memory_holder& rhs); 40 | 41 | private: 42 | shared_memory m_pMemory; 43 | }; 44 | } // namespace detail 45 | } // namespace YAML 46 | 47 | #endif // VALUE_DETAIL_MEMORY_H_62B23520_7C8E_11DE_8A39_0800200C9A66 48 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/detail/node.h: -------------------------------------------------------------------------------- 1 | #ifndef NODE_DETAIL_NODE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define NODE_DETAIL_NODE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | #include "yaml-cpp/emitterstyle.h" 12 | #include "yaml-cpp/node/detail/node_ref.h" 13 | #include "yaml-cpp/node/ptr.h" 14 | #include "yaml-cpp/node/type.h" 15 | #include 16 | #include 17 | 18 | namespace YAML { 19 | namespace detail { 20 | class node { 21 | private: 22 | struct less { 23 | bool operator ()(const node* l, const node* r) const {return l->m_index < r->m_index;} 24 | }; 25 | 26 | public: 27 | node() : m_pRef(new node_ref), m_dependencies{}, m_index{} {} 28 | node(const node&) = delete; 29 | node& operator=(const node&) = delete; 30 | 31 | bool is(const node& rhs) const { return m_pRef == rhs.m_pRef; } 32 | const node_ref* ref() const { return m_pRef.get(); } 33 | 34 | bool is_defined() const { return m_pRef->is_defined(); } 35 | const Mark& mark() const { return m_pRef->mark(); } 36 | NodeType::value type() const { return m_pRef->type(); } 37 | 38 | const std::string& scalar() const { return m_pRef->scalar(); } 39 | const std::string& tag() const { return m_pRef->tag(); } 40 | EmitterStyle::value style() const { return m_pRef->style(); } 41 | 42 | template 43 | bool equals(const T& rhs, shared_memory_holder pMemory); 44 | bool equals(const char* rhs, shared_memory_holder pMemory); 45 | 46 | void mark_defined() { 47 | if (is_defined()) 48 | return; 49 | 50 | m_pRef->mark_defined(); 51 | for (node* dependency : m_dependencies) 52 | dependency->mark_defined(); 53 | m_dependencies.clear(); 54 | } 55 | 56 | void add_dependency(node& rhs) { 57 | if (is_defined()) 58 | rhs.mark_defined(); 59 | else 60 | m_dependencies.insert(&rhs); 61 | } 62 | 63 | void set_ref(const node& rhs) { 64 | if (rhs.is_defined()) 65 | mark_defined(); 66 | m_pRef = rhs.m_pRef; 67 | } 68 | void set_data(const node& rhs) { 69 | if (rhs.is_defined()) 70 | mark_defined(); 71 | m_pRef->set_data(*rhs.m_pRef); 72 | } 73 | 74 | void set_mark(const Mark& mark) { m_pRef->set_mark(mark); } 75 | 76 | void set_type(NodeType::value type) { 77 | if (type != NodeType::Undefined) 78 | mark_defined(); 79 | m_pRef->set_type(type); 80 | } 81 | void set_null() { 82 | mark_defined(); 83 | m_pRef->set_null(); 84 | } 85 | void set_scalar(const std::string& scalar) { 86 | mark_defined(); 87 | m_pRef->set_scalar(scalar); 88 | } 89 | void set_tag(const std::string& tag) { 90 | mark_defined(); 91 | m_pRef->set_tag(tag); 92 | } 93 | 94 | // style 95 | void set_style(EmitterStyle::value style) { 96 | mark_defined(); 97 | m_pRef->set_style(style); 98 | } 99 | 100 | // size/iterator 101 | std::size_t size() const { return m_pRef->size(); } 102 | 103 | const_node_iterator begin() const { 104 | return static_cast(*m_pRef).begin(); 105 | } 106 | node_iterator begin() { return m_pRef->begin(); } 107 | 108 | const_node_iterator end() const { 109 | return static_cast(*m_pRef).end(); 110 | } 111 | node_iterator end() { return m_pRef->end(); } 112 | 113 | // sequence 114 | void push_back(node& input, shared_memory_holder pMemory) { 115 | m_pRef->push_back(input, pMemory); 116 | input.add_dependency(*this); 117 | m_index = m_amount.fetch_add(1); 118 | } 119 | void insert(node& key, node& value, shared_memory_holder pMemory) { 120 | m_pRef->insert(key, value, pMemory); 121 | key.add_dependency(*this); 122 | value.add_dependency(*this); 123 | } 124 | 125 | // indexing 126 | template 127 | node* get(const Key& key, shared_memory_holder pMemory) const { 128 | // NOTE: this returns a non-const node so that the top-level Node can wrap 129 | // it, and returns a pointer so that it can be nullptr (if there is no such 130 | // key). 131 | return static_cast(*m_pRef).get(key, pMemory); 132 | } 133 | template 134 | node& get(const Key& key, shared_memory_holder pMemory) { 135 | node& value = m_pRef->get(key, pMemory); 136 | value.add_dependency(*this); 137 | return value; 138 | } 139 | template 140 | bool remove(const Key& key, shared_memory_holder pMemory) { 141 | return m_pRef->remove(key, pMemory); 142 | } 143 | 144 | node* get(node& key, shared_memory_holder pMemory) const { 145 | // NOTE: this returns a non-const node so that the top-level Node can wrap 146 | // it, and returns a pointer so that it can be nullptr (if there is no such 147 | // key). 148 | return static_cast(*m_pRef).get(key, pMemory); 149 | } 150 | node& get(node& key, shared_memory_holder pMemory) { 151 | node& value = m_pRef->get(key, pMemory); 152 | key.add_dependency(*this); 153 | value.add_dependency(*this); 154 | return value; 155 | } 156 | bool remove(node& key, shared_memory_holder pMemory) { 157 | return m_pRef->remove(key, pMemory); 158 | } 159 | 160 | // map 161 | template 162 | void force_insert(const Key& key, const Value& value, 163 | shared_memory_holder pMemory) { 164 | m_pRef->force_insert(key, value, pMemory); 165 | } 166 | 167 | private: 168 | shared_node_ref m_pRef; 169 | using nodes = std::set; 170 | nodes m_dependencies; 171 | size_t m_index; 172 | static std::atomic m_amount; 173 | }; 174 | } // namespace detail 175 | } // namespace YAML 176 | 177 | #endif // NODE_DETAIL_NODE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 178 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/detail/node_data.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_DETAIL_NODE_DATA_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_DETAIL_NODE_DATA_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | 16 | #include "yaml-cpp/dll.h" 17 | #include "yaml-cpp/node/detail/node_iterator.h" 18 | #include "yaml-cpp/node/iterator.h" 19 | #include "yaml-cpp/node/ptr.h" 20 | #include "yaml-cpp/node/type.h" 21 | 22 | namespace YAML { 23 | namespace detail { 24 | class node; 25 | } // namespace detail 26 | } // namespace YAML 27 | 28 | namespace YAML { 29 | namespace detail { 30 | class YAML_CPP_API node_data { 31 | public: 32 | node_data(); 33 | node_data(const node_data&) = delete; 34 | node_data& operator=(const node_data&) = delete; 35 | 36 | void mark_defined(); 37 | void set_mark(const Mark& mark); 38 | void set_type(NodeType::value type); 39 | void set_tag(const std::string& tag); 40 | void set_null(); 41 | void set_scalar(const std::string& scalar); 42 | void set_style(EmitterStyle::value style); 43 | 44 | bool is_defined() const { return m_isDefined; } 45 | const Mark& mark() const { return m_mark; } 46 | NodeType::value type() const { 47 | return m_isDefined ? m_type : NodeType::Undefined; 48 | } 49 | const std::string& scalar() const { return m_scalar; } 50 | const std::string& tag() const { return m_tag; } 51 | EmitterStyle::value style() const { return m_style; } 52 | 53 | // size/iterator 54 | std::size_t size() const; 55 | 56 | const_node_iterator begin() const; 57 | node_iterator begin(); 58 | 59 | const_node_iterator end() const; 60 | node_iterator end(); 61 | 62 | // sequence 63 | void push_back(node& node, const shared_memory_holder& pMemory); 64 | void insert(node& key, node& value, const shared_memory_holder& pMemory); 65 | 66 | // indexing 67 | template 68 | node* get(const Key& key, shared_memory_holder pMemory) const; 69 | template 70 | node& get(const Key& key, shared_memory_holder pMemory); 71 | template 72 | bool remove(const Key& key, shared_memory_holder pMemory); 73 | 74 | node* get(node& key, const shared_memory_holder& pMemory) const; 75 | node& get(node& key, const shared_memory_holder& pMemory); 76 | bool remove(node& key, const shared_memory_holder& pMemory); 77 | 78 | // map 79 | template 80 | void force_insert(const Key& key, const Value& value, 81 | shared_memory_holder pMemory); 82 | 83 | public: 84 | static const std::string& empty_scalar(); 85 | 86 | private: 87 | void compute_seq_size() const; 88 | void compute_map_size() const; 89 | 90 | void reset_sequence(); 91 | void reset_map(); 92 | 93 | void insert_map_pair(node& key, node& value); 94 | void convert_to_map(const shared_memory_holder& pMemory); 95 | void convert_sequence_to_map(const shared_memory_holder& pMemory); 96 | 97 | template 98 | static node& convert_to_node(const T& rhs, shared_memory_holder pMemory); 99 | 100 | private: 101 | bool m_isDefined; 102 | Mark m_mark; 103 | NodeType::value m_type; 104 | std::string m_tag; 105 | EmitterStyle::value m_style; 106 | 107 | // scalar 108 | std::string m_scalar; 109 | 110 | // sequence 111 | using node_seq = std::vector; 112 | node_seq m_sequence; 113 | 114 | mutable std::size_t m_seqSize; 115 | 116 | // map 117 | using node_map = std::vector>; 118 | node_map m_map; 119 | 120 | using kv_pair = std::pair; 121 | using kv_pairs = std::list; 122 | mutable kv_pairs m_undefinedPairs; 123 | }; 124 | } 125 | } 126 | 127 | #endif // VALUE_DETAIL_NODE_DATA_H_62B23520_7C8E_11DE_8A39_0800200C9A66 128 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/detail/node_iterator.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_DETAIL_NODE_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_DETAIL_NODE_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | #include "yaml-cpp/node/ptr.h" 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | namespace YAML { 20 | namespace detail { 21 | struct iterator_type { 22 | enum value { NoneType, Sequence, Map }; 23 | }; 24 | 25 | template 26 | struct node_iterator_value : public std::pair { 27 | using kv = std::pair; 28 | 29 | node_iterator_value() : kv(), pNode(nullptr) {} 30 | explicit node_iterator_value(V& rhs) : kv(), pNode(&rhs) {} 31 | explicit node_iterator_value(V& key, V& value) : kv(&key, &value), pNode(nullptr) {} 32 | 33 | V& operator*() const { return *pNode; } 34 | V& operator->() const { return *pNode; } 35 | 36 | V* pNode; 37 | }; 38 | 39 | using node_seq = std::vector; 40 | using node_map = std::vector>; 41 | 42 | template 43 | struct node_iterator_type { 44 | using seq = node_seq::iterator; 45 | using map = node_map::iterator; 46 | }; 47 | 48 | template 49 | struct node_iterator_type { 50 | using seq = node_seq::const_iterator; 51 | using map = node_map::const_iterator; 52 | }; 53 | 54 | template 55 | class node_iterator_base { 56 | private: 57 | struct enabler {}; 58 | 59 | struct proxy { 60 | explicit proxy(const node_iterator_value& x) : m_ref(x) {} 61 | node_iterator_value* operator->() { return std::addressof(m_ref); } 62 | operator node_iterator_value*() { return std::addressof(m_ref); } 63 | 64 | node_iterator_value m_ref; 65 | }; 66 | 67 | public: 68 | using iterator_category = std::forward_iterator_tag; 69 | using value_type = node_iterator_value; 70 | using difference_type = std::ptrdiff_t; 71 | using pointer = node_iterator_value*; 72 | using reference = node_iterator_value; 73 | using SeqIter = typename node_iterator_type::seq; 74 | using MapIter = typename node_iterator_type::map; 75 | 76 | node_iterator_base() 77 | : m_type(iterator_type::NoneType), m_seqIt(), m_mapIt(), m_mapEnd() {} 78 | explicit node_iterator_base(SeqIter seqIt) 79 | : m_type(iterator_type::Sequence), 80 | m_seqIt(seqIt), 81 | m_mapIt(), 82 | m_mapEnd() {} 83 | explicit node_iterator_base(MapIter mapIt, MapIter mapEnd) 84 | : m_type(iterator_type::Map), 85 | m_seqIt(), 86 | m_mapIt(mapIt), 87 | m_mapEnd(mapEnd) { 88 | m_mapIt = increment_until_defined(m_mapIt); 89 | } 90 | 91 | template 92 | node_iterator_base(const node_iterator_base& rhs, 93 | typename std::enable_if::value, 94 | enabler>::type = enabler()) 95 | : m_type(rhs.m_type), 96 | m_seqIt(rhs.m_seqIt), 97 | m_mapIt(rhs.m_mapIt), 98 | m_mapEnd(rhs.m_mapEnd) {} 99 | 100 | template 101 | friend class node_iterator_base; 102 | 103 | template 104 | bool operator==(const node_iterator_base& rhs) const { 105 | if (m_type != rhs.m_type) 106 | return false; 107 | 108 | switch (m_type) { 109 | case iterator_type::NoneType: 110 | return true; 111 | case iterator_type::Sequence: 112 | return m_seqIt == rhs.m_seqIt; 113 | case iterator_type::Map: 114 | return m_mapIt == rhs.m_mapIt; 115 | } 116 | return true; 117 | } 118 | 119 | template 120 | bool operator!=(const node_iterator_base& rhs) const { 121 | return !(*this == rhs); 122 | } 123 | 124 | node_iterator_base& operator++() { 125 | switch (m_type) { 126 | case iterator_type::NoneType: 127 | break; 128 | case iterator_type::Sequence: 129 | ++m_seqIt; 130 | break; 131 | case iterator_type::Map: 132 | ++m_mapIt; 133 | m_mapIt = increment_until_defined(m_mapIt); 134 | break; 135 | } 136 | return *this; 137 | } 138 | 139 | node_iterator_base operator++(int) { 140 | node_iterator_base iterator_pre(*this); 141 | ++(*this); 142 | return iterator_pre; 143 | } 144 | 145 | value_type operator*() const { 146 | switch (m_type) { 147 | case iterator_type::NoneType: 148 | return value_type(); 149 | case iterator_type::Sequence: 150 | return value_type(**m_seqIt); 151 | case iterator_type::Map: 152 | return value_type(*m_mapIt->first, *m_mapIt->second); 153 | } 154 | return value_type(); 155 | } 156 | 157 | proxy operator->() const { return proxy(**this); } 158 | 159 | MapIter increment_until_defined(MapIter it) { 160 | while (it != m_mapEnd && !is_defined(it)) 161 | ++it; 162 | return it; 163 | } 164 | 165 | bool is_defined(MapIter it) const { 166 | return it->first->is_defined() && it->second->is_defined(); 167 | } 168 | 169 | private: 170 | typename iterator_type::value m_type; 171 | 172 | SeqIter m_seqIt; 173 | MapIter m_mapIt, m_mapEnd; 174 | }; 175 | 176 | using node_iterator = node_iterator_base; 177 | using const_node_iterator = node_iterator_base; 178 | } 179 | } 180 | 181 | #endif // VALUE_DETAIL_NODE_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 182 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/detail/node_ref.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_DETAIL_NODE_REF_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_DETAIL_NODE_REF_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | #include "yaml-cpp/node/type.h" 12 | #include "yaml-cpp/node/ptr.h" 13 | #include "yaml-cpp/node/detail/node_data.h" 14 | 15 | namespace YAML { 16 | namespace detail { 17 | class node_ref { 18 | public: 19 | node_ref() : m_pData(new node_data) {} 20 | node_ref(const node_ref&) = delete; 21 | node_ref& operator=(const node_ref&) = delete; 22 | 23 | bool is_defined() const { return m_pData->is_defined(); } 24 | const Mark& mark() const { return m_pData->mark(); } 25 | NodeType::value type() const { return m_pData->type(); } 26 | const std::string& scalar() const { return m_pData->scalar(); } 27 | const std::string& tag() const { return m_pData->tag(); } 28 | EmitterStyle::value style() const { return m_pData->style(); } 29 | 30 | void mark_defined() { m_pData->mark_defined(); } 31 | void set_data(const node_ref& rhs) { m_pData = rhs.m_pData; } 32 | 33 | void set_mark(const Mark& mark) { m_pData->set_mark(mark); } 34 | void set_type(NodeType::value type) { m_pData->set_type(type); } 35 | void set_tag(const std::string& tag) { m_pData->set_tag(tag); } 36 | void set_null() { m_pData->set_null(); } 37 | void set_scalar(const std::string& scalar) { m_pData->set_scalar(scalar); } 38 | void set_style(EmitterStyle::value style) { m_pData->set_style(style); } 39 | 40 | // size/iterator 41 | std::size_t size() const { return m_pData->size(); } 42 | 43 | const_node_iterator begin() const { 44 | return static_cast(*m_pData).begin(); 45 | } 46 | node_iterator begin() { return m_pData->begin(); } 47 | 48 | const_node_iterator end() const { 49 | return static_cast(*m_pData).end(); 50 | } 51 | node_iterator end() { return m_pData->end(); } 52 | 53 | // sequence 54 | void push_back(node& node, shared_memory_holder pMemory) { 55 | m_pData->push_back(node, pMemory); 56 | } 57 | void insert(node& key, node& value, shared_memory_holder pMemory) { 58 | m_pData->insert(key, value, pMemory); 59 | } 60 | 61 | // indexing 62 | template 63 | node* get(const Key& key, shared_memory_holder pMemory) const { 64 | return static_cast(*m_pData).get(key, pMemory); 65 | } 66 | template 67 | node& get(const Key& key, shared_memory_holder pMemory) { 68 | return m_pData->get(key, pMemory); 69 | } 70 | template 71 | bool remove(const Key& key, shared_memory_holder pMemory) { 72 | return m_pData->remove(key, pMemory); 73 | } 74 | 75 | node* get(node& key, shared_memory_holder pMemory) const { 76 | return static_cast(*m_pData).get(key, pMemory); 77 | } 78 | node& get(node& key, shared_memory_holder pMemory) { 79 | return m_pData->get(key, pMemory); 80 | } 81 | bool remove(node& key, shared_memory_holder pMemory) { 82 | return m_pData->remove(key, pMemory); 83 | } 84 | 85 | // map 86 | template 87 | void force_insert(const Key& key, const Value& value, 88 | shared_memory_holder pMemory) { 89 | m_pData->force_insert(key, value, pMemory); 90 | } 91 | 92 | private: 93 | shared_node_data m_pData; 94 | }; 95 | } 96 | } 97 | 98 | #endif // VALUE_DETAIL_NODE_REF_H_62B23520_7C8E_11DE_8A39_0800200C9A66 99 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/emit.h: -------------------------------------------------------------------------------- 1 | #ifndef NODE_EMIT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define NODE_EMIT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | 13 | #include "yaml-cpp/dll.h" 14 | 15 | namespace YAML { 16 | class Emitter; 17 | class Node; 18 | 19 | /** 20 | * Emits the node to the given {@link Emitter}. If there is an error in writing, 21 | * {@link Emitter#good} will return false. 22 | */ 23 | YAML_CPP_API Emitter& operator<<(Emitter& out, const Node& node); 24 | 25 | /** Emits the node to the given output stream. */ 26 | YAML_CPP_API std::ostream& operator<<(std::ostream& out, const Node& node); 27 | 28 | /** Converts the node to a YAML string. */ 29 | YAML_CPP_API std::string Dump(const Node& node); 30 | } // namespace YAML 31 | 32 | #endif // NODE_EMIT_H_62B23520_7C8E_11DE_8A39_0800200C9A66 33 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/impl.h: -------------------------------------------------------------------------------- 1 | #ifndef NODE_IMPL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define NODE_IMPL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/exceptions.h" 11 | #include "yaml-cpp/node/detail/memory.h" 12 | #include "yaml-cpp/node/detail/node.h" 13 | #include "yaml-cpp/node/iterator.h" 14 | #include "yaml-cpp/node/node.h" 15 | #include 16 | #include 17 | 18 | namespace YAML { 19 | inline Node::Node() 20 | : m_isValid(true), m_invalidKey{}, m_pMemory(nullptr), m_pNode(nullptr) {} 21 | 22 | inline Node::Node(NodeType::value type) 23 | : m_isValid(true), 24 | m_invalidKey{}, 25 | m_pMemory(new detail::memory_holder), 26 | m_pNode(&m_pMemory->create_node()) { 27 | m_pNode->set_type(type); 28 | } 29 | 30 | template 31 | inline Node::Node(const T& rhs) 32 | : m_isValid(true), 33 | m_invalidKey{}, 34 | m_pMemory(new detail::memory_holder), 35 | m_pNode(&m_pMemory->create_node()) { 36 | Assign(rhs); 37 | } 38 | 39 | inline Node::Node(const detail::iterator_value& rhs) 40 | : m_isValid(rhs.m_isValid), 41 | m_invalidKey(rhs.m_invalidKey), 42 | m_pMemory(rhs.m_pMemory), 43 | m_pNode(rhs.m_pNode) {} 44 | 45 | inline Node::Node(const Node& rhs) = default; 46 | 47 | inline Node::Node(Zombie) 48 | : m_isValid(false), m_invalidKey{}, m_pMemory{}, m_pNode(nullptr) {} 49 | 50 | inline Node::Node(Zombie, const std::string& key) 51 | : m_isValid(false), m_invalidKey(key), m_pMemory{}, m_pNode(nullptr) {} 52 | 53 | inline Node::Node(detail::node& node, detail::shared_memory_holder pMemory) 54 | : m_isValid(true), m_invalidKey{}, m_pMemory(pMemory), m_pNode(&node) {} 55 | 56 | inline Node::~Node() = default; 57 | 58 | inline void Node::EnsureNodeExists() const { 59 | if (!m_isValid) 60 | throw InvalidNode(m_invalidKey); 61 | if (!m_pNode) { 62 | m_pMemory.reset(new detail::memory_holder); 63 | m_pNode = &m_pMemory->create_node(); 64 | m_pNode->set_null(); 65 | } 66 | } 67 | 68 | inline bool Node::IsDefined() const { 69 | if (!m_isValid) { 70 | return false; 71 | } 72 | return m_pNode ? m_pNode->is_defined() : true; 73 | } 74 | 75 | inline Mark Node::Mark() const { 76 | if (!m_isValid) { 77 | throw InvalidNode(m_invalidKey); 78 | } 79 | return m_pNode ? m_pNode->mark() : Mark::null_mark(); 80 | } 81 | 82 | inline NodeType::value Node::Type() const { 83 | if (!m_isValid) 84 | throw InvalidNode(m_invalidKey); 85 | return m_pNode ? m_pNode->type() : NodeType::Null; 86 | } 87 | 88 | // access 89 | 90 | // template helpers 91 | template 92 | struct as_if { 93 | explicit as_if(const Node& node_) : node(node_) {} 94 | const Node& node; 95 | 96 | T operator()(const S& fallback) const { 97 | if (!node.m_pNode) 98 | return fallback; 99 | 100 | T t; 101 | if (convert::decode(node, t)) 102 | return t; 103 | return fallback; 104 | } 105 | }; 106 | 107 | template 108 | struct as_if { 109 | explicit as_if(const Node& node_) : node(node_) {} 110 | const Node& node; 111 | 112 | std::string operator()(const S& fallback) const { 113 | if (node.Type() == NodeType::Null) 114 | return "null"; 115 | if (node.Type() != NodeType::Scalar) 116 | return fallback; 117 | return node.Scalar(); 118 | } 119 | }; 120 | 121 | template 122 | struct as_if { 123 | explicit as_if(const Node& node_) : node(node_) {} 124 | const Node& node; 125 | 126 | T operator()() const { 127 | if (!node.m_pNode) 128 | throw TypedBadConversion(node.Mark()); 129 | 130 | T t; 131 | if (convert::decode(node, t)) 132 | return t; 133 | throw TypedBadConversion(node.Mark()); 134 | } 135 | }; 136 | 137 | template <> 138 | struct as_if { 139 | explicit as_if(const Node& node_) : node(node_) {} 140 | const Node& node; 141 | 142 | std::string operator()() const { 143 | if (node.Type() == NodeType::Null) 144 | return "null"; 145 | if (node.Type() != NodeType::Scalar) 146 | throw TypedBadConversion(node.Mark()); 147 | return node.Scalar(); 148 | } 149 | }; 150 | 151 | // access functions 152 | template 153 | inline T Node::as() const { 154 | if (!m_isValid) 155 | throw InvalidNode(m_invalidKey); 156 | return as_if(*this)(); 157 | } 158 | 159 | template 160 | inline T Node::as(const S& fallback) const { 161 | if (!m_isValid) 162 | return fallback; 163 | return as_if(*this)(fallback); 164 | } 165 | 166 | inline const std::string& Node::Scalar() const { 167 | if (!m_isValid) 168 | throw InvalidNode(m_invalidKey); 169 | return m_pNode ? m_pNode->scalar() : detail::node_data::empty_scalar(); 170 | } 171 | 172 | inline const std::string& Node::Tag() const { 173 | if (!m_isValid) 174 | throw InvalidNode(m_invalidKey); 175 | return m_pNode ? m_pNode->tag() : detail::node_data::empty_scalar(); 176 | } 177 | 178 | inline void Node::SetTag(const std::string& tag) { 179 | EnsureNodeExists(); 180 | m_pNode->set_tag(tag); 181 | } 182 | 183 | inline EmitterStyle::value Node::Style() const { 184 | if (!m_isValid) 185 | throw InvalidNode(m_invalidKey); 186 | return m_pNode ? m_pNode->style() : EmitterStyle::Default; 187 | } 188 | 189 | inline void Node::SetStyle(EmitterStyle::value style) { 190 | EnsureNodeExists(); 191 | m_pNode->set_style(style); 192 | } 193 | 194 | // assignment 195 | inline bool Node::is(const Node& rhs) const { 196 | if (!m_isValid || !rhs.m_isValid) 197 | throw InvalidNode(m_invalidKey); 198 | if (!m_pNode || !rhs.m_pNode) 199 | return false; 200 | return m_pNode->is(*rhs.m_pNode); 201 | } 202 | 203 | template 204 | inline Node& Node::operator=(const T& rhs) { 205 | Assign(rhs); 206 | return *this; 207 | } 208 | 209 | inline Node& Node::operator=(const Node& rhs) { 210 | if (is(rhs)) 211 | return *this; 212 | AssignNode(rhs); 213 | return *this; 214 | } 215 | 216 | inline void Node::reset(const YAML::Node& rhs) { 217 | if (!m_isValid || !rhs.m_isValid) 218 | throw InvalidNode(m_invalidKey); 219 | m_pMemory = rhs.m_pMemory; 220 | m_pNode = rhs.m_pNode; 221 | } 222 | 223 | template 224 | inline void Node::Assign(const T& rhs) { 225 | if (!m_isValid) 226 | throw InvalidNode(m_invalidKey); 227 | AssignData(convert::encode(rhs)); 228 | } 229 | 230 | template <> 231 | inline void Node::Assign(const std::string& rhs) { 232 | EnsureNodeExists(); 233 | m_pNode->set_scalar(rhs); 234 | } 235 | 236 | inline void Node::Assign(const char* rhs) { 237 | EnsureNodeExists(); 238 | m_pNode->set_scalar(rhs); 239 | } 240 | 241 | inline void Node::Assign(char* rhs) { 242 | EnsureNodeExists(); 243 | m_pNode->set_scalar(rhs); 244 | } 245 | 246 | inline void Node::AssignData(const Node& rhs) { 247 | EnsureNodeExists(); 248 | rhs.EnsureNodeExists(); 249 | 250 | m_pNode->set_data(*rhs.m_pNode); 251 | m_pMemory->merge(*rhs.m_pMemory); 252 | } 253 | 254 | inline void Node::AssignNode(const Node& rhs) { 255 | if (!m_isValid) 256 | throw InvalidNode(m_invalidKey); 257 | rhs.EnsureNodeExists(); 258 | 259 | if (!m_pNode) { 260 | m_pNode = rhs.m_pNode; 261 | m_pMemory = rhs.m_pMemory; 262 | return; 263 | } 264 | 265 | m_pNode->set_ref(*rhs.m_pNode); 266 | m_pMemory->merge(*rhs.m_pMemory); 267 | m_pNode = rhs.m_pNode; 268 | } 269 | 270 | // size/iterator 271 | inline std::size_t Node::size() const { 272 | if (!m_isValid) 273 | throw InvalidNode(m_invalidKey); 274 | return m_pNode ? m_pNode->size() : 0; 275 | } 276 | 277 | inline const_iterator Node::begin() const { 278 | if (!m_isValid) 279 | return const_iterator(); 280 | return m_pNode ? const_iterator(m_pNode->begin(), m_pMemory) 281 | : const_iterator(); 282 | } 283 | 284 | inline iterator Node::begin() { 285 | if (!m_isValid) 286 | return iterator(); 287 | return m_pNode ? iterator(m_pNode->begin(), m_pMemory) : iterator(); 288 | } 289 | 290 | inline const_iterator Node::end() const { 291 | if (!m_isValid) 292 | return const_iterator(); 293 | return m_pNode ? const_iterator(m_pNode->end(), m_pMemory) : const_iterator(); 294 | } 295 | 296 | inline iterator Node::end() { 297 | if (!m_isValid) 298 | return iterator(); 299 | return m_pNode ? iterator(m_pNode->end(), m_pMemory) : iterator(); 300 | } 301 | 302 | // sequence 303 | template 304 | inline void Node::push_back(const T& rhs) { 305 | if (!m_isValid) 306 | throw InvalidNode(m_invalidKey); 307 | push_back(Node(rhs)); 308 | } 309 | 310 | inline void Node::push_back(const Node& rhs) { 311 | EnsureNodeExists(); 312 | rhs.EnsureNodeExists(); 313 | 314 | m_pNode->push_back(*rhs.m_pNode, m_pMemory); 315 | m_pMemory->merge(*rhs.m_pMemory); 316 | } 317 | 318 | template 319 | std::string key_to_string(const Key& key) { 320 | return streamable_to_string::value>().impl(key); 321 | } 322 | 323 | // indexing 324 | template 325 | inline const Node Node::operator[](const Key& key) const { 326 | EnsureNodeExists(); 327 | detail::node* value = 328 | static_cast(*m_pNode).get(key, m_pMemory); 329 | if (!value) { 330 | return Node(ZombieNode, key_to_string(key)); 331 | } 332 | return Node(*value, m_pMemory); 333 | } 334 | 335 | template 336 | inline Node Node::operator[](const Key& key) { 337 | EnsureNodeExists(); 338 | detail::node& value = m_pNode->get(key, m_pMemory); 339 | return Node(value, m_pMemory); 340 | } 341 | 342 | template 343 | inline bool Node::remove(const Key& key) { 344 | EnsureNodeExists(); 345 | return m_pNode->remove(key, m_pMemory); 346 | } 347 | 348 | inline const Node Node::operator[](const Node& key) const { 349 | EnsureNodeExists(); 350 | key.EnsureNodeExists(); 351 | m_pMemory->merge(*key.m_pMemory); 352 | detail::node* value = 353 | static_cast(*m_pNode).get(*key.m_pNode, m_pMemory); 354 | if (!value) { 355 | return Node(ZombieNode, key_to_string(key)); 356 | } 357 | return Node(*value, m_pMemory); 358 | } 359 | 360 | inline Node Node::operator[](const Node& key) { 361 | EnsureNodeExists(); 362 | key.EnsureNodeExists(); 363 | m_pMemory->merge(*key.m_pMemory); 364 | detail::node& value = m_pNode->get(*key.m_pNode, m_pMemory); 365 | return Node(value, m_pMemory); 366 | } 367 | 368 | inline bool Node::remove(const Node& key) { 369 | EnsureNodeExists(); 370 | key.EnsureNodeExists(); 371 | return m_pNode->remove(*key.m_pNode, m_pMemory); 372 | } 373 | 374 | // map 375 | template 376 | inline void Node::force_insert(const Key& key, const Value& value) { 377 | EnsureNodeExists(); 378 | m_pNode->force_insert(key, value, m_pMemory); 379 | } 380 | 381 | // free functions 382 | inline bool operator==(const Node& lhs, const Node& rhs) { return lhs.is(rhs); } 383 | } // namespace YAML 384 | 385 | #endif // NODE_IMPL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 386 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/iterator.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | #include "yaml-cpp/node/node.h" 12 | #include "yaml-cpp/node/detail/iterator_fwd.h" 13 | #include "yaml-cpp/node/detail/iterator.h" 14 | #include 15 | #include 16 | #include 17 | 18 | namespace YAML { 19 | namespace detail { 20 | struct iterator_value : public Node, std::pair { 21 | iterator_value() = default; 22 | explicit iterator_value(const Node& rhs) 23 | : Node(rhs), 24 | std::pair(Node(Node::ZombieNode), Node(Node::ZombieNode)) {} 25 | explicit iterator_value(const Node& key, const Node& value) 26 | : Node(Node::ZombieNode), std::pair(key, value) {} 27 | }; 28 | } 29 | } 30 | 31 | #endif // VALUE_ITERATOR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 32 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/node.h: -------------------------------------------------------------------------------- 1 | #ifndef NODE_NODE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define NODE_NODE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | 13 | #include "yaml-cpp/dll.h" 14 | #include "yaml-cpp/emitterstyle.h" 15 | #include "yaml-cpp/mark.h" 16 | #include "yaml-cpp/node/detail/iterator_fwd.h" 17 | #include "yaml-cpp/node/ptr.h" 18 | #include "yaml-cpp/node/type.h" 19 | 20 | namespace YAML { 21 | namespace detail { 22 | class node; 23 | class node_data; 24 | struct iterator_value; 25 | } // namespace detail 26 | } // namespace YAML 27 | 28 | namespace YAML { 29 | class YAML_CPP_API Node { 30 | public: 31 | friend class NodeBuilder; 32 | friend class NodeEvents; 33 | friend struct detail::iterator_value; 34 | friend class detail::node; 35 | friend class detail::node_data; 36 | template 37 | friend class detail::iterator_base; 38 | template 39 | friend struct as_if; 40 | 41 | using iterator = YAML::iterator; 42 | using const_iterator = YAML::const_iterator; 43 | 44 | Node(); 45 | explicit Node(NodeType::value type); 46 | template 47 | explicit Node(const T& rhs); 48 | explicit Node(const detail::iterator_value& rhs); 49 | Node(const Node& rhs); 50 | ~Node(); 51 | 52 | YAML::Mark Mark() const; 53 | NodeType::value Type() const; 54 | bool IsDefined() const; 55 | bool IsNull() const { return Type() == NodeType::Null; } 56 | bool IsScalar() const { return Type() == NodeType::Scalar; } 57 | bool IsSequence() const { return Type() == NodeType::Sequence; } 58 | bool IsMap() const { return Type() == NodeType::Map; } 59 | 60 | // bool conversions 61 | explicit operator bool() const { return IsDefined(); } 62 | bool operator!() const { return !IsDefined(); } 63 | 64 | // access 65 | template 66 | T as() const; 67 | template 68 | T as(const S& fallback) const; 69 | const std::string& Scalar() const; 70 | 71 | const std::string& Tag() const; 72 | void SetTag(const std::string& tag); 73 | 74 | // style 75 | // WARNING: This API might change in future releases. 76 | EmitterStyle::value Style() const; 77 | void SetStyle(EmitterStyle::value style); 78 | 79 | // assignment 80 | bool is(const Node& rhs) const; 81 | template 82 | Node& operator=(const T& rhs); 83 | Node& operator=(const Node& rhs); 84 | void reset(const Node& rhs = Node()); 85 | 86 | // size/iterator 87 | std::size_t size() const; 88 | 89 | const_iterator begin() const; 90 | iterator begin(); 91 | 92 | const_iterator end() const; 93 | iterator end(); 94 | 95 | // sequence 96 | template 97 | void push_back(const T& rhs); 98 | void push_back(const Node& rhs); 99 | 100 | // indexing 101 | template 102 | const Node operator[](const Key& key) const; 103 | template 104 | Node operator[](const Key& key); 105 | template 106 | bool remove(const Key& key); 107 | 108 | const Node operator[](const Node& key) const; 109 | Node operator[](const Node& key); 110 | bool remove(const Node& key); 111 | 112 | // map 113 | template 114 | void force_insert(const Key& key, const Value& value); 115 | 116 | private: 117 | enum Zombie { ZombieNode }; 118 | explicit Node(Zombie); 119 | explicit Node(Zombie, const std::string&); 120 | explicit Node(detail::node& node, detail::shared_memory_holder pMemory); 121 | 122 | void EnsureNodeExists() const; 123 | 124 | template 125 | void Assign(const T& rhs); 126 | void Assign(const char* rhs); 127 | void Assign(char* rhs); 128 | 129 | void AssignData(const Node& rhs); 130 | void AssignNode(const Node& rhs); 131 | 132 | private: 133 | bool m_isValid; 134 | // String representation of invalid key, if the node is invalid. 135 | std::string m_invalidKey; 136 | mutable detail::shared_memory_holder m_pMemory; 137 | mutable detail::node* m_pNode; 138 | }; 139 | 140 | YAML_CPP_API bool operator==(const Node& lhs, const Node& rhs); 141 | 142 | YAML_CPP_API Node Clone(const Node& node); 143 | 144 | template 145 | struct convert; 146 | } 147 | 148 | #endif // NODE_NODE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 149 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/parse.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_PARSE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_PARSE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | #include 13 | 14 | #include "yaml-cpp/dll.h" 15 | 16 | namespace YAML { 17 | class Node; 18 | 19 | /** 20 | * Loads the input string as a single YAML document. 21 | * 22 | * @throws {@link ParserException} if it is malformed. 23 | */ 24 | YAML_CPP_API Node Load(const std::string& input); 25 | 26 | /** 27 | * Loads the input string as a single YAML document. 28 | * 29 | * @throws {@link ParserException} if it is malformed. 30 | */ 31 | YAML_CPP_API Node Load(const char* input); 32 | 33 | /** 34 | * Loads the input stream as a single YAML document. 35 | * 36 | * @throws {@link ParserException} if it is malformed. 37 | */ 38 | YAML_CPP_API Node Load(std::istream& input); 39 | 40 | /** 41 | * Loads the input file as a single YAML document. 42 | * 43 | * @throws {@link ParserException} if it is malformed. 44 | * @throws {@link BadFile} if the file cannot be loaded. 45 | */ 46 | YAML_CPP_API Node LoadFile(const std::string& filename); 47 | 48 | /** 49 | * Loads the input string as a list of YAML documents. 50 | * 51 | * @throws {@link ParserException} if it is malformed. 52 | */ 53 | YAML_CPP_API std::vector LoadAll(const std::string& input); 54 | 55 | /** 56 | * Loads the input string as a list of YAML documents. 57 | * 58 | * @throws {@link ParserException} if it is malformed. 59 | */ 60 | YAML_CPP_API std::vector LoadAll(const char* input); 61 | 62 | /** 63 | * Loads the input stream as a list of YAML documents. 64 | * 65 | * @throws {@link ParserException} if it is malformed. 66 | */ 67 | YAML_CPP_API std::vector LoadAll(std::istream& input); 68 | 69 | /** 70 | * Loads the input file as a list of YAML documents. 71 | * 72 | * @throws {@link ParserException} if it is malformed. 73 | * @throws {@link BadFile} if the file cannot be loaded. 74 | */ 75 | YAML_CPP_API std::vector LoadAllFromFile(const std::string& filename); 76 | } // namespace YAML 77 | 78 | #endif // VALUE_PARSE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 79 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/ptr.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_PTR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_PTR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | #include 12 | 13 | namespace YAML { 14 | namespace detail { 15 | class node; 16 | class node_ref; 17 | class node_data; 18 | class memory; 19 | class memory_holder; 20 | 21 | using shared_node = std::shared_ptr; 22 | using shared_node_ref = std::shared_ptr; 23 | using shared_node_data = std::shared_ptr; 24 | using shared_memory_holder = std::shared_ptr; 25 | using shared_memory = std::shared_ptr; 26 | } 27 | } 28 | 29 | #endif // VALUE_PTR_H_62B23520_7C8E_11DE_8A39_0800200C9A66 30 | -------------------------------------------------------------------------------- /include/yaml-cpp/node/type.h: -------------------------------------------------------------------------------- 1 | #ifndef VALUE_TYPE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define VALUE_TYPE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | namespace YAML { 11 | struct NodeType { 12 | enum value { Undefined, Null, Scalar, Sequence, Map }; 13 | }; 14 | } 15 | 16 | #endif // VALUE_TYPE_H_62B23520_7C8E_11DE_8A39_0800200C9A66 17 | -------------------------------------------------------------------------------- /include/yaml-cpp/noexcept.h: -------------------------------------------------------------------------------- 1 | #ifndef NOEXCEPT_H_768872DA_476C_11EA_88B8_90B11C0C0FF8 2 | #define NOEXCEPT_H_768872DA_476C_11EA_88B8_90B11C0C0FF8 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | // This is here for compatibility with older versions of Visual Studio 11 | // which don't support noexcept. 12 | #if defined(_MSC_VER) && _MSC_VER < 1900 13 | #define YAML_CPP_NOEXCEPT _NOEXCEPT 14 | #else 15 | #define YAML_CPP_NOEXCEPT noexcept 16 | #endif 17 | 18 | #endif 19 | -------------------------------------------------------------------------------- /include/yaml-cpp/null.h: -------------------------------------------------------------------------------- 1 | #ifndef NULL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define NULL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/dll.h" 11 | #include 12 | 13 | namespace YAML { 14 | class Node; 15 | 16 | struct YAML_CPP_API _Null {}; 17 | inline bool operator==(const _Null&, const _Null&) { return true; } 18 | inline bool operator!=(const _Null&, const _Null&) { return false; } 19 | 20 | YAML_CPP_API bool IsNull(const Node& node); // old API only 21 | YAML_CPP_API bool IsNullString(const std::string& str); 22 | 23 | extern YAML_CPP_API _Null Null; 24 | } 25 | 26 | #endif // NULL_H_62B23520_7C8E_11DE_8A39_0800200C9A66 27 | -------------------------------------------------------------------------------- /include/yaml-cpp/ostream_wrapper.h: -------------------------------------------------------------------------------- 1 | #ifndef OSTREAM_WRAPPER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define OSTREAM_WRAPPER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | 13 | #include "yaml-cpp/dll.h" 14 | 15 | namespace YAML { 16 | class YAML_CPP_API ostream_wrapper { 17 | public: 18 | ostream_wrapper(); 19 | explicit ostream_wrapper(std::ostream& stream); 20 | ostream_wrapper(const ostream_wrapper&) = delete; 21 | ostream_wrapper(ostream_wrapper&&) = delete; 22 | ostream_wrapper& operator=(const ostream_wrapper&) = delete; 23 | ostream_wrapper& operator=(ostream_wrapper&&) = delete; 24 | ~ostream_wrapper(); 25 | 26 | void write(const std::string& str); 27 | void write(const char* str, std::size_t size); 28 | 29 | void set_comment() { m_comment = true; } 30 | 31 | const char* str() const { 32 | if (m_pStream) { 33 | return nullptr; 34 | } else { 35 | m_buffer[m_pos] = '\0'; 36 | return &m_buffer[0]; 37 | } 38 | } 39 | 40 | std::size_t row() const { return m_row; } 41 | std::size_t col() const { return m_col; } 42 | std::size_t pos() const { return m_pos; } 43 | bool comment() const { return m_comment; } 44 | 45 | private: 46 | void update_pos(char ch); 47 | 48 | private: 49 | mutable std::vector m_buffer; 50 | std::ostream* const m_pStream; 51 | 52 | std::size_t m_pos; 53 | std::size_t m_row, m_col; 54 | bool m_comment; 55 | }; 56 | 57 | template 58 | inline ostream_wrapper& operator<<(ostream_wrapper& stream, 59 | const char (&str)[N]) { 60 | stream.write(str, N - 1); 61 | return stream; 62 | } 63 | 64 | inline ostream_wrapper& operator<<(ostream_wrapper& stream, 65 | const std::string& str) { 66 | stream.write(str); 67 | return stream; 68 | } 69 | 70 | inline ostream_wrapper& operator<<(ostream_wrapper& stream, char ch) { 71 | stream.write(&ch, 1); 72 | return stream; 73 | } 74 | } // namespace YAML 75 | 76 | #endif // OSTREAM_WRAPPER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 77 | -------------------------------------------------------------------------------- /include/yaml-cpp/parser.h: -------------------------------------------------------------------------------- 1 | #ifndef PARSER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define PARSER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | 13 | #include "yaml-cpp/dll.h" 14 | 15 | namespace YAML { 16 | class EventHandler; 17 | class Node; 18 | class Scanner; 19 | struct Directives; 20 | struct Token; 21 | 22 | /** 23 | * A parser turns a stream of bytes into one stream of "events" per YAML 24 | * document in the input stream. 25 | */ 26 | class YAML_CPP_API Parser { 27 | public: 28 | /** Constructs an empty parser (with no input. */ 29 | Parser(); 30 | 31 | Parser(const Parser&) = delete; 32 | Parser(Parser&&) = delete; 33 | Parser& operator=(const Parser&) = delete; 34 | Parser& operator=(Parser&&) = delete; 35 | 36 | /** 37 | * Constructs a parser from the given input stream. The input stream must 38 | * live as long as the parser. 39 | */ 40 | explicit Parser(std::istream& in); 41 | 42 | ~Parser(); 43 | 44 | /** Evaluates to true if the parser has some valid input to be read. */ 45 | explicit operator bool() const; 46 | 47 | /** 48 | * Resets the parser with the given input stream. Any existing state is 49 | * erased. 50 | */ 51 | void Load(std::istream& in); 52 | 53 | /** 54 | * Handles the next document by calling events on the {@code eventHandler}. 55 | * 56 | * @throw a ParserException on error. 57 | * @return false if there are no more documents 58 | */ 59 | bool HandleNextDocument(EventHandler& eventHandler); 60 | 61 | void PrintTokens(std::ostream& out); 62 | 63 | private: 64 | /** 65 | * Reads any directives that are next in the queue, setting the internal 66 | * {@code m_pDirectives} state. 67 | */ 68 | void ParseDirectives(); 69 | 70 | void HandleDirective(const Token& token); 71 | 72 | /** 73 | * Handles a "YAML" directive, which should be of the form 'major.minor' (like 74 | * a version number). 75 | */ 76 | void HandleYamlDirective(const Token& token); 77 | 78 | /** 79 | * Handles a "TAG" directive, which should be of the form 'handle prefix', 80 | * where 'handle' is converted to 'prefix' in the file. 81 | */ 82 | void HandleTagDirective(const Token& token); 83 | 84 | private: 85 | std::unique_ptr m_pScanner; 86 | std::unique_ptr m_pDirectives; 87 | }; 88 | } // namespace YAML 89 | 90 | #endif // PARSER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 91 | -------------------------------------------------------------------------------- /include/yaml-cpp/stlemitter.h: -------------------------------------------------------------------------------- 1 | #ifndef STLEMITTER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define STLEMITTER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | 15 | namespace YAML { 16 | template 17 | inline Emitter& EmitSeq(Emitter& emitter, const Seq& seq) { 18 | emitter << BeginSeq; 19 | for (const auto& v : seq) 20 | emitter << v; 21 | emitter << EndSeq; 22 | return emitter; 23 | } 24 | 25 | template 26 | inline Emitter& operator<<(Emitter& emitter, const std::vector& v) { 27 | return EmitSeq(emitter, v); 28 | } 29 | 30 | template 31 | inline Emitter& operator<<(Emitter& emitter, const std::list& v) { 32 | return EmitSeq(emitter, v); 33 | } 34 | 35 | template 36 | inline Emitter& operator<<(Emitter& emitter, const std::set& v) { 37 | return EmitSeq(emitter, v); 38 | } 39 | 40 | template 41 | inline Emitter& operator<<(Emitter& emitter, const std::map& m) { 42 | emitter << BeginMap; 43 | for (const auto& v : m) 44 | emitter << Key << v.first << Value << v.second; 45 | emitter << EndMap; 46 | return emitter; 47 | } 48 | } 49 | 50 | #endif // STLEMITTER_H_62B23520_7C8E_11DE_8A39_0800200C9A66 51 | -------------------------------------------------------------------------------- /include/yaml-cpp/traits.h: -------------------------------------------------------------------------------- 1 | #ifndef TRAITS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define TRAITS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | 15 | namespace YAML { 16 | template 17 | struct is_numeric { 18 | enum { value = false }; 19 | }; 20 | 21 | template <> 22 | struct is_numeric { 23 | enum { value = true }; 24 | }; 25 | template <> 26 | struct is_numeric { 27 | enum { value = true }; 28 | }; 29 | template <> 30 | struct is_numeric { 31 | enum { value = true }; 32 | }; 33 | template <> 34 | struct is_numeric { 35 | enum { value = true }; 36 | }; 37 | template <> 38 | struct is_numeric { 39 | enum { value = true }; 40 | }; 41 | template <> 42 | struct is_numeric { 43 | enum { value = true }; 44 | }; 45 | template <> 46 | struct is_numeric { 47 | enum { value = true }; 48 | }; 49 | template <> 50 | struct is_numeric { 51 | enum { value = true }; 52 | }; 53 | #if defined(_MSC_VER) && (_MSC_VER < 1310) 54 | template <> 55 | struct is_numeric<__int64> { 56 | enum { value = true }; 57 | }; 58 | template <> 59 | struct is_numeric { 60 | enum { value = true }; 61 | }; 62 | #else 63 | template <> 64 | struct is_numeric { 65 | enum { value = true }; 66 | }; 67 | template <> 68 | struct is_numeric { 69 | enum { value = true }; 70 | }; 71 | #endif 72 | template <> 73 | struct is_numeric { 74 | enum { value = true }; 75 | }; 76 | template <> 77 | struct is_numeric { 78 | enum { value = true }; 79 | }; 80 | template <> 81 | struct is_numeric { 82 | enum { value = true }; 83 | }; 84 | 85 | template 86 | struct enable_if_c { 87 | using type = T; 88 | }; 89 | 90 | template 91 | struct enable_if_c {}; 92 | 93 | template 94 | struct enable_if : public enable_if_c {}; 95 | 96 | template 97 | struct disable_if_c { 98 | using type = T; 99 | }; 100 | 101 | template 102 | struct disable_if_c {}; 103 | 104 | template 105 | struct disable_if : public disable_if_c {}; 106 | } 107 | 108 | template 109 | struct is_streamable { 110 | template 111 | static auto test(int) 112 | -> decltype(std::declval() << std::declval(), std::true_type()); 113 | 114 | template 115 | static auto test(...) -> std::false_type; 116 | 117 | static const bool value = decltype(test(0))::value; 118 | }; 119 | 120 | template 121 | struct streamable_to_string { 122 | static std::string impl(const Key& key) { 123 | std::stringstream ss; 124 | ss << key; 125 | return ss.str(); 126 | } 127 | }; 128 | 129 | template 130 | struct streamable_to_string { 131 | static std::string impl(const Key&) { 132 | return ""; 133 | } 134 | }; 135 | #endif // TRAITS_H_62B23520_7C8E_11DE_8A39_0800200C9A66 136 | -------------------------------------------------------------------------------- /include/yaml-cpp/yaml.h: -------------------------------------------------------------------------------- 1 | #ifndef YAML_H_62B23520_7C8E_11DE_8A39_0800200C9A66 2 | #define YAML_H_62B23520_7C8E_11DE_8A39_0800200C9A66 3 | 4 | #if defined(_MSC_VER) || \ 5 | (defined(__GNUC__) && (__GNUC__ == 3 && __GNUC_MINOR__ >= 4) || \ 6 | (__GNUC__ >= 4)) // GCC supports "pragma once" correctly since 3.4 7 | #pragma once 8 | #endif 9 | 10 | #include "yaml-cpp/parser.h" 11 | #include "yaml-cpp/emitter.h" 12 | #include "yaml-cpp/emitterstyle.h" 13 | #include "yaml-cpp/stlemitter.h" 14 | #include "yaml-cpp/exceptions.h" 15 | 16 | #include "yaml-cpp/node/node.h" 17 | #include "yaml-cpp/node/impl.h" 18 | #include "yaml-cpp/node/convert.h" 19 | #include "yaml-cpp/node/iterator.h" 20 | #include "yaml-cpp/node/detail/impl.h" 21 | #include "yaml-cpp/node/parse.h" 22 | #include "yaml-cpp/node/emit.h" 23 | 24 | #endif // YAML_H_62B23520_7C8E_11DE_8A39_0800200C9A66 25 | -------------------------------------------------------------------------------- /launch/start.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | -------------------------------------------------------------------------------- /libs/yaml/libgmock.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ISEE-Technology/lidar-with-velocity/ffc15d120d08099a40affe2d651800b4f66aceb1/libs/yaml/libgmock.a -------------------------------------------------------------------------------- /libs/yaml/libgmock_main.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ISEE-Technology/lidar-with-velocity/ffc15d120d08099a40affe2d651800b4f66aceb1/libs/yaml/libgmock_main.a -------------------------------------------------------------------------------- /libs/yaml/libgtest.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ISEE-Technology/lidar-with-velocity/ffc15d120d08099a40affe2d651800b4f66aceb1/libs/yaml/libgtest.a -------------------------------------------------------------------------------- /libs/yaml/libgtest_main.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ISEE-Technology/lidar-with-velocity/ffc15d120d08099a40affe2d651800b4f66aceb1/libs/yaml/libgtest_main.a -------------------------------------------------------------------------------- /libs/yaml/libyaml-cpp.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ISEE-Technology/lidar-with-velocity/ffc15d120d08099a40affe2d651800b4f66aceb1/libs/yaml/libyaml-cpp.a -------------------------------------------------------------------------------- /libs/yaml/libyaml-cpp.so: -------------------------------------------------------------------------------- 1 | libyaml-cpp.so.0.6 -------------------------------------------------------------------------------- /libs/yaml/libyaml-cpp.so.0.6: -------------------------------------------------------------------------------- 1 | libyaml-cpp.so.0.6.0 -------------------------------------------------------------------------------- /libs/yaml/libyaml-cpp.so.0.6.0: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ISEE-Technology/lidar-with-velocity/ffc15d120d08099a40affe2d651800b4f66aceb1/libs/yaml/libyaml-cpp.so.0.6.0 -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | object_undistort 4 | 0.0.0 5 | The object_undistort package 6 | 7 | 8 | 9 | 10 | yw 11 | 12 | 13 | 14 | 15 | 16 | TODO 17 | 18 | 19 | catkin 20 | roscpp 21 | rosmsg 22 | rospy 23 | sensor_msgs 24 | pcl_ros 25 | message_generation 26 | 27 | 28 | roscpp 29 | rosmsg 30 | rospy 31 | roscpp 32 | rosmsg 33 | rospy 34 | sensor_msgs 35 | pcl_ros 36 | message_generation 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /rviz_cfg/vis.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 70 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /Global Options1 8 | - /Status1 9 | - /Marker2/Status1 10 | - /PointCloud24 11 | Splitter Ratio: 0.5 12 | Tree Height: 371 13 | - Class: rviz/Selection 14 | Name: Selection 15 | - Class: rviz/Tool Properties 16 | Expanded: 17 | - /2D Pose Estimate1 18 | - /2D Nav Goal1 19 | - /Publish Point1 20 | Name: Tool Properties 21 | Splitter Ratio: 0.5886790156364441 22 | - Class: rviz/Views 23 | Expanded: 24 | - /Current View1 25 | Name: Views 26 | Splitter Ratio: 0.5 27 | - Class: rviz/Time 28 | Experimental: false 29 | Name: Time 30 | SyncMode: 0 31 | SyncSource: Image 32 | Preferences: 33 | PromptSaveOnExit: true 34 | Toolbars: 35 | toolButtonStyle: 2 36 | Visualization Manager: 37 | Class: "" 38 | Displays: 39 | - Alpha: 0.5 40 | Cell Size: 1 41 | Class: rviz/Grid 42 | Color: 160; 160; 164 43 | Enabled: false 44 | Line Style: 45 | Line Width: 0.029999999329447746 46 | Value: Lines 47 | Name: Grid 48 | Normal Cell Count: 0 49 | Offset: 50 | X: 0 51 | Y: 0 52 | Z: 0 53 | Plane: XY 54 | Plane Cell Count: 100 55 | Reference Frame: 56 | Value: false 57 | - Class: rviz/Marker 58 | Enabled: false 59 | Marker Topic: /marker_3d 60 | Name: Marker 61 | Namespaces: 62 | {} 63 | Queue Size: 100 64 | Value: false 65 | - Alpha: 1 66 | Autocompute Intensity Bounds: true 67 | Autocompute Value Bounds: 68 | Max Value: 10 69 | Min Value: -10 70 | Value: true 71 | Axis: Z 72 | Channel Name: intensity 73 | Class: rviz/PointCloud2 74 | Color: 255; 255; 255 75 | Color Transformer: FlatColor 76 | Decay Time: 0 77 | Enabled: false 78 | Invert Rainbow: false 79 | Max Color: 255; 255; 255 80 | Max Intensity: 5.999958515167236 81 | Min Color: 0; 0; 0 82 | Min Intensity: 0 83 | Name: PointCloud2 84 | Position Transformer: XYZ 85 | Queue Size: 10 86 | Selectable: true 87 | Size (Pixels): 2 88 | Size (m): 0.009999999776482582 89 | Style: Points 90 | Topic: /raw_cloud 91 | Unreliable: false 92 | Use Fixed Frame: true 93 | Use rainbow: true 94 | Value: false 95 | - Alpha: 1 96 | Autocompute Intensity Bounds: true 97 | Autocompute Value Bounds: 98 | Max Value: 10 99 | Min Value: -10 100 | Value: true 101 | Axis: Z 102 | Channel Name: intensity 103 | Class: rviz/PointCloud2 104 | Color: 255; 255; 255 105 | Color Transformer: FlatColor 106 | Decay Time: 0 107 | Enabled: false 108 | Invert Rainbow: false 109 | Max Color: 255; 255; 255 110 | Max Intensity: 5.999958515167236 111 | Min Color: 0; 0; 0 112 | Min Intensity: 0 113 | Name: PointCloud2 114 | Position Transformer: XYZ 115 | Queue Size: 10 116 | Selectable: true 117 | Size (Pixels): 2 118 | Size (m): 0.009999999776482582 119 | Style: Points 120 | Topic: /background_cloud 121 | Unreliable: false 122 | Use Fixed Frame: true 123 | Use rainbow: true 124 | Value: false 125 | - Alpha: 1 126 | Autocompute Intensity Bounds: true 127 | Autocompute Value Bounds: 128 | Max Value: 10 129 | Min Value: -10 130 | Value: true 131 | Axis: Z 132 | Channel Name: intensity 133 | Class: rviz/PointCloud2 134 | Color: 255; 255; 255 135 | Color Transformer: RGB8 136 | Decay Time: 0 137 | Enabled: true 138 | Invert Rainbow: false 139 | Max Color: 255; 255; 255 140 | Max Intensity: 5.999958515167236 141 | Min Color: 0; 0; 0 142 | Min Intensity: 0 143 | Name: PointCloud2 144 | Position Transformer: XYZ 145 | Queue Size: 10 146 | Selectable: true 147 | Size (Pixels): 3 148 | Size (m): 0.009999999776482582 149 | Style: Points 150 | Topic: /undistorted_obj_cloud 151 | Unreliable: false 152 | Use Fixed Frame: true 153 | Use rainbow: true 154 | Value: true 155 | - Class: rviz/Image 156 | Enabled: false 157 | Image Topic: /raw_img 158 | Max Value: 1 159 | Median window: 5 160 | Min Value: 0 161 | Name: Image 162 | Normalize Range: true 163 | Queue Size: 2 164 | Transport Hint: raw 165 | Unreliable: false 166 | Value: false 167 | - Class: rviz/Axes 168 | Enabled: true 169 | Length: 3 170 | Name: Axes 171 | Radius: 0.10000000149011612 172 | Reference Frame: 173 | Value: true 174 | - Class: rviz/Image 175 | Enabled: true 176 | Image Topic: /img_detection 177 | Max Value: 1 178 | Median window: 5 179 | Min Value: 0 180 | Name: Image 181 | Normalize Range: true 182 | Queue Size: 2 183 | Transport Hint: raw 184 | Unreliable: false 185 | Value: true 186 | - Class: rviz/Marker 187 | Enabled: true 188 | Marker Topic: /obj_velocity_arrow 189 | Name: Marker 190 | Namespaces: 191 | obj_vel_arrow: true 192 | Queue Size: 100 193 | Value: true 194 | - Class: rviz/MarkerArray 195 | Enabled: true 196 | Marker Topic: /obj_velocity_txt 197 | Name: MarkerArray 198 | Namespaces: 199 | obj_vel_txt: true 200 | Queue Size: 0 201 | Value: true 202 | - Alpha: 0.30000001192092896 203 | Autocompute Intensity Bounds: true 204 | Autocompute Value Bounds: 205 | Max Value: 10 206 | Min Value: -10 207 | Value: true 208 | Axis: Z 209 | Channel Name: intensity 210 | Class: rviz/PointCloud2 211 | Color: 255; 255; 255 212 | Color Transformer: FlatColor 213 | Decay Time: 0 214 | Enabled: true 215 | Invert Rainbow: false 216 | Max Color: 255; 255; 255 217 | Max Intensity: 0.058176979422569275 218 | Min Color: 0; 0; 0 219 | Min Intensity: -0.11193299293518066 220 | Name: PointCloud2 221 | Position Transformer: XYZ 222 | Queue Size: 10 223 | Selectable: true 224 | Size (Pixels): 1 225 | Size (m): 0.009999999776482582 226 | Style: Points 227 | Topic: /background_cloud 228 | Unreliable: false 229 | Use Fixed Frame: true 230 | Use rainbow: true 231 | Value: true 232 | - Alpha: 0.5 233 | Cell Size: 1 234 | Class: rviz/Grid 235 | Color: 160; 160; 164 236 | Enabled: false 237 | Line Style: 238 | Line Width: 0.029999999329447746 239 | Value: Lines 240 | Name: Grid 241 | Normal Cell Count: 0 242 | Offset: 243 | X: 20 244 | Y: 0 245 | Z: 0 246 | Plane: YZ 247 | Plane Cell Count: 100 248 | Reference Frame: 249 | Value: false 250 | Enabled: true 251 | Global Options: 252 | Background Color: 0; 0; 0 253 | Default Light: true 254 | Fixed Frame: livox 255 | Frame Rate: 30 256 | Name: root 257 | Tools: 258 | - Class: rviz/Interact 259 | Hide Inactive Objects: true 260 | - Class: rviz/MoveCamera 261 | - Class: rviz/Select 262 | - Class: rviz/FocusCamera 263 | - Class: rviz/Measure 264 | - Class: rviz/SetInitialPose 265 | Theta std deviation: 0.2617993950843811 266 | Topic: /initialpose 267 | X std deviation: 0.5 268 | Y std deviation: 0.5 269 | - Class: rviz/SetGoal 270 | Topic: /move_base_simple/goal 271 | - Class: rviz/PublishPoint 272 | Single click: true 273 | Topic: /clicked_point 274 | Value: true 275 | Views: 276 | Current: 277 | Class: rviz/Orbit 278 | Distance: 17.758193969726562 279 | Enable Stereo Rendering: 280 | Stereo Eye Separation: 0.05999999865889549 281 | Stereo Focal Distance: 1 282 | Swap Stereo Eyes: false 283 | Value: false 284 | Focal Point: 285 | X: 18.334627151489258 286 | Y: 1.1047059297561646 287 | Z: 2.6359643936157227 288 | Focal Shape Fixed Size: true 289 | Focal Shape Size: 0.05000000074505806 290 | Invert Z Axis: false 291 | Name: Current View 292 | Near Clip Distance: 0.009999999776482582 293 | Pitch: 0.8346499800682068 294 | Target Frame: 295 | Value: Orbit (rviz) 296 | Yaw: 3.2751293182373047 297 | Saved: ~ 298 | Window Geometry: 299 | Displays: 300 | collapsed: true 301 | Height: 1383 302 | Hide Left Dock: true 303 | Hide Right Dock: true 304 | Image: 305 | collapsed: false 306 | QMainWindow State: 000000ff00000000fd00000004000000000000022300000275fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000016f00000275000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b2000000000000000000000002000004df00000153fc0100000003fb0000000a0049006d0061006700650100000000000004df0000005e00fffffffb0000000a0049006d00610067006502000000430000003200000280000001e0fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000039f0000003efc0100000002fb0000000800540069006d006500000000000000039f000004f300fffffffb0000000800540069006d00650100000000000004500000000000000000000004df000003db00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730000000000ffffffff0000000000000000 307 | Selection: 308 | collapsed: false 309 | Time: 310 | collapsed: false 311 | Tool Properties: 312 | collapsed: false 313 | Views: 314 | collapsed: true 315 | Width: 1247 316 | X: 1313 317 | Y: 27 318 | -------------------------------------------------------------------------------- /src/assignment/Hungarian.cpp: -------------------------------------------------------------------------------- 1 | /////////////////////////////////////////////////////////////////////////////// 2 | // Hungarian.cpp: Implementation file for Class HungarianAlgorithm. 3 | // 4 | // This is a C++ wrapper with slight modification of a hungarian algorithm implementation by Markus Buehren. 5 | // The original implementation is a few mex-functions for use in MATLAB, found here: 6 | // http://www.mathworks.com/matlabcentral/fileexchange/6543-functions-for-the-rectangular-assignment-problem 7 | // 8 | // Both this code and the orignal code are published under the BSD license. 9 | // by Cong Ma, 2016 10 | // 11 | 12 | #include "tracker/Hungarian.h" 13 | #include 14 | #include 15 | 16 | HungarianAlgorithm::HungarianAlgorithm() {} 17 | 18 | HungarianAlgorithm::~HungarianAlgorithm() {} 19 | 20 | 21 | //********************************************************// 22 | // A single function wrapper for solving assignment problem. 23 | //********************************************************// 24 | double HungarianAlgorithm::Solve(vector> &DistMatrix, vector &Assignment) { 25 | unsigned int nRows = DistMatrix.size(); 26 | unsigned int nCols = DistMatrix[0].size(); 27 | 28 | double *distMatrixIn = new double[nRows * nCols]; 29 | int *assignment = new int[nRows]; 30 | double cost = 0.0; 31 | 32 | // Fill in the distMatrixIn. Mind the index is "i + nRows * j". 33 | // Here the cost matrix of size MxN is defined as a double precision array of N*M elements. 34 | // In the solving functions matrices are seen to be saved MATLAB-internally in row-order. 35 | // (i.e. the matrix [1 2; 3 4] will be stored as a vector [1 3 2 4], NOT [1 2 3 4]). 36 | for (unsigned int i = 0; i < nRows; i++) 37 | for (unsigned int j = 0; j < nCols; j++) 38 | distMatrixIn[i + nRows * j] = DistMatrix[i][j]; 39 | 40 | // call solving function 41 | assignmentoptimal(assignment, &cost, distMatrixIn, nRows, nCols); 42 | 43 | Assignment.clear(); 44 | for (unsigned int r = 0; r < nRows; r++) 45 | Assignment.push_back(assignment[r]); 46 | 47 | delete[] distMatrixIn; 48 | delete[] assignment; 49 | return cost; 50 | } 51 | 52 | 53 | //********************************************************// 54 | // Solve optimal solution for assignment problem using Munkres algorithm, also known as Hungarian Algorithm. 55 | //********************************************************// 56 | void HungarianAlgorithm::assignmentoptimal(int *assignment, double *cost, double *distMatrixIn, int nOfRows, 57 | int nOfColumns) { 58 | double *distMatrix, *distMatrixTemp, *distMatrixEnd, *columnEnd, value, minValue; 59 | bool *coveredColumns, *coveredRows, *starMatrix, *newStarMatrix, *primeMatrix; 60 | int nOfElements, minDim, row, col; 61 | 62 | /* initialization */ 63 | *cost = 0; 64 | for (row = 0; row < nOfRows; row++) 65 | assignment[row] = -1; 66 | 67 | /* generate working copy of distance Matrix */ 68 | /* check if all matrix elements are positive */ 69 | nOfElements = nOfRows * nOfColumns; 70 | distMatrix = (double *) malloc(nOfElements * sizeof(double)); 71 | distMatrixEnd = distMatrix + nOfElements; 72 | 73 | for (row = 0; row < nOfElements; row++) { 74 | value = distMatrixIn[row]; 75 | if (value < 0) 76 | cerr << "All matrix elements have to be non-negative." << endl; 77 | distMatrix[row] = value; 78 | } 79 | 80 | 81 | /* memory allocation */ 82 | coveredColumns = (bool *) calloc(nOfColumns, sizeof(bool)); 83 | coveredRows = (bool *) calloc(nOfRows, sizeof(bool)); 84 | starMatrix = (bool *) calloc(nOfElements, sizeof(bool)); 85 | primeMatrix = (bool *) calloc(nOfElements, sizeof(bool)); 86 | newStarMatrix = (bool *) calloc(nOfElements, sizeof(bool)); /* used in step4 */ 87 | 88 | /* preliminary steps */ 89 | if (nOfRows <= nOfColumns) { 90 | minDim = nOfRows; 91 | 92 | for (row = 0; row < nOfRows; row++) { 93 | /* find the smallest element in the row */ 94 | distMatrixTemp = distMatrix + row; 95 | minValue = *distMatrixTemp; 96 | distMatrixTemp += nOfRows; 97 | while (distMatrixTemp < distMatrixEnd) { 98 | value = *distMatrixTemp; 99 | if (value < minValue) 100 | minValue = value; 101 | distMatrixTemp += nOfRows; 102 | } 103 | 104 | /* subtract the smallest element from each element of the row */ 105 | distMatrixTemp = distMatrix + row; 106 | while (distMatrixTemp < distMatrixEnd) { 107 | *distMatrixTemp -= minValue; 108 | distMatrixTemp += nOfRows; 109 | } 110 | } 111 | 112 | /* Steps 1 and 2a */ 113 | for (row = 0; row < nOfRows; row++) 114 | for (col = 0; col < nOfColumns; col++) 115 | if (abs(distMatrix[row + nOfRows * col]) < DBL_EPSILON) 116 | if (!coveredColumns[col]) { 117 | starMatrix[row + nOfRows * col] = true; 118 | coveredColumns[col] = true; 119 | break; 120 | } 121 | } else /* if(nOfRows > nOfColumns) */ 122 | { 123 | minDim = nOfColumns; 124 | 125 | for (col = 0; col < nOfColumns; col++) { 126 | /* find the smallest element in the column */ 127 | distMatrixTemp = distMatrix + nOfRows * col; 128 | columnEnd = distMatrixTemp + nOfRows; 129 | 130 | minValue = *distMatrixTemp++; 131 | while (distMatrixTemp < columnEnd) { 132 | value = *distMatrixTemp++; 133 | if (value < minValue) 134 | minValue = value; 135 | } 136 | 137 | /* subtract the smallest element from each element of the column */ 138 | distMatrixTemp = distMatrix + nOfRows * col; 139 | while (distMatrixTemp < columnEnd) 140 | *distMatrixTemp++ -= minValue; 141 | } 142 | 143 | /* Steps 1 and 2a */ 144 | for (col = 0; col < nOfColumns; col++) 145 | for (row = 0; row < nOfRows; row++) 146 | if (abs(distMatrix[row + nOfRows * col]) < DBL_EPSILON) 147 | if (!coveredRows[row]) { 148 | starMatrix[row + nOfRows * col] = true; 149 | coveredColumns[col] = true; 150 | coveredRows[row] = true; 151 | break; 152 | } 153 | for (row = 0; row < nOfRows; row++) 154 | coveredRows[row] = false; 155 | 156 | } 157 | 158 | /* move to step 2b */ 159 | step2b(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, 160 | nOfColumns, minDim); 161 | 162 | /* compute cost and remove invalid assignments */ 163 | computeassignmentcost(assignment, cost, distMatrixIn, nOfRows); 164 | 165 | /* free allocated memory */ 166 | free(distMatrix); 167 | free(coveredColumns); 168 | free(coveredRows); 169 | free(starMatrix); 170 | free(primeMatrix); 171 | free(newStarMatrix); 172 | 173 | return; 174 | } 175 | 176 | /********************************************************/ 177 | void HungarianAlgorithm::buildassignmentvector(int *assignment, bool *starMatrix, int nOfRows, int nOfColumns) { 178 | int row, col; 179 | 180 | for (row = 0; row < nOfRows; row++) 181 | for (col = 0; col < nOfColumns; col++) 182 | if (starMatrix[row + nOfRows * col]) { 183 | #ifdef ONE_INDEXING 184 | assignment[row] = col + 1; /* MATLAB-Indexing */ 185 | #else 186 | assignment[row] = col; 187 | #endif 188 | break; 189 | } 190 | } 191 | 192 | /********************************************************/ 193 | void HungarianAlgorithm::computeassignmentcost(int *assignment, double *cost, double *distMatrix, int nOfRows) { 194 | int row, col; 195 | 196 | for (row = 0; row < nOfRows; row++) { 197 | col = assignment[row]; 198 | if (col >= 0) 199 | *cost += distMatrix[row + nOfRows * col]; 200 | } 201 | } 202 | 203 | /********************************************************/ 204 | void HungarianAlgorithm::step2a(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, 205 | bool *primeMatrix, bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, 206 | int minDim) { 207 | bool *starMatrixTemp, *columnEnd; 208 | int col; 209 | 210 | /* cover every column containing a starred zero */ 211 | for (col = 0; col < nOfColumns; col++) { 212 | starMatrixTemp = starMatrix + nOfRows * col; 213 | columnEnd = starMatrixTemp + nOfRows; 214 | while (starMatrixTemp < columnEnd) { 215 | if (*starMatrixTemp++) { 216 | coveredColumns[col] = true; 217 | break; 218 | } 219 | } 220 | } 221 | 222 | /* move to step 3 */ 223 | step2b(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, 224 | nOfColumns, minDim); 225 | } 226 | 227 | /********************************************************/ 228 | void HungarianAlgorithm::step2b(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, 229 | bool *primeMatrix, bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, 230 | int minDim) { 231 | int col, nOfCoveredColumns; 232 | 233 | /* count covered columns */ 234 | nOfCoveredColumns = 0; 235 | for (col = 0; col < nOfColumns; col++) 236 | if (coveredColumns[col]) 237 | nOfCoveredColumns++; 238 | 239 | if (nOfCoveredColumns == minDim) { 240 | /* algorithm finished */ 241 | buildassignmentvector(assignment, starMatrix, nOfRows, nOfColumns); 242 | } else { 243 | /* move to step 3 */ 244 | step3(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, 245 | nOfColumns, minDim); 246 | } 247 | 248 | } 249 | 250 | /********************************************************/ 251 | void 252 | HungarianAlgorithm::step3(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, 253 | bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim) { 254 | bool zerosFound; 255 | int row, col, starCol; 256 | 257 | zerosFound = true; 258 | while (zerosFound) { 259 | zerosFound = false; 260 | for (col = 0; col < nOfColumns; col++) 261 | if (!coveredColumns[col]) 262 | for (row = 0; row < nOfRows; row++) 263 | if ((!coveredRows[row]) && (abs(distMatrix[row + nOfRows * col]) < DBL_EPSILON)) { 264 | /* prime zero */ 265 | primeMatrix[row + nOfRows * col] = true; 266 | 267 | /* find starred zero in current row */ 268 | for (starCol = 0; starCol < nOfColumns; starCol++) 269 | if (starMatrix[row + nOfRows * starCol]) 270 | break; 271 | 272 | if (starCol == nOfColumns) /* no starred zero found */ 273 | { 274 | /* move to step 4 */ 275 | step4(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, 276 | coveredRows, nOfRows, nOfColumns, minDim, row, col); 277 | return; 278 | } else { 279 | coveredRows[row] = true; 280 | coveredColumns[starCol] = false; 281 | zerosFound = true; 282 | break; 283 | } 284 | } 285 | } 286 | 287 | /* move to step 5 */ 288 | step5(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, 289 | nOfColumns, minDim); 290 | } 291 | 292 | /********************************************************/ 293 | void 294 | HungarianAlgorithm::step4(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, 295 | bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim, int row, 296 | int col) { 297 | int n, starRow, starCol, primeRow, primeCol; 298 | int nOfElements = nOfRows * nOfColumns; 299 | 300 | /* generate temporary copy of starMatrix */ 301 | for (n = 0; n < nOfElements; n++) 302 | newStarMatrix[n] = starMatrix[n]; 303 | 304 | /* star current zero */ 305 | newStarMatrix[row + nOfRows * col] = true; 306 | 307 | /* find starred zero in current column */ 308 | starCol = col; 309 | for (starRow = 0; starRow < nOfRows; starRow++) 310 | if (starMatrix[starRow + nOfRows * starCol]) 311 | break; 312 | 313 | while (starRow < nOfRows) { 314 | /* unstar the starred zero */ 315 | newStarMatrix[starRow + nOfRows * starCol] = false; 316 | 317 | /* find primed zero in current row */ 318 | primeRow = starRow; 319 | for (primeCol = 0; primeCol < nOfColumns; primeCol++) 320 | if (primeMatrix[primeRow + nOfRows * primeCol]) 321 | break; 322 | 323 | /* star the primed zero */ 324 | newStarMatrix[primeRow + nOfRows * primeCol] = true; 325 | 326 | /* find starred zero in current column */ 327 | starCol = primeCol; 328 | for (starRow = 0; starRow < nOfRows; starRow++) 329 | if (starMatrix[starRow + nOfRows * starCol]) 330 | break; 331 | } 332 | 333 | /* use temporary copy as new starMatrix */ 334 | /* delete all primes, uncover all rows */ 335 | for (n = 0; n < nOfElements; n++) { 336 | primeMatrix[n] = false; 337 | starMatrix[n] = newStarMatrix[n]; 338 | } 339 | for (n = 0; n < nOfRows; n++) 340 | coveredRows[n] = false; 341 | 342 | /* move to step 2a */ 343 | step2a(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, 344 | nOfColumns, minDim); 345 | } 346 | 347 | /********************************************************/ 348 | void 349 | HungarianAlgorithm::step5(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, 350 | bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim) { 351 | double h, value; 352 | int row, col; 353 | 354 | /* find smallest uncovered element h */ 355 | h = DBL_MAX; 356 | for (row = 0; row < nOfRows; row++) 357 | if (!coveredRows[row]) 358 | for (col = 0; col < nOfColumns; col++) 359 | if (!coveredColumns[col]) { 360 | value = distMatrix[row + nOfRows * col]; 361 | if (value < h) 362 | h = value; 363 | } 364 | 365 | /* add h to each covered row */ 366 | for (row = 0; row < nOfRows; row++) 367 | if (coveredRows[row]) 368 | for (col = 0; col < nOfColumns; col++) 369 | distMatrix[row + nOfRows * col] += h; 370 | 371 | /* subtract h from each uncovered column */ 372 | for (col = 0; col < nOfColumns; col++) 373 | if (!coveredColumns[col]) 374 | for (row = 0; row < nOfRows; row++) 375 | distMatrix[row + nOfRows * col] -= h; 376 | 377 | /* move to step 3 */ 378 | step3(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, 379 | nOfColumns, minDim); 380 | } 381 | -------------------------------------------------------------------------------- /src/assignment/assignment.cpp: -------------------------------------------------------------------------------- 1 | #include "common/assignment.h" 2 | 3 | assignment::assignment(int argc, char** argv) 4 | { 5 | ros::init(argc, argv, "lidar_with_velocity"); 6 | ros::NodeHandle nh; 7 | 8 | // read the param 9 | if(!config_.readParam(nh)) 10 | { 11 | std::cout << "ERROR! read param fail!" << std::endl; 12 | exit(1); 13 | } 14 | 15 | 16 | 17 | run(argc, argv, nh); 18 | } 19 | 20 | assignment::~assignment(){} 21 | 22 | bool assignment::run(int argc, char** argv, ros::NodeHandle & nh) 23 | { 24 | 25 | VisHandel vis(nh); 26 | 27 | std::vector raw_img_fn; 28 | cv::glob(config_.raw_img_path_, raw_img_fn, false); 29 | if (raw_img_fn.size() == 0) 30 | { 31 | throw("raw img path doesn't exist !"); 32 | } 33 | else 34 | { 35 | std::cout << "find raw img : " << raw_img_fn.size() << std::endl; 36 | } 37 | 38 | 39 | std::vector label_img_fn; 40 | cv::glob(config_.label_img_path_, label_img_fn, false); 41 | if (label_img_fn.size() == 0) 42 | { 43 | throw("label img path doesn't exist !"); 44 | } 45 | else 46 | { 47 | std::cout << "find label img : " << label_img_fn.size() << std::endl; 48 | } 49 | 50 | 51 | std::vector allFileName = getFilesList(config_.pcd_path_, false); 52 | if (allFileName.size() == 0) 53 | { 54 | throw("pcd path doesn't exist !"); 55 | } 56 | else 57 | { 58 | std::cout << "find pcd : " << allFileName.size() << std::endl; 59 | } 60 | 61 | std::vector bboxAllFileName = getFilesList(config_.bbox_path_, false); 62 | if (bboxAllFileName.size() == 0) 63 | { 64 | throw("bbox path doesn't exist !"); 65 | } 66 | else 67 | { 68 | std::cout << "find bbox : " << bboxAllFileName.size() << std::endl; 69 | } 70 | 71 | std::vector detection3dFileName = getFilesList(config_.cube_path_, false); 72 | if (detection3dFileName.size() == 0) 73 | { 74 | throw("3d detection path doesn't exist !"); 75 | } 76 | else 77 | { 78 | std::cout << "find cube : " << detection3dFileName.size() << std::endl << std::endl; 79 | } 80 | 81 | Timer detection_3d_timer("detection_3d_timer"); 82 | std::vector detection_3d_buffer; 83 | for (size_t detection_3d_idx = 0; detection_3d_idx < detection3dFileName.size(); 84 | detection_3d_idx++) 85 | { 86 | std::string detection_3d_path = detection3dFileName[detection_3d_idx]; 87 | std::string detection_3d_name = detection_3d_path; 88 | detection_3d_name.erase(0, config_.cube_path_.size()); 89 | detection_3d_name.erase(detection_3d_name.size() - 5, detection_3d_name.size()); 90 | YAML::Node detection_3d_data = YAML::LoadFile(detection_3d_path); 91 | int obj_size; 92 | frameCubes current_cubes; 93 | if (detection_3d_data["ob_num"]) 94 | { 95 | obj_size = detection_3d_data["ob_num"].as(); 96 | } 97 | for (size_t ob_idx = 0; ob_idx < obj_size; ob_idx++) 98 | { 99 | std::string ob_name = "ob" + std::to_string(ob_idx + 1); 100 | std::string object_type; 101 | double confidence; 102 | Eigen::Matrix cube_vertexs; 103 | if (detection_3d_data[ob_name]["class"]) 104 | { 105 | object_type = detection_3d_data[ob_name]["class"].as(); 106 | } 107 | if (detection_3d_data[ob_name]["confidence"]) 108 | { 109 | confidence = detection_3d_data[ob_name]["confidence"].as(); 110 | } 111 | if (detection_3d_data[ob_name]["points"]) 112 | { 113 | std::vector vertexs_data = 114 | detection_3d_data[ob_name]["points"].as>(); 115 | double* vertexs_array = vertexs_data.data(); 116 | cube_vertexs = Eigen::Map>(vertexs_array).transpose(); 117 | cube3d detected_cube( 118 | object_type, 119 | confidence, 120 | cube_vertexs 121 | ); 122 | current_cubes.push_back(detected_cube); 123 | } 124 | } 125 | frameCubesWithTime detection_cube(std::atoi(detection_3d_name.c_str()), current_cubes); 126 | detection_3d_buffer.push_back(detection_cube); 127 | } 128 | std::cout << "\nreaded detection 3d files : " << detection_3d_buffer.size() << ", "; 129 | detection_3d_timer.rlog("detection_3d_timer cost"); 130 | cout << "\n"; 131 | 132 | Timer raw_reader_timer("raw_reader_timer"); 133 | std::vector raw_img_buffer; 134 | for (size_t raw_img_idx = 0; raw_img_idx < raw_img_fn.size(); raw_img_idx++) 135 | { 136 | std::string raw_img_time_str = raw_img_fn[raw_img_idx]; 137 | raw_img_time_str 138 | = raw_img_time_str.erase(0, config_.raw_img_path_.size()).erase(10,1).erase(19,4); 139 | uint64_t raw_img_time_uint64; 140 | raw_img_time_uint64 = 141 | std::strtoull(raw_img_time_str.c_str(), NULL, 0); 142 | std::cout << "\rreading raw img : " << raw_img_time_uint64 << ", " 143 | << raw_img_idx+1 << "/" << raw_img_fn.size(); 144 | cv::Mat current_raw_img; 145 | current_raw_img = cv::imread(raw_img_fn[raw_img_idx]); 146 | imageWithTime raw_img_and_time(raw_img_time_uint64, 147 | current_raw_img); 148 | raw_img_buffer.push_back(raw_img_and_time); 149 | } 150 | std::cout << "\nreaded raw img : " << raw_img_buffer.size() << ", "; 151 | raw_reader_timer.rlog("raw_reader_timer cost"); 152 | std::cout << "\n"; 153 | 154 | Timer label_reader_timer("label_reader_timer"); 155 | std::vector label_img_buffer; 156 | for (size_t label_img_idx = 0; label_img_idx < label_img_fn.size(); 157 | label_img_idx++) 158 | { 159 | std::string label_img_time_str = label_img_fn[label_img_idx]; 160 | label_img_time_str 161 | = label_img_time_str.erase(0, 162 | config_.label_img_path_.size()).erase(10,1).erase(19,4); 163 | uint64_t label_img_time_uint64; 164 | label_img_time_uint64 = 165 | std::strtoull(label_img_time_str.c_str(), NULL, 0); 166 | std::cout << "\rreading label img : " << label_img_time_uint64 << ", " 167 | << label_img_idx+1 << "/" << label_img_fn.size(); 168 | cv::Mat current_label_img; 169 | current_label_img = cv::imread(label_img_fn[label_img_idx]); 170 | imageWithTime label_img_and_time(label_img_time_uint64, 171 | current_label_img); 172 | label_img_buffer.push_back(label_img_and_time); 173 | } 174 | std::cout << "\nreaded label img : " << label_img_buffer.size() << ", "; 175 | label_reader_timer.rlog("label_reader_timer cost"); 176 | std::cout << "\n"; 177 | 178 | Timer bbox_reader_timer("bbox_reader_timer"); 179 | std::vector bbox_buffer; 180 | for (size_t framebboxs_idx = 0; framebboxs_idx < bboxAllFileName.size(); 181 | framebboxs_idx++) 182 | { 183 | frameBboxs current_frame_obj; 184 | std::string frameBboxs_path = bboxAllFileName[framebboxs_idx]; 185 | std::string bboxs_time_str = bboxAllFileName[framebboxs_idx]; 186 | bboxs_time_str = bboxs_time_str.erase(0, 187 | bboxs_time_str.size() - 25).erase(20, 5).erase(10, 1); 188 | uint64_t bboxs_time_uint64; 189 | bboxs_time_uint64 = std::strtoull(bboxs_time_str.c_str(), NULL, 0); 190 | YAML::Node bboxs_data = YAML::LoadFile(frameBboxs_path); 191 | int obj_size; 192 | if (bboxs_data["ob_num"]) 193 | { 194 | obj_size = bboxs_data["ob_num"].as(); 195 | obj_size -= 1; 196 | } 197 | for (size_t ob_idx = 0; ob_idx < obj_size; ob_idx++) 198 | { 199 | std::string ob_name = "ob" + std::to_string(ob_idx + 1); 200 | std::string object_type; 201 | double score; 202 | int bbox_x1; 203 | int bbox_x2; 204 | int bbox_y1; 205 | int bbox_y2; 206 | if (bboxs_data[ob_name]["object_name"]) 207 | { 208 | object_type = bboxs_data[ob_name]["object_name"].as(); 209 | } 210 | if (bboxs_data[ob_name]["confidence_score"]) 211 | { 212 | score = bboxs_data[ob_name]["confidence_score"].as(); 213 | } 214 | if (bboxs_data[ob_name]["bbox_x1"]) 215 | { 216 | bbox_x1 = bboxs_data[ob_name]["bbox_x1"].as(); 217 | } 218 | if (bboxs_data[ob_name]["bbox_x2"]) 219 | { 220 | bbox_x2 = bboxs_data[ob_name]["bbox_x2"].as(); 221 | } 222 | if (bboxs_data[ob_name]["bbox_y1"]) 223 | { 224 | bbox_y1 = bboxs_data[ob_name]["bbox_y1"].as(); 225 | }if (bboxs_data[ob_name]["bbox_y2"]) 226 | { 227 | bbox_y2 = bboxs_data[ob_name]["bbox_y2"].as(); 228 | } 229 | obBBOX object( 230 | object_type, 231 | score, 232 | bbox_y1, 233 | bbox_y2, 234 | bbox_x1, 235 | bbox_x2 236 | ); 237 | current_frame_obj.push_back(object); 238 | } 239 | frameBboxsWithTime current_frame_with_time(bboxs_time_uint64, 240 | current_frame_obj); 241 | bbox_buffer.push_back(current_frame_with_time); 242 | } 243 | std::cout << "readed Bbox : " << bbox_buffer.size() << ", "; 244 | bbox_reader_timer.rlog("bbox_reader_timer cost"); 245 | std::cout << "\n"; 246 | 247 | Timer pcd_reader_timer("pcd_reader_timer"); 248 | std::vector pcd_buffer; 249 | std::vector> pose_buffer; 250 | YAML::Node pose_config = YAML::LoadFile( 251 | this->config_.pose_path_ 252 | ); 253 | for (size_t pcd_idx = 0; pcd_idx < allFileName.size(); pcd_idx++) 254 | { 255 | std::vector frame_pcds = 256 | getFilesList(allFileName[pcd_idx], false); 257 | pcl::PointCloud current_point_cloud[hubLidarNum]; 258 | std::string pcds_time_str = allFileName[pcd_idx]; 259 | std::string pose_time = pcds_time_str.erase(0,pcds_time_str.size()-20); 260 | pcds_time_str = pcds_time_str.erase( 261 | 0,pcds_time_str.size()-20).erase(10,1); 262 | uint64_t pcds_time_uint64; 263 | pcds_time_uint64 = std::strtoull(pcds_time_str.c_str(), NULL, 0); 264 | pcdWithTime current_pcds; 265 | Eigen::Matrix4d pose_matrix; 266 | if (pose_config[pose_time]) 267 | { 268 | std::vector pose_vector = 269 | pose_config[ 270 | pose_time 271 | ].as>(); 272 | double* pose_array = pose_vector.data(); 273 | pose_matrix = 274 | Eigen::Map(pose_array).transpose(); 275 | } 276 | else 277 | { 278 | return false; 279 | } 280 | for (size_t lidar_idx = 0; lidar_idx < frame_pcds.size(); lidar_idx++) 281 | { 282 | std::string pcd_time_str = frame_pcds[lidar_idx]; 283 | pcd_time_str = pcd_time_str.erase( 284 | 0,pcd_time_str.size()-23).erase(19,4); 285 | uint64_t pcd_time_uint64; 286 | pcd_time_uint64 = std::strtoull(pcd_time_str.c_str(), NULL, 0); 287 | pcl::io::loadPCDFile(frame_pcds[lidar_idx], 288 | current_point_cloud[lidar_idx]); 289 | std::cout << "\rreading pcd : " << pcds_time_uint64 << ", " 290 | << lidar_idx+1 << "/" << frame_pcds.size() << ", " 291 | << pcd_idx+1 << "/" << allFileName.size(); 292 | current_pcds.push_back( 293 | std::pair>( 294 | pcd_time_uint64, current_point_cloud[lidar_idx] 295 | )); 296 | } 297 | pcdsWithTime pcds_and_time(pcds_time_uint64, current_pcds); 298 | pcd_buffer.push_back(pcds_and_time); 299 | pose_buffer.push_back(pair(pcds_time_uint64, 300 | pose_matrix)); 301 | } 302 | std::cout << "\nreaded pcd : " << pcd_buffer.size() << ", "; 303 | pcd_reader_timer.rlog("pcd_reader_timer cost"); 304 | std::cout << "\n"; 305 | 306 | std::cout << "readed pose : " << pose_buffer.size() << "\n\n"; 307 | 308 | if(pcd_buffer.size() == raw_img_buffer.size() 309 | && pcd_buffer.size() == label_img_buffer.size()) 310 | { 311 | std::sort(raw_img_buffer.begin(), raw_img_buffer.end(), imgSort); 312 | std::sort(label_img_buffer.begin(), label_img_buffer.end(), imgSort); 313 | std::sort(pcd_buffer.begin(), pcd_buffer.end(), pcdSort); 314 | std::sort(bbox_buffer.begin(), bbox_buffer.end(), bboxSort); 315 | std::sort(detection_3d_buffer.begin(), detection_3d_buffer.end(), cubeSort); 316 | std::sort(pose_buffer.begin(), pose_buffer.end(), poseSort); 317 | } 318 | else 319 | { 320 | throw("ERROR! input imgs and pcds don't match!"); 321 | } 322 | 323 | boost::shared_ptr viewer_objs 324 | (new pcl::visualization::PCLVisualizer("3D Viewer objects")); 325 | viewer_objs->setBackgroundColor(0, 0, 0); 326 | viewer_objs->addCoordinateSystem(0.5); 327 | viewer_objs->setCameraPosition(-46.698877,8.333347,39.880589,0.449239,-0.004796,0.893399); 328 | 329 | fusion_tracker fusionTracker; 330 | size_t loop_count = 0; 331 | std::vector> final_last_pcs; 332 | visualization_msgs::MarkerArray obj_vel_txt_markerarray; 333 | 334 | for (size_t frame_idx = 0; frame_idx < pcd_buffer.size(); ++frame_idx) 335 | { 336 | cout << "=========================== seq:" << frame_idx + 1 << " ===========================" << endl; 337 | 338 | expand_3d_cube(detection_3d_buffer[frame_idx]); 339 | 340 | Frame frame( 341 | raw_img_buffer[frame_idx], 342 | label_img_buffer[frame_idx], 343 | pcd_buffer[frame_idx], 344 | bbox_buffer[frame_idx], 345 | detection_3d_buffer[frame_idx], 346 | config_ 347 | ); 348 | 349 | frame.full_detection(&pcd_buffer[frame_idx]); 350 | // frame.verboseFrame(); 351 | 352 | std::vector aligned_detection_buffer; 353 | std::vector> * obj_clouds; 354 | pcl::PointCloud obj_cloud; 355 | obj_clouds = frame.getObjcloud(); 356 | if (bbox_buffer[frame_idx].second.size() == 0 || 357 | detection_3d_buffer[frame_idx].second.size() == 0) 358 | { 359 | continue; 360 | } 361 | 362 | frame.detection_align( 363 | obj_clouds, 364 | &raw_img_buffer[frame_idx].second, 365 | &detection_3d_buffer[frame_idx].second, 366 | &bbox_buffer[frame_idx].second, 367 | &pose_buffer[frame_idx].second, 368 | aligned_detection_buffer 369 | ); 370 | 371 | vis.txt_marker_3d_publisher(aligned_detection_buffer); 372 | 373 | sensor_msgs::PointCloud2 raw_cloud_msg; 374 | pcl::PointCloud frame_pcd = *frame.getCloud(); 375 | pcl::toROSMsg(frame_pcd, raw_cloud_msg); 376 | viewer_objs->addPointCloud( 377 | frame_pcd.makeShared(), 378 | "background_cloud" + std::to_string(frame_idx + 1) 379 | ); 380 | vis.raw_cloud_publisher(raw_cloud_msg); 381 | 382 | sensor_msgs::PointCloud2 background_cloud_msg; 383 | pcl::PointCloud background_cloud = *frame.getBackgroundcloud(); 384 | pcl::toROSMsg(background_cloud, background_cloud_msg); 385 | vis.background_cloud_publisher(background_cloud_msg); 386 | 387 | for (size_t pcd_idx = 0; pcd_idx < aligned_detection_buffer.size(); pcd_idx++) 388 | { 389 | obj_cloud += aligned_detection_buffer[pcd_idx].cloud_; 390 | } 391 | sensor_msgs::PointCloud2 obj_cloud_msg; 392 | // pcl::toROSMsg(obj_cloud, obj_cloud_msg); 393 | // vis.raw_obj_cloud_publisher(obj_cloud_msg); 394 | 395 | vis.raw_img_publisher(raw_img_buffer[frame_idx].second); 396 | 397 | vis.label_img_publisher(label_img_buffer[frame_idx].second); 398 | 399 | Timer total_timer("total time"); 400 | fusionTracker.tracking( 401 | aligned_detection_buffer, 402 | raw_img_buffer[frame_idx].second, 403 | config_, 404 | viewer_objs, 405 | obj_vel_txt_markerarray, 406 | &vis 407 | ); 408 | total_timer.rlog("total time cost:"); 409 | 410 | 411 | loop_count++; 412 | while (1) 413 | { 414 | is_nextFrame_ = 0; 415 | 416 | viewer_objs->spinOnce(1); 417 | // viewer_objs->removeAllShapes(); 418 | 419 | viewer_objs->registerKeyboardCallback(&nextFrame, &is_nextFrame_); 420 | 421 | cv::waitKey(1); 422 | 423 | if (is_nextFrame_ != 0) 424 | { 425 | viewer_objs->removeAllPointClouds(); 426 | break; 427 | } 428 | } 429 | } 430 | exit(-1); 431 | } 432 | 433 | void nextFrame(const pcl::visualization::KeyboardEvent& event, void* val) 434 | { 435 | int *pKey = (int *)val; 436 | if (event.keyDown()) 437 | { 438 | if(strcmp(event.getKeySym().c_str(), "f")) 439 | { 440 | *pKey = 1; 441 | } 442 | else if (strcmp(event.getKeySym().c_str(), "q")) 443 | { 444 | *pKey = 2; 445 | } 446 | else 447 | { 448 | *pKey = 0; 449 | } 450 | 451 | } 452 | } 453 | 454 | std::vector getFilesList(std::string dirpath, bool is_recursive) 455 | { 456 | DIR *dir = opendir(dirpath.c_str()); 457 | if (dir == NULL) 458 | { 459 | std::cout << "opendir error" << std::endl; 460 | } 461 | 462 | std::vector allPath; 463 | struct dirent *entry; 464 | while ((entry = readdir(dir)) != NULL) 465 | { 466 | // if (entry->d_type == DT_DIR) 467 | if(is_recursive) 468 | {//It's dir 469 | if (strcmp(entry->d_name, ".") == 0 || strcmp(entry->d_name, "..") == 0) 470 | continue; 471 | std::string dirNew; 472 | if(std::strcmp(&(dirpath[dirpath.length()-1]), "/") != 0) 473 | { 474 | dirNew = dirpath + "/" + entry->d_name; 475 | } 476 | else 477 | { 478 | dirNew = dirpath + entry->d_name; 479 | 480 | } 481 | std::vector tempPath = getFilesList(dirNew, 482 | !entry->d_type == DT_DIR); 483 | allPath.insert(allPath.end(), tempPath.begin(), tempPath.end()); 484 | 485 | } 486 | else 487 | { 488 | if (strcmp(entry->d_name, ".") == 0 || strcmp(entry->d_name, "..") == 0) 489 | continue; 490 | std::string name = entry->d_name; 491 | std::string imgdir; 492 | if(std::strcmp(&(dirpath[dirpath.length()-1]), "/") != 0) 493 | { 494 | imgdir = dirpath + "/" + name; 495 | } 496 | else 497 | { 498 | imgdir = dirpath + name; 499 | } 500 | allPath.push_back(imgdir); 501 | } 502 | 503 | } 504 | closedir(dir); 505 | return allPath; 506 | } 507 | 508 | bool imgSort(const imageWithTime& left, const imageWithTime& right) 509 | { 510 | return (left.first < right.first); 511 | } 512 | 513 | bool pcdSort(const pcdsWithTime& left, const pcdsWithTime& right) 514 | { 515 | return (left.first < right.first); 516 | } 517 | bool bboxSort(const frameBboxsWithTime& left, const frameBboxsWithTime& right) 518 | { 519 | return (left.first < right.first); 520 | } 521 | bool cubeSort(const frameCubesWithTime& left, const frameCubesWithTime& right) 522 | { 523 | return (left.first < right.first); 524 | } 525 | bool poseSort(const pair& left, 526 | const pair& right) 527 | { 528 | return (left.first < right.first); 529 | } 530 | bool pcSort(const pcl::PointCloud& left, 531 | const pcl::PointCloud& right) 532 | { 533 | return (left.size() < right.size()); 534 | } 535 | 536 | double GetIOU(Cube bb_test, Cube bb_gt) 537 | { 538 | /* a 2d projection iou method */ 539 | cv::Rect_ box1( 540 | bb_test.centerx_+0.5*bb_test.depth_, 541 | bb_test.centery_+0.5*bb_test.width_, 542 | bb_test.depth_, 543 | bb_test.width_ 544 | ); 545 | cv::Rect_ box2( 546 | bb_gt.centerx_+0.5*bb_gt.depth_, 547 | bb_gt.centery_+0.5*bb_gt.width_, 548 | bb_gt.depth_, 549 | bb_gt.width_ 550 | ); 551 | float in = (box1 & box2).area(); 552 | float un = box1.area() + box2.area() - in; 553 | 554 | if (un < DBL_EPSILON) 555 | return 0; 556 | 557 | return (double)(in / un); 558 | 559 | } 560 | 561 | void expand_3d_cube( 562 | frameCubesWithTime & cubes_in 563 | ) 564 | { 565 | for (size_t obj_idx = 0; obj_idx < cubes_in.second.size(); obj_idx++) 566 | { 567 | Eigen::Vector3d obj_center = cubes_in.second[obj_idx].cube_vertexs_.colwise().mean(); 568 | for (size_t pt_idx = 0; pt_idx < 8; pt_idx++) 569 | { 570 | Eigen::Vector3d expand_value; 571 | double expand_ratio = 0.2; 572 | expand_value[0] = expand_ratio * (cubes_in.second[obj_idx].cube_vertexs_(pt_idx,0) - obj_center[0]); 573 | expand_value[1] = expand_ratio * (cubes_in.second[obj_idx].cube_vertexs_(pt_idx,1) - obj_center[1]); 574 | expand_value[2] = expand_ratio * (cubes_in.second[obj_idx].cube_vertexs_(pt_idx,2) - obj_center[2]); 575 | 576 | cubes_in.second[obj_idx].cube_vertexs_(pt_idx,0) += expand_value[0]; 577 | cubes_in.second[obj_idx].cube_vertexs_(pt_idx,1) += expand_value[1]; 578 | cubes_in.second[obj_idx].cube_vertexs_(pt_idx,2) += expand_value[2]; 579 | } 580 | } 581 | 582 | } -------------------------------------------------------------------------------- /src/assignment/config.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include "common/config.h" 4 | 5 | Config::Config() 6 | { 7 | 8 | } 9 | 10 | Config::~Config() 11 | { 12 | 13 | } 14 | 15 | 16 | bool Config::readParam(ros::NodeHandle & nh) 17 | { 18 | std::cout << "-----------------config param-----------------" << std::endl; 19 | 20 | std::string cfig_path; 21 | nh.param("cfig_path",cfig_path,""); 22 | std::cout << "cfig_path : " << cfig_path << std::endl; 23 | 24 | YAML::Node config = YAML::LoadFile( 25 | cfig_path.c_str() 26 | ); 27 | if (config["camera_intrinsic"]) 28 | { 29 | std::vector camera_intrinsic_vector = 30 | config["camera_intrinsic"].as>(); 31 | double* camera_intrinsic_array = camera_intrinsic_vector.data(); 32 | camera_intrinsic_ = 33 | Eigen::Map(camera_intrinsic_array).transpose(); 34 | std::cout << "\ncamera_intrinsic:\n" << camera_intrinsic_ << std::endl; 35 | } 36 | else 37 | { 38 | return false; 39 | } 40 | if (config["camera_extrinsic"]) 41 | { 42 | std::vector camera_extrinsic_vector = 43 | config["camera_extrinsic"].as>(); 44 | double* camera_extrinsic_array = camera_extrinsic_vector.data(); 45 | camera_extrinsic_ = 46 | Eigen::Map(camera_extrinsic_array).transpose(); 47 | std::cout << "\ncamera_extrinsic:\n" << camera_extrinsic_ << std::endl; 48 | } 49 | else 50 | { 51 | return false; 52 | } 53 | if (config["lidar_lidar_extrinsic"]) 54 | { 55 | Eigen::Matrix lidar_lidar_extrinsic_; 56 | std::vector lidar_lidar_extrinsic_vector = 57 | config["lidar_lidar_extrinsic"].as>(); 58 | double* lidar_lidar_extrinsic_array = lidar_lidar_extrinsic_vector.data(); 59 | lidar_lidar_extrinsic_ = 60 | Eigen::Map>(lidar_lidar_extrinsic_array).transpose(); 61 | std::cout << "\nlidar_lidar_extrinsic:\n" << lidar_lidar_extrinsic_ << std::endl; 62 | 63 | for (size_t row_idx = 0; row_idx < 6; row_idx++) 64 | { 65 | double roll = lidar_lidar_extrinsic_(row_idx, 0); 66 | double pitch = lidar_lidar_extrinsic_(row_idx, 1); 67 | double yaw = lidar_lidar_extrinsic_(row_idx, 2); 68 | yaw /= 180.0/3.1415926; 69 | pitch /= 180.0/3.1415926; 70 | roll /= 180.0/3.1415926; 71 | Eigen::Matrix3d rotation_matrix; 72 | rotation_matrix = Eigen::AngleAxisd(yaw,Eigen::Vector3d::UnitZ()) * 73 | Eigen::AngleAxisd(pitch,Eigen::Vector3d::UnitY()) * 74 | Eigen::AngleAxisd(roll,Eigen::Vector3d::UnitX()); 75 | Eigen::Matrix4d lidar_lidar_extrinsic; 76 | lidar_lidar_extrinsic = Eigen::Matrix4d::Identity(); 77 | lidar_lidar_extrinsic.topLeftCorner(3,3) = rotation_matrix; 78 | lidar_lidar_extrinsic.topRightCorner(3,1) = Eigen::Vector3d( 79 | lidar_lidar_extrinsic_(row_idx, 3), 80 | lidar_lidar_extrinsic_(row_idx, 4), 81 | lidar_lidar_extrinsic_(row_idx, 5) 82 | ); 83 | lidar_lidar_ex_.push_back(lidar_lidar_extrinsic); 84 | std::cout << "lidar " << row_idx << " extrinsic = \n" 85 | << lidar_lidar_extrinsic << "\n"; 86 | } 87 | 88 | 89 | } 90 | else 91 | { 92 | return false; 93 | } 94 | if (config["lidar_to_apx_extrinsic"]) 95 | { 96 | std::vector lidar_to_apx_extrinsic_vector = 97 | config["lidar_to_apx_extrinsic"].as>(); 98 | double* lidar_to_apx_extrinsic_array = lidar_to_apx_extrinsic_vector.data(); 99 | lidar_to_apx_extrinsic_ = 100 | Eigen::Map(lidar_to_apx_extrinsic_array).transpose(); 101 | rtk_to_lidar_extrinsic_ = lidar_to_apx_extrinsic_.inverse(); 102 | std::cout << "\nlidar_to_apx_extrinsic:\n" 103 | << lidar_to_apx_extrinsic_ << std::endl; 104 | } 105 | else 106 | { 107 | return false; 108 | } 109 | if (config["dataset_path"]) 110 | { 111 | dataset_path_ = config["dataset_path"].as(); 112 | std::cout << "\ndataset_path :\n" << dataset_path_ << std::endl; 113 | 114 | pose_path_ = dataset_path_ + "/global_pose.yaml"; 115 | raw_img_path_ = dataset_path_ + "/rgb_img/"; 116 | label_img_path_ = dataset_path_ + "/label_img/"; 117 | pcd_path_ = dataset_path_ + "/pcd/"; 118 | bbox_path_ = dataset_path_ + "/detection_2d/"; 119 | cube_path_ = dataset_path_ + "/detection_3d/"; 120 | } 121 | else 122 | { 123 | return false; 124 | } 125 | if (config["camera_factor"]) 126 | { 127 | camera_factor_ = config["camera_factor"].as(); 128 | std::cout << "\ncamera_factor :\n" << camera_factor_ << std::endl; 129 | } 130 | else 131 | { 132 | return false; 133 | } 134 | if (config["imageRows"]) 135 | { 136 | imageRows_ = config["imageRows"].as(); 137 | std::cout << "\nimageRows :\n" << imageRows_ << std::endl; 138 | } 139 | else 140 | { 141 | return false; 142 | } 143 | if (config["imageCols"]) 144 | { 145 | imageCols_ = config["imageCols"].as(); 146 | std::cout << "\nimageCols :\n" << imageCols_ << std::endl; 147 | } 148 | else 149 | { 150 | return false; 151 | } 152 | if (config["sparse_optical_flow_param"]["maxCorners"]) 153 | { 154 | maxCorners_ = config["sparse_optical_flow_param"]["maxCorners"].as(); 155 | std::cout << "\nmaxCorners_ :\n" << maxCorners_ << std::endl; 156 | } 157 | else 158 | { 159 | return false; 160 | } 161 | if (config["sparse_optical_flow_param"]["qualityLevel"]) 162 | { 163 | qualityLevel_ = config["sparse_optical_flow_param"]["qualityLevel"].as(); 164 | std::cout << "\nqualityLevel_ :\n" << qualityLevel_ << std::endl; 165 | } 166 | else 167 | { 168 | return false; 169 | } 170 | if (config["sparse_optical_flow_param"]["minDistance"]) 171 | { 172 | minDistance_ = config["sparse_optical_flow_param"]["minDistance"].as(); 173 | std::cout << "\nminDistance_ :\n" << minDistance_ << std::endl; 174 | } 175 | else 176 | { 177 | return false; 178 | } 179 | if (config["sparse_optical_flow_param"]["blockSize"]) 180 | { 181 | blockSize_ = config["sparse_optical_flow_param"]["blockSize"].as(); 182 | std::cout << "\nblockSize_ :\n" << blockSize_ << std::endl; 183 | } 184 | else 185 | { 186 | return false; 187 | } 188 | if (config["sparse_optical_flow_param"]["Harris_k_value"]) 189 | { 190 | Harris_k_value_ = config["sparse_optical_flow_param"]["Harris_k_value"].as(); 191 | std::cout << "\nHarris_k_value_ :\n" << Harris_k_value_ << std::endl; 192 | } 193 | else 194 | { 195 | return false; 196 | } 197 | std::cout << "-----------------config param-----------------" << std::endl; 198 | return true; 199 | } -------------------------------------------------------------------------------- /src/assignment/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "common/assignment.h" 3 | 4 | int main (int argc, char** argv) 5 | { 6 | 7 | // start 8 | std::cout << "\nObject-Undistorting START ! \n\n"; 9 | assignment mainAssignment(argc, argv); 10 | } -------------------------------------------------------------------------------- /src/main_ros.cpp: -------------------------------------------------------------------------------- 1 | #include "ros/ros.h" 2 | #include 3 | 4 | // int main(int argc, char **argv) 5 | // { 6 | // ros::init(argc, argv, "add_two_ints_client"); 7 | 8 | // ros::NodeHandle n; 9 | // ros::ServiceClient client = 10 | // n.serviceClient("gnd_estimate_service"); 11 | // object_undistort::pcsrv srv; 12 | // srv.request.a = int64_t(3); 13 | // // srv.request.b = atoll(argv[2]); 14 | 15 | // ros::Time start_time = ros::Time::now(); 16 | // if (client.call(srv)) 17 | // { 18 | // ROS_INFO("response : %ld", (long int)srv.response.b); 19 | // std::cout << "cost time = " << ros::Time::now() - start_time << std::endl; 20 | // } 21 | // else 22 | // { 23 | // ROS_ERROR("Failed to call service add_two_ints"); 24 | // return 1; 25 | // } 26 | 27 | // return 0; 28 | // } --------------------------------------------------------------------------------