├── CMakeLists.txt
├── LICENSE
├── README.md
├── Tutorial_Mid-100.md
├── config
├── performance_precision.yaml
└── performance_realtime.yaml
├── include
└── tools
│ ├── common.h
│ ├── common_tools.h
│ ├── logger.hpp
│ ├── os_compatible.hpp
│ ├── pcl_tools.hpp
│ ├── rapidjson
│ ├── allocators.h
│ ├── cursorstreamwrapper.h
│ ├── document.h
│ ├── encodedstream.h
│ ├── encodings.h
│ ├── error
│ │ ├── en.h
│ │ └── error.h
│ ├── filereadstream.h
│ ├── filewritestream.h
│ ├── fwd.h
│ ├── internal
│ │ ├── biginteger.h
│ │ ├── diyfp.h
│ │ ├── dtoa.h
│ │ ├── ieee754.h
│ │ ├── itoa.h
│ │ ├── meta.h
│ │ ├── pow10.h
│ │ ├── regex.h
│ │ ├── stack.h
│ │ ├── strfunc.h
│ │ ├── strtod.h
│ │ └── swap.h
│ ├── istreamwrapper.h
│ ├── memorybuffer.h
│ ├── memorystream.h
│ ├── msinttypes
│ │ ├── inttypes.h
│ │ └── stdint.h
│ ├── ostreamwrapper.h
│ ├── pointer.h
│ ├── prettywriter.h
│ ├── rapidjson.h
│ ├── reader.h
│ ├── schema.h
│ ├── stream.h
│ ├── stringbuffer.h
│ └── writer.h
│ ├── tools_eigen_math.hpp
│ ├── tools_json.hpp
│ ├── tools_logger.hpp
│ ├── tools_random.hpp
│ └── tools_timer.hpp
├── launch
├── livox.launch
├── rosbag.launch
├── rosbag_largescale.launch
├── rosbag_loop.launch
├── rosbag_loop_simple.launch
├── rosbag_mid100.launch
└── rosbag_realtime.launch
├── package.xml
├── pics
├── CYT_01.png
├── CYT_02.png
├── HKUST_01.png
├── HKUST_02.png
├── HKU_ZYM_01.png
├── HKU_ZYM_02.png
├── for_mid100
│ ├── mid_100_demo.gif
│ ├── modify_the_launch_files.png
│ ├── remap_topics.png
│ └── rostopic.png
├── handheld.png
├── hkust_stair.gif
├── loop_4in1.png
├── loop_hku_main.png
├── loop_hku_zym.png
├── loop_simple.png
├── system_low_cost.png
├── video_lc.png
├── video_loam.png
└── zym_rotate.gif
├── rviz_cfg
├── .bashrc
├── rosbag.rviz
└── rosbag_b.rviz
└── source
├── cell_map_keyframe.hpp
├── ceres_icp.hpp
├── ceres_pose_graph_3d.hpp
├── eigen_math.hpp
├── laser_feature_extractor.cpp
├── laser_feature_extractor.hpp
├── laser_mapping.cpp
├── laser_mapping.hpp
├── livox_feature_extractor.hpp
├── point_cloud_registration.hpp
├── read_camera.cpp
└── scene_alignment.hpp
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(loam_livox)
3 |
4 | set(CMAKE_BUILD_TYPE "Release")
5 | set(CMAKE_CXX_FLAGS "-std=c++14")
6 | set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g")
7 |
8 | find_package(catkin REQUIRED COMPONENTS
9 | geometry_msgs
10 | nav_msgs
11 | sensor_msgs
12 | roscpp
13 | rospy
14 | rosbag
15 | std_msgs
16 | image_transport
17 | cv_bridge
18 | tf
19 | )
20 |
21 | find_package(Eigen3 REQUIRED)
22 | find_package(OpenCV REQUIRED)
23 | find_package(Ceres REQUIRED)
24 |
25 | find_package(PCL REQUIRED)
26 | message(STATUS "***** PCL version: ${PCL_VERSION} *****")
27 | ####
28 |
29 | include_directories(
30 | include
31 | ${catkin_INCLUDE_DIRS}
32 | ${PCL_INCLUDE_DIRS}
33 | ${OpenCV_INCLUDE_DIRS}
34 | ${CERES_INCLUDE_DIRS}
35 | ./include/tools/
36 | )
37 |
38 | catkin_package(
39 | CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs
40 | DEPENDS EIGEN3 PCL
41 | INCLUDE_DIRS include
42 | )
43 |
44 |
45 | add_executable(livox_scanRegistration source/laser_feature_extractor.cpp)
46 | target_link_libraries(livox_scanRegistration ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS})
47 |
48 | add_executable(livox_laserMapping source/laser_mapping.cpp )
49 | target_link_libraries(livox_laserMapping ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${CERES_LIBRARIES} )
50 |
51 | add_executable(read_camera source/read_camera.cpp)
52 | target_link_libraries(read_camera ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${CERES_LIBRARIES} ${OpenCV_LIBS})
53 |
54 |
55 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # LOAM-Livox
2 | ## A robust LiDAR Odometry and Mapping (LOAM) package for Livox-LiDAR
3 |
4 |
5 |

