Skip to content

Commit

Permalink
tag 1.0
Browse files Browse the repository at this point in the history
  • Loading branch information
YuePanEdward committed Oct 25, 2019
1 parent 900a453 commit e257059
Show file tree
Hide file tree
Showing 5 changed files with 139 additions and 5 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ message("SRC_LIST is " ${SRC_LIST})
SET(DEP_LIBS ${DEP_LIBS} ${PCL_LIBRARIES} ${OpenCV_LIBS} /usr/local/lib/libproj.so glog::glog ${GFLAGS_LIBRARIES})

# Pure Lidar Odometry test
add_executable(lo_test_kitti ${PROJECT_SOURCE_DIR}/samples/lidar_odometry_test_kitti.cpp ${SRC_LIST})
add_executable(lo_test_kitti ${PROJECT_SOURCE_DIR}/test/lidar_odometry_test_kitti.cpp ${SRC_LIST})
target_link_libraries(lo_test_kitti ${DEP_LIBS})

add_executable(lo_test_apollo ${PROJECT_SOURCE_DIR}/samples/lidar_odometry_test_apollo.cpp ${SRC_LIST})
add_executable(lo_test_apollo ${PROJECT_SOURCE_DIR}/test/lidar_odometry_test_apollo.cpp ${SRC_LIST})
target_link_libraries(lo_test_apollo ${DEP_LIBS})
21 changes: 21 additions & 0 deletions LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
MIT License

Copyright (c) 2019 Yue Pan

Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
7 changes: 4 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,16 @@
Lidar Odometry and Mapping with Mutiple Metrics Linear Least Square ICP

## Principle
Instead of using non-linear optimization when doing transformation estimation, this algorithm use the linear least square for all of the point-to-point, point-to-line and point-to-plane distance metrics during the ICP registration process.
Instead of using non-linear optimization when doing transformation estimation, this algorithm use the linear least square for all of the point-to-point, point-to-line and point-to-plane distance metrics during the ICP registration process based on a good enough initial guess.


## How to use

1. Install dependent 3rd libraries:
PCL, OpenCV, Eigen, VTK, Glog, Gflags.

