diff --git a/README.md b/README.md
index 08a86de..29869d3 100644
--- a/README.md
+++ b/README.md
@@ -5,8 +5,9 @@ This implementation is modified from [A-LOAM](https://github.com/HKUST-Aerial-Ro
Comparing with A-LOAM, this implementation has following features:
-- it's ROS-free
-- it's more readable and easier to understand/modify
+- ROS-free: it can run without ROS environment
+- Multi-threading instead of multi-process: more deterministic
+- Higher code quality: more readable and easier to understand/modify
@@ -56,7 +57,16 @@ You can modify `examples/main_noros.cc` to add support for other point cloud for
# Dependences
+### OS
+Tested on ubuntu 16.04/18.04/20.04.
+
### C++17
+If cannot find *std::filesystem* error is encountered during your compiling, please upgrade your compiler.
+We recommend `g++-9` (or higher version).
+
+### ROS
+Only `examples/main_rosbag.cc` needs ROS. You can exclude it from compiling by modifying `examples/CMakeLists.txt`.
+
### Eigen: linear algebra, quaternion
```
sudo apt install libeigen3-dev
@@ -78,6 +88,4 @@ sudo apt install libyaml-cpp-dev
### ceres: non-linear optimization
```
sudo apt install libceres-dev
-```
-
-### ROS (optional)
+```
\ No newline at end of file
diff --git a/examples/main_noros.cc b/examples/main_noros.cc
index bdd9cb9..7ddbff7 100644
--- a/examples/main_noros.cc
+++ b/examples/main_noros.cc
@@ -50,7 +50,7 @@ int main(int argc, char *argv[]) {
PointCloudPtr cloud(new PointCloud);
pcl::io::loadPCDFile(path.string(), *cloud);
PointCloudHandler(cloud, &slam);
- std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ std::this_thread::sleep_for(std::chrono::milliseconds(100)); // 10 Hz
}
return 0;
}
diff --git a/examples/package.xml b/examples/package.xml
index 5cde9d8..a79b173 100644
--- a/examples/package.xml
+++ b/examples/package.xml
@@ -7,7 +7,7 @@
A ROS-free implementation of LOAM.
- feixyz
+ feixyz
BSD