6 |

7 |
8 |
9 | **Loam-Livox** is a robust, low drift, and real time odometry and mapping package for [*Livox LiDARs*](https://www.livoxtech.com/), significant low cost and high performance LiDARs that are designed for massive industrials uses. Our package address many key issues: feature extraction and selection in a very limited FOV, robust outliers rejection, moving objects filtering, and motion distortion compensation. In addition, we also integrate other features like parallelable pipeline, point cloud management using cells and maps, loop closure, utilities for maps saving and reload, etc. To know more about the details, please refer to our related paper:)
10 |
11 |
12 |

13 |
14 |
15 |
16 | In the development of our package, we reference to LOAM, [LOAM_NOTED](https://github.com/cuitaixiang/LOAM_NOTED), and [A-LOAM](https://github.com/HKUST-Aerial-Robotics/A-LOAM).
17 |
18 | **Developer:** [Jiarong Lin](https://github.com/ziv-lin)
19 |
20 | **Our related paper**: our related papers are now available on arxiv:
21 | 1. [Loam_livox: A fast, robust, high-precision LiDAR odometry and mapping package for LiDARs of small FoV](https://arxiv.org/abs/1909.06700)
22 | 2. [A fast, complete, point cloud based loop closure for LiDAR odometry and mapping](https://arxiv.org/abs/1909.11811)
23 |
24 | **Our related video**: our related videos are now available on YouTube (click below images to open):
25 |
26 |

27 |

28 |
29 |
30 |
31 | ## 1. Prerequisites
32 | ### 1.1 **Ubuntu** and **ROS**
33 | Ubuntu 64-bit 16.04 or 18.04.
34 | ROS Kinetic or Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation) and its additional ROS pacakge:
35 |
36 | ```
37 | sudo apt-get install ros-XXX-cv-bridge ros-XXX-tf ros-XXX-message-filters ros-XXX-image-transport
38 | ```
39 | **NOTICE:** remember to replace "XXX" on above command as your ROS distributions, for example, if your use ROS-kinetic, the command should be:
40 |
41 | ```
42 | sudo apt-get install ros-kinetic-cv-bridge ros-kinetic-tf ros-kinetic-message-filters ros-kinetic-image-transport
43 | ```
44 |
45 | ### 1.2. **Ceres Solver**
46 | Follow [Ceres Installation](http://ceres-solver.org/installation.html).
47 |
48 | ### 1.3. **PCL**
49 | Follow [PCL Installation](http://www.pointclouds.org/downloads/linux.html).
50 |
51 | **NOTICE:** Recently, we find that the point cloud output form the voxelgrid filter vary form PCL 1.7 and 1.9, and PCL 1.7 leads some failure in some of our examples ([issue #28](https://github.com/hku-mars/loam_livox/issues/28)). By this, we strongly recommand you to use update your PCL as version 1.9 if you are using the lower version.
52 |
53 | ## 2. Build
54 | Clone the repository and catkin_make:
55 |
56 | ```
57 | cd ~/catkin_ws/src
58 | git clone https://github.com/hku-mars/loam_livox.git
59 | cd ../
60 | catkin_make
61 | source ~/catkin_ws/devel/setup.bash
62 | ```
63 | ## 3. Directly run
64 | ### 3.1 Livox Mid-40
65 | Connect to your PC to Livox LiDAR (Mid-40) by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then (launch our algorithm **first**, then livox-ros-driver):
66 |
67 | ```
68 | roslaunch loam_livox livox.launch
69 | roslaunch livox_ros_driver livox_lidar.launch
70 | ```
71 | ### 3.2 Livox Mid-100
72 | Unfortunately, the default configuration of Livox-ros-driver mix all three lidar point cloud as together, which causes some difficulties in our feature extraction and motion blur compensation. By this, some of the adaptations (modify some configurations) are required to launch our package.
73 |
74 | For more details, please kindly refer our [**tutorials (click me to open)**](./Tutorial_Mid-100.md).
75 |
76 | ## 4. Rosbag Example
77 | ### 4.1. **Common rosbag**
78 | Download [Our recorded rosbag](https://drive.google.com/drive/folders/1HWomWWPSEVvka2QVB2G41iRvSwIt5NWf?usp=sharing) and then
79 | ```
80 | roslaunch loam_livox rosbag.launch
81 | rosbag play YOUR_DOWNLOADED.bag
82 | ```
83 |
84 |

85 |

86 |
87 |
88 |
89 |

90 |

91 |
92 |
93 | ### 4.1. **Large-scale rosbag**
94 | For large scale rosbag (for example, the [HKUST_01.bag](https://drive.google.com/file/d/1OoAu0WcRhyDsQB9ltPLWeZ2WZlGJz6LO/view?usp=sharing) ), we recommand you launch with bigger line and plane resolution (using *rosbag_largescale.launch*)
95 | ```
96 | roslaunch loam_livox rosbag_largescale.launch
97 | rosbag play YOUR_DOWNLOADED.bag
98 | ```
99 |
100 |

101 |

102 |
103 |
104 | ### 4.2 **Livox Mid-100 example**
105 | Download our recorded rosbag files ([mid100_example.bag](https://drive.google.com/open?id=1hvjmt4YuGROE-3HWqOfUdofc6zvXxjmU) ), then:
106 | ```
107 | roslaunch loam_livox rosbag_mid100.launch
108 | rosbag play mid100_example.bag
109 | ```
110 |
111 |

112 |
113 |
114 | ## 5. Rosbag Example with loop closure enabled
115 |
116 | ### 5.1. **Loop closure demostration**
117 | We provide a rosbag file of small size (named "loop_loop_hku_zym.bag", [Download here](https://drive.google.com/file/d/1rXRzbiZYeFtCWhmwCj8OuZaUUkGCsNrM)) for demostration:
118 |
119 |

120 |
121 |
122 | ```
123 | roslaunch loam_livox rosbag_loop_simple.launch
124 | rosbag play YOUR_PATH/loop_simple.bag
125 | ```
126 | ### 5.2. **Other examples**
127 |
128 |

129 |

130 |
131 |
132 | For other example ([loop_loop_hku_zym.bag](https://drive.google.com/open?id=1J3sVQEwnkjaimf9abH1qjId1S4VEZuMu), [loop_hku_main.bag](https://drive.google.com/open?id=1HrlFkzLMfcYbQsbOiSlSlm5blybrSVd2)), launch with:
133 | ```
134 | roslaunch loam_livox rosbag_loop.launch
135 | rosbag play YOUR_DOWNLOADED.bag
136 | ```
137 | **NOTICE:** The only difference between launch files "rosbag_loop_simple.launch" and "rosbag_loop.launch" is the minimum number of keyframes (minimum_keyframe_differen) between two candidate frames of loop detection.
138 |
139 |
140 | ## 6. Have troubles in downloading the rosbag files?
141 | If you have some troubles in downloading the rosbag files form google net-disk (like [issue #33](https://github.com/hku-mars/loam_livox/issues/33)), you can download the same files from [Baidu net-disk](https://pan.baidu.com/s/1nMSJRuP8io8mEqLgACUT_w).
142 | ```
143 | Link(链接): https://pan.baidu.com/s/1nMSJRuP8io8mEqLgACUT_w
144 | Extraction code(提取码): sv9z
145 | ```
146 | If the share link is disabled, please feel free to email me (ziv.lin.ljr@gmail.com) for updating the link as soon as possible.
147 |
148 | ## 7. Our 3D-printable handheld device
149 | To get our following handheld device, please go to another one of our [open source reposity](https://github.com/ziv-lin/My_solidworks/tree/master/livox_handhold), all of the 3D parts are all designed of FDM printable. We also release our solidwork files so that you can freely make your own adjustments.
150 |
151 |
152 |

153 |

154 |
155 |
156 | ## 8.Acknowledgments
157 | Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time) LOAM, [LOAM_NOTED](https://github.com/cuitaixiang/LOAM_NOTED), and [A-LOAM](https://github.com/HKUST-Aerial-Robotics/A-LOAM).
158 |
159 | ## 9. License
160 | The source code is released under [GPLv2](http://www.gnu.org/licenses/) license.
161 |
162 | We are still working on improving the performance and reliability of our codes. For any technical issues, please contact me via email Jiarong Lin < ziv.lin.ljr@gmail.com >.
163 |
164 | For commercial use, please contact Dr. Fu Zhang < fuzhang@hku.hk >
165 |
--------------------------------------------------------------------------------
/Tutorial_Mid-100.md:
--------------------------------------------------------------------------------
1 | # Launch our package with Livox Mid-100
2 | As we have mentioned in our [project page](./README.md), the default configuration of Livox-ros-driver mix all three lidar point cloud as together, which causes some difficulties in our feature extraction and motion blur compensation. By this, some of the adaptations (modify some configurations) are required to launch our package :)
3 |
4 |

5 |
6 | # 1. Installation the newest [Livox-SDK](https://github.com/Livox-SDK/Livox-SDK) and [Livox-ros-driver](https://github.com/Livox-SDK/livox_ros_driver)
7 | Publish the Mid-100 point cloud data as three independence topics is the relatively new feature of drivers. If you are using the older kits, please update your driver (including both the SDK and ROS-dirver) as the newest version.
8 |
9 | ## 1.1 Install Livox-SDK
10 | Follow [Livox-SDK Installation](https://github.com/Livox-SDK/Livox-SDK).
11 | ## 1.2 Install Livox-ros-driver
12 |
13 | Follow [Livox-ros-driver Installation](https://github.com/Livox-SDK/livox_ros_driver).
14 |
15 | ## 2. Publish Mid-100 point cloud data as three independence topics
16 | To change the way of publishing the point cloud, you can modify the parameter named "multi_topic" in the launch file ([livox_lidar.launch](https://github.com/Livox-SDK/livox_ros_driver/blob/master/livox_ros_driver/launch/livox_lidar.launch) ) from "0" to "1", like this:
17 |
18 |

19 |
20 |
21 |
22 | If your configurations are correct, you will see this the point cloud data are published by three rostopics, like this:
23 | ```
24 | roslaunch livox_ros_driver livox_lidar.launch
25 | rostopic list
26 | ```
27 |
28 |

29 |
30 | The ros-messages with its topic named **"/livox/lidar_SN"** is of the data published by Mid-100.
31 |
32 | ## 3. Launch our package
33 | Before launch our package, you need to remap the topic to ensure our package can receive the point cloud data.
34 |
35 | Open our launch files (for example, the [rosbag_mid100.launch](./launch/rosbag_mid100.launch)), then remap the topic name "/laser_points_0", "/laser_points_1" and "/laser_points_3" to the topic "/livox/lidar_SN", shown as the following figure:
36 |
37 |

38 |
39 |
40 | ## 4. Rosbag example
41 | Download our recorded rosbag files ([mid100_example.bag](mid100_example) ), then:
42 | ```
43 | roslaunch loam_livox rosbag_mid100.launch
44 | rosbag play mid100_example.bag
45 | ```
--------------------------------------------------------------------------------
/config/performance_precision.yaml:
--------------------------------------------------------------------------------
1 | common:
2 | lidar_type: "livox"
3 | maximum_parallel_thread: 1 # number of thread use for interative pose optimization
4 | odom_mode: 1
5 | if_motion_deblur: 0 # motion deblur, 0: piesewise processing; 1: linear interpolation
6 | if_save_to_pcd_files: 0
7 | if_update_mean_and_cov_incrementally: 1
8 | threshold_cell_revisit: 2000 # if update frame index bigger than this threshold, treat target cell as revisited
9 |
10 | feature_extraction:
11 | scan_line: 64
12 | mapping_line_resolution: 0.1
13 | mapping_plane_resolution: 0.4
14 | livox_min_sigma: 7e-4
15 | livox_min_dis: 0.1
16 | corner_curvature: 0.1
17 | surface_curvature: 0.005
18 | minimum_view_angle: 5
19 |
20 | optimization:
21 | minimum_icp_R_diff: 0.01
22 | minimum_icp_T_diff: 0.01
23 | maximum_residual_blocks: 200
24 | max_allow_final_cost: 2.0
25 | icp_maximum_iteration: 15
26 | ceres_maximum_iteration: 50
27 |
28 | mapping:
29 | matching_mode: 0 # 0 = history, 1 = cube
30 | input_downsample_mode: 1 #
31 | init_accumulate_frames: 50
32 | maximum_mapping_buffer: 20000000
33 | maximum_histroy_buffer: 400
34 | maximum_in_fov_angle: 45
35 | maximum_pointcloud_delay_time: 0.1
36 | maximum_search_range_corner: 100
37 | maximum_search_range_surface: 100
38 | surround_pointcloud_resolution: 0.30
39 | max_allow_incre_R: 20
40 | max_allow_incre_T: 0.3
41 | max_allow_final_cost: 2.0
42 |
43 | loop_closure:
44 | if_enable_loop_closure: 0
45 | if_dump_keyframe_data: 0
46 | scans_of_each_keyframe: 300
47 | scans_between_two_keyframe: 100
48 | minimum_keyframe_differen: 200
49 | minimum_similarity_linear: 0.65
50 | minimum_similarity_planar: 0.94
51 | map_alignment_resolution: 0.1
52 | maximum_keyframe_in_waiting_list: 10
53 | map_alignment_maximum_icp_iteration: 5
54 | map_alignment_inlier_threshold: 0.20
55 | map_alignment_if_dump_matching_result: 0
56 | scene_alignment_maximum_residual_block: 3000
--------------------------------------------------------------------------------
/config/performance_realtime.yaml:
--------------------------------------------------------------------------------
1 | common:
2 | lidar_type: "livox"
3 | maximum_parallel_thread: 3 # number of thread use for interative pose optimization
4 | odom_mode: 1
5 | if_motion_deblur: 0 # motion deblur, 0: piesewise processing; 1: linear interpolation
6 | if_save_to_pcd_files: 0
7 | if_update_mean_and_cov_incrementally: 0
8 | threshold_cell_revisit: 100000 # if update frame index bigger than this threshold, treat target cell as revisited
9 |
10 | feature_extraction:
11 | scan_line: 64
12 | mapping_line_resolution: 0.2
13 | mapping_plane_resolution: 0.6
14 | livox_min_sigma: 7e-4
15 | livox_min_dis: 0.1
16 | corner_curvature: 0.1
17 | surface_curvature: 0.005
18 | minimum_view_angle: 5
19 |
20 | optimization:
21 | minimum_icp_R_diff: 0.01
22 | minimum_icp_T_diff: 0.01
23 | maximum_residual_blocks: 150
24 | max_allow_final_cost: 2.0
25 | icp_maximum_iteration: 15
26 | ceres_maximum_iteration: 50
27 |
28 | mapping:
29 | matching_mode: 0 # 0 = history, 1 = cube
30 | input_downsample_mode: 1 #
31 | init_accumulate_frames: 50
32 | maximum_mapping_buffer: 50
33 | maximum_histroy_buffer: 200
34 | maximum_in_fov_angle: 45
35 | maximum_pointcloud_delay_time: 1.0
36 | maximum_search_range_corner: 100
37 | maximum_search_range_surface: 100
38 | surround_pointcloud_resolution: 0.5
39 |
40 | loop_closure:
41 | if_enable_loop_closure: 0
42 | if_dump_keyframe_data: 0
43 | scans_of_each_keyframe: 300
44 | scans_between_two_keyframe: 100
45 | minimum_keyframe_differen: 200
46 | minimum_similarity_linear: 0.65
47 | minimum_similarity_planar: 0.94
48 | map_alignment_resolution: 0.1
49 | maximum_keyframe_in_waiting_list: 10
50 | map_alignment_maximum_icp_iteration: 5
51 | map_alignment_inlier_threshold: 0.20
52 | map_alignment_if_dump_matching_result: 0
53 | scene_alignment_maximum_residual_block: 3000
--------------------------------------------------------------------------------
/include/tools/common.h:
--------------------------------------------------------------------------------
1 | // Author: Jiarong Lin ziv.lin.ljr@gmail.com
2 |
3 | #pragma once
4 |
5 | #include
6 |
7 | #include
8 | #define printf_line printf( " %s %d \r\n", __FILE__, __LINE__ );
9 | typedef pcl::PointXYZI PointType;
10 |
11 | inline double rad2deg(double radians)
12 | {
13 | return radians * 180.0 / M_PI;
14 | }
15 |
16 | inline double deg2rad(double degrees)
17 | {
18 | return degrees * M_PI / 180.0;
19 | }
20 |
--------------------------------------------------------------------------------
/include/tools/common_tools.h:
--------------------------------------------------------------------------------
1 | #ifndef __COMMON_TOOLS_H__
2 | #define __COMMON_TOOLS_H__
3 |
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include "tools_logger.hpp"
12 | #include "tools_timer.hpp"
13 | #include "tools_random.hpp"
14 | #include "tools_json.hpp"
15 | #include "os_compatible.hpp"
16 | namespace Common_tools
17 | {
18 | template
19 | static std::vector vector_2d_to_1d(std::vector> & pt_vec_vec)
20 | {
21 | std::vector pt_vec;
22 | for (unsigned int i = 0; i < pt_vec_vec.size(); i++)
23 | {
24 | pt_vec.insert(pt_vec.end(), pt_vec_vec[i].begin(), pt_vec_vec[i].end());
25 | }
26 | return pt_vec;
27 | };
28 |
29 | template
30 | std::vector std_set_to_vector (const std::set & input_set)
31 | {
32 | std::vector output_vector;
33 | for(auto it = input_set.begin() ; it!= input_set.end(); it++)
34 | {
35 | output_vector.push_back(*(it));
36 | }
37 | return output_vector;
38 | };
39 |
40 | template
41 | std::set std_vector_to_set (const std::vector & input_vector)
42 | {
43 | std::set output_set;
44 | for(auto it = input_vector.begin() ; it!= input_vector.end(); it++)
45 | {
46 | output_set.insert(*(it));
47 | }
48 | return output_set;
49 | };
50 |
51 | template
52 | void maintain_maximum_thread_pool(std::list & thread_pool, size_t maximum_parallel_thread)
53 | {
54 | if(thread_pool.size() >= (size_t) maximum_parallel_thread)
55 | {
56 | //printf("******** Maximum thread number reach, current size = %d, wait finish... *****\r\n", thread_pool.size());
57 | while ( 1 )
58 | {
59 | //printf_line;
60 | for ( auto it = thread_pool.begin(); it != thread_pool.end(); it++ )
61 | {
62 |
63 | auto status = (*it)->wait_for(std::chrono::nanoseconds(1));
64 | if ( status == std::future_status::ready )
65 | {
66 | //cout << "status == std::future_status::ready" << endl;
67 | delete *it;
68 | thread_pool.erase( it );
69 | break;
70 | }
71 | }
72 | if(thread_pool.size() < (size_t) maximum_parallel_thread)
73 | {
74 | break;
75 | }
76 | std::this_thread::sleep_for( std::chrono::nanoseconds( 1 ) );
77 | }
78 |
79 | }
80 |
81 | };
82 |
83 | inline bool if_file_exit( const std::string &name )
84 | {
85 | //Copy from: https://stackoverflow.com/questions/12774207/fastest-way-to-check-if-a-file-exist-using-standard-c-c11-c
86 | struct stat buffer;
87 | return ( stat( name.c_str(), &buffer ) == 0 );
88 | };
89 | }
90 | #endif
91 |
--------------------------------------------------------------------------------
/include/tools/logger.hpp:
--------------------------------------------------------------------------------
1 | // Author: Lin Jiarong ziv.lin.ljr@gmail.com
2 |
3 | #ifndef __LOGGER_HPP__
4 | #define __LOGGER_HPP__
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include