If you'd like to use your own data and want to know its absolute projected coordinate, install Proj.
[PCL](https://github.com/PointCloudLibrary/pcl), [OpenCV](https://github.com/opencv/opencv), [Eigen](https://eigen.tuxfamily.org/dox/), [Glog](https://github.com/google/glog), [Gflags](https://github.com/gflags/gflags).

If you'd like to use your own data and want to know its absolute projected coordinate, install [Proj](https://proj.org/download.html).

2. Compile
```
Expand Down
56 changes: 56 additions & 0 deletions test/lidar_odometry_test_apollo.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
#include <iostream>
#include <fstream>
#include <string>
#include <map>

#include <gflags/gflags.h>
#include <glog/logging.h>

#include <Eigen/Core>
#include <Eigen/Geometry>

#include "types.h"
#include "llslo.h"
#include "map_viewer.hpp"
#include "dataio.hpp"

DEFINE_int32(transaction_id, -1, "transaction id.");
DEFINE_string(transaction_folder, "", "transaction folder.");
DEFINE_string(pcd_filelist, "", "pcd file list.");
DEFINE_string(config_file, "", "config file.");
DEFINE_string(output_foler, "", "output folder.");
DEFINE_int32(begin_frame_id, -1, "begin frame id.");
DEFINE_int32(end_frame_id, -1, "end frame id.");
DEFINE_string(exp_num, "1", "id of experiment");


int main(int argc, char **argv)
{
//google::SetLogDestination(google::GLOG_INFO, "./log");
google::ParseCommandLineFlags(&argc, &argv, true);
google::InitGoogleLogging("lls_loam"); // init google logging must be carried out after parse command line flags is carried out.
LOG(INFO) << "Logging is written to " << FLAGS_log_dir;
CHECK(FLAGS_transaction_folder != "") << "Need to specify the pcd folder to read.";
CHECK(FLAGS_pcd_filelist != "") << "Need to specify the pcd file list to read.";
CHECK(FLAGS_begin_frame_id != -1) << "Need to specify the begin frame id.";
CHECK(FLAGS_end_frame_id != -1) << "Need to specify the end frame id.";

lls_loam::transaction_param_t trsct_prm;
trsct_prm.transaction_id = FLAGS_transaction_id;
trsct_prm.transaction_root_path = FLAGS_transaction_folder;
trsct_prm.lidar_root_path = FLAGS_transaction_folder + "/HDL64";
trsct_prm.gnss_root_path = FLAGS_transaction_folder + "/OXTS";
trsct_prm.lidar_file_list = FLAGS_pcd_filelist;
trsct_prm.submap_full_root_path = FLAGS_transaction_folder + "/SubmapFull_" + FLAGS_exp_num;
trsct_prm.submap_feature_root_path = FLAGS_transaction_folder + "/SubmapFeature_" + FLAGS_exp_num;
//Key parameter to set
trsct_prm.local_map_max_size=10; //Local map's max frame number

lls_loam::Transaction transaction(trsct_prm);

// Import Data
transaction.LoadApolloData(FLAGS_begin_frame_id,FLAGS_end_frame_id);

// Lidar Odometery
transaction.RunPureLidarOdometry(transaction.sub_maps_[0]);
}
56 changes: 56 additions & 0 deletions test/lidar_odometry_test_kitti.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
#include <iostream>
#include <fstream>
#include <string>
#include <map>

#include <gflags/gflags.h>
#include <glog/logging.h>

#include <Eigen/Core>
#include <Eigen/Geometry>

#include "types.h"
#include "llslo.h"
#include "map_viewer.hpp"
#include "dataio.hpp"

DEFINE_int32(transaction_id, -1, "transaction id.");
DEFINE_string(transaction_folder, "", "transaction folder.");
DEFINE_string(pcd_filelist, "", "pcd file list.");
DEFINE_string(config_file, "", "config file.");
DEFINE_string(output_foler, "", "output folder.");
DEFINE_int32(begin_frame_id, -1, "begin frame id.");
DEFINE_int32(end_frame_id, -1, "end frame id.");
DEFINE_string(exp_num, "1", "id of experiment");


int main(int argc, char **argv)
{
//google::SetLogDestination(google::GLOG_INFO, "./log");
google::ParseCommandLineFlags(&argc, &argv, true);
google::InitGoogleLogging("lls_loam"); // init google logging must be carried out after parse command line flags is carried out.
LOG(INFO) << "Logging is written to " << FLAGS_log_dir;
CHECK(FLAGS_transaction_folder != "") << "Need to specify the pcd folder to read.";
CHECK(FLAGS_pcd_filelist != "") << "Need to specify the pcd file list to read.";
CHECK(FLAGS_begin_frame_id != -1) << "Need to specify the begin frame id.";
CHECK(FLAGS_end_frame_id != -1) << "Need to specify the end frame id.";

lls_loam::transaction_param_t trsct_prm;
trsct_prm.transaction_id = FLAGS_transaction_id;
trsct_prm.transaction_root_path = FLAGS_transaction_folder;
trsct_prm.lidar_root_path = FLAGS_transaction_folder + "/HDL64";
trsct_prm.gnss_root_path = FLAGS_transaction_folder + "/OXTS";
trsct_prm.lidar_file_list = FLAGS_pcd_filelist;
trsct_prm.submap_full_root_path = FLAGS_transaction_folder + "/SubmapFull_" + FLAGS_exp_num;
trsct_prm.submap_feature_root_path = FLAGS_transaction_folder + "/SubmapFeature_" + FLAGS_exp_num;
//Key parameter to set
trsct_prm.local_map_max_size=10; //Local map's max frame number

lls_loam::Transaction transaction(trsct_prm);

// Import Data
transaction.LoadKITTIData(FLAGS_begin_frame_id,FLAGS_end_frame_id);

// Lidar Odometery
transaction.RunPureLidarOdometry(transaction.sub_maps_[0]);
}

0 comments on commit e257059

Please sign in to comment.