Skip to content

Commit 79d847d

Browse files
authored
Merge pull request #6 from TUMFTM/3-switch-to-gicp
Restructe with major changes to the core library
2 parents 27e242e + 3f91410 commit 79d847d

23 files changed

+235
-98
lines changed

README.md

Lines changed: 19 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717

1818
## Concept
1919

20-
We use reference maps in combination with classical LiDAR odometry to enable drift-free localization/mapping. Our approach was developed for high-precision mapping. It enables georeferenced LiDAR-only point cloud mapping without GNSS. A detailed description of our pipeline can be found in the linked paper.
20+
We use reference maps in combination with classical LiDAR odometry to enable drift-free localization/mapping. Our approach is designed for high precision mapping. It enables georeferenced LiDAR-only point cloud mapping without GNSS. A detailed description of our pipeline can be found in the linked paper.
2121

2222
<img src=doc/pipeline_diagram.png alt="diagram" width="480" />
2323

@@ -26,7 +26,7 @@ We use reference maps in combination with classical LiDAR odometry to enable dri
2626
<details>
2727
<summary>Install</summary>
2828

29-
We provide a Docker image on Docker Hub, which will automatically pulled within the Run section, but you also have the option to build is locally.
29+
We provide a Docker image on Docker Hub, which will automatically be pulled within the Run section, but you also have the option to build it locally.
3030
```sh
3131
./docker/build_docker.sh # (optional)
3232
```
@@ -35,7 +35,7 @@ We provide a Docker image on Docker Hub, which will automatically pulled within
3535
<details>
3636
<summary>Run</summary>
3737

38-
To use our approach, you need a reference map and an initial guess for the first pose.
38+
To use our approach, you need a reference map and an initial guess of the first pose.
3939

4040
The easiest way to use our approach is with the provided Docker image.
4141
```sh
@@ -49,6 +49,21 @@ The output of the algorithm are poses in the KITTI format.
4949

5050
We also provide Python bindings. Have a look in the `python` folder, where we provide a test script.
5151

52+
</details>
53+
<details>
54+
<summary>Configure</summary>
55+
56+
The configuration of this pipeline can be changed in the `cpp/config` files. The naming suggest the intended usecase for the files. The most important parameters to play with if your results are not as good as expected are:
57+
58+
| Parameter | Description | Default | Note |
59+
| :-------- | :-------- | :--------: | :-------- |
60+
| pipeline_.visualize | Toggle GUI | `true` | use `false` on headless servers |
61+
| preprocess_.downsampling_resolution | Scans are voxelized before usage | `1.5` | Reduce the size for increased robustness |
62+
| preprocess_.num_neighbors | Points for covariance calculation | `10` | Try both directions |
63+
| registration_.voxel_resolution | Voxelhashmap voxel size | `1.0` | Reduce the size for increased robustness |
64+
| registration_.lambda | Optimization dampening factor | `1.0` | Increase to increase the robustness |
65+
66+
5267
</details>
5368
<details>
5469
<summary>Develop</summary>
@@ -82,7 +97,7 @@ pip install -e .
8297

8398
## Acknowledgement
8499

85-
Great inspiration was taken from the following repositories. If you are using our work, please also leave a star at their repositories and cite their work.
100+
Great inspiration has come from the following repositories. If you use our work, please also leave a star in their repositories and cite their work.
86101

87102
* [KISS-ICP](https://github.com/PRBonn/kiss-icp)
88103
* [small_gicp](https://github.com/koide3/small_gicp)

cpp/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ add_library(
2828
core/registration.cpp
2929
core/pose_graph.cpp
3030
core/prediction.cpp
31+
core/preprocess.cpp
3132
io/kitti_loader.cpp
3233
io/map_loader.cpp
3334
pipeline/openlidarmap.cpp

cpp/config/config.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
#include <iostream>
44

55
#include "config/ceres_config.hpp"
6+
#include "config/kernel_config.hpp"
67
#include "config/pipeline_config.hpp"
78
#include "config/preprocess_config.hpp"
89
#include "config/registration_config.hpp"
@@ -11,6 +12,7 @@ namespace openlidarmap::config {
1112

1213
struct Config {
1314
CeresConfig ceres_{};
15+
KernelConfig kernel_{};
1416
RegistrationConfig registration_{};
1517
PreProcessConfig preprocess_{};
1618
PipelineConfig pipeline_{};

cpp/config/kernel_config.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
#pragma once
2+
3+
#include <cstddef>
4+
5+
namespace openlidarmap::config {
6+
7+
struct KernelConfig {
8+
double model_sse{};
9+
size_t num_samples{};
10+
double sigma{};
11+
12+
KernelConfig()
13+
: model_sse(1.0),
14+
num_samples(1),
15+
sigma(1.0) {}
16+
};
17+
18+
} // namespace openlidarmap::config

cpp/config/pipeline_config.hpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,14 @@ struct PipelineConfig {
99
double rotation_threshold{};
1010
size_t sliding_window_size{};
1111
bool use_sliding_window{};
12+
bool visualize{};
1213

1314
PipelineConfig()
14-
: translation_threshold(0.1),
15-
rotation_threshold(0.1),
15+
: translation_threshold(0.05),
16+
rotation_threshold(0.05),
1617
sliding_window_size(250),
17-
use_sliding_window(true) {}
18+
use_sliding_window(true),
19+
visualize(true) {}
1820
};
1921

2022
} // namespace openlidarmap::config

cpp/config/preprocess_config.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,10 @@ struct PreProcessConfig {
66
double min_range{};
77
double max_range{};
88
double downsampling_resolution{};
9+
int num_neighbors{};
910

10-
PreProcessConfig() : min_range(5.0), max_range(100.0), downsampling_resolution(1.5) {}
11+
PreProcessConfig() : min_range(5.0), max_range(100.0),
12+
downsampling_resolution(1.5), num_neighbors(10) {}
1113
};
1214

1315
} // namespace openlidarmap::config

cpp/config/registration_config.hpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ namespace openlidarmap::config {
77
struct RegistrationConfig {
88
double voxel_resolution{};
99
double max_correspondence_distance{};
10+
double max_dist_sq{};
1011
double rotation_eps{};
1112
double translation_eps{};
1213
double lambda{};
@@ -20,15 +21,16 @@ struct RegistrationConfig {
2021
RegistrationConfig()
2122
: voxel_resolution(1.0),
2223
max_correspondence_distance(6.0),
24+
max_dist_sq(max_correspondence_distance * max_correspondence_distance),
2325
rotation_eps(0.1 * M_PI / 180.0),
2426
translation_eps(1e-3),
2527
lambda(1.0),
2628
max_iterations(1000),
2729
verbose(false),
28-
map_overlap(0),
29-
removal_horizon(1e9),
30+
map_overlap(50),
31+
removal_horizon(100),
3032
search_offset(27),
31-
max_num_points_in_cell{100} {}
33+
max_num_points_in_cell(20) {}
3234
};
3335

3436
} // namespace openlidarmap::config

cpp/core/pose_factor_abs.hpp

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -12,21 +12,22 @@ struct AbsPoseError {
1212

1313
template <typename T>
1414
bool operator()(const T *const pose, T *residual) const {
15-
// Position error
15+
constexpr double STDDEV = 1.0;
16+
1617
for (int i = 0; i < 3; ++i) {
17-
residual[i] = pose[i] - T(abs_measure_[i]);
18+
residual[i] = (pose[i] - T(abs_measure_[i])) / T(STDDEV);
1819
}
1920

2021
// Quaternion error
2122
Eigen::Quaternion<T> q1(pose[6], pose[3], pose[4], pose[5]);
22-
Eigen::Quaternion<T> q2{T(abs_measure_[6]), T(abs_measure_[3]), T(abs_measure_[4]),
23-
T(abs_measure_[5])};
24-
Eigen::Quaternion<T> q_error = q1.normalized() * q2.normalized().conjugate();
23+
Eigen::Quaternion<T> q2{T(abs_measure_[6]), T(abs_measure_[3]),
24+
T(abs_measure_[4]), T(abs_measure_[5])};
25+
Eigen::Quaternion<T> q_error = q1.normalized() * q2.normalized().inverse();
2526

2627
// Convert quaternion error to residual
27-
residual[3] = T(2.0) * q_error.x();
28-
residual[4] = T(2.0) * q_error.y();
29-
residual[5] = T(2.0) * q_error.z();
28+
residual[3] = T(2.0) * q_error.x() / T(STDDEV);
29+
residual[4] = T(2.0) * q_error.y() / T(STDDEV);
30+
residual[5] = T(2.0) * q_error.z() / T(STDDEV);
3031

3132
return true;
3233
}

cpp/core/pose_factor_rel.hpp

Lines changed: 37 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -12,29 +12,46 @@ struct RelPoseError {
1212

1313
template <typename T>
1414
bool operator()(const T *const pose_i, const T *const pose_j, T *residual) const {
15-
Eigen::Map<const Eigen::Matrix<T, 3, 1>> pos_i(pose_i);
16-
Eigen::Map<const Eigen::Matrix<T, 3, 1>> pos_j(pose_j);
15+
constexpr double STDDEV = 1.0;
1716

18-
// Extract quaternions (x,y,z,w order) to Eigen (w,x,y,z order)
17+
Eigen::Transform<T,3,Eigen::Isometry> T_i = Eigen::Transform<T,3,Eigen::Isometry>::Identity();
18+
T_i.translation() = Eigen::Map<const Eigen::Matrix<T,3,1>>(pose_i);
1919
Eigen::Quaternion<T> q_i(pose_i[6], pose_i[3], pose_i[4], pose_i[5]);
20-
Eigen::Quaternion<T> q_j(pose_j[6], pose_j[3], pose_j[4], pose_j[5]);
21-
22-
// Convert relative measurement
23-
Eigen::Matrix<T, 3, 1> rel_pos{T(rel_measure_[0]), T(rel_measure_[1]), T(rel_measure_[2])};
24-
Eigen::Quaternion<T> rel_q{T(rel_measure_[6]), T(rel_measure_[3]), T(rel_measure_[4]),
25-
T(rel_measure_[5])};
26-
27-
// Position error
28-
residual[0] = pos_j.x() - rel_pos.x();
29-
residual[1] = pos_j.y() - rel_pos.y();
30-
residual[2] = pos_j.z() - rel_pos.z();
20+
T_i.linear() = q_i.normalized().toRotationMatrix();
3121

32-
// Quaternion error
33-
Eigen::Quaternion<T> q_error = q_j.normalized() * rel_q.normalized().conjugate();
34-
35-
residual[3] = T(2.0) * q_error.x();
36-
residual[4] = T(2.0) * q_error.y();
37-
residual[5] = T(2.0) * q_error.z();
22+
Eigen::Transform<T,3,Eigen::Isometry> T_j = Eigen::Transform<T,3,Eigen::Isometry>::Identity();
23+
T_j.translation() = Eigen::Map<const Eigen::Matrix<T,3,1>>(pose_j);
24+
Eigen::Quaternion<T> q_j(pose_j[6], pose_j[3], pose_j[4], pose_j[5]);
25+
T_j.linear() = q_j.normalized().toRotationMatrix();
26+
27+
Eigen::Transform<T,3,Eigen::Isometry> T_target = Eigen::Transform<T,3,Eigen::Isometry>::Identity();
28+
T_target.translation() = Eigen::Matrix<T,3,1>(
29+
T(rel_measure_[0]),
30+
T(rel_measure_[1]),
31+
T(rel_measure_[2])
32+
);
33+
34+
const T w = T(rel_measure_[6]);
35+
const T x = T(rel_measure_[3]);
36+
const T y = T(rel_measure_[4]);
37+
const T z = T(rel_measure_[5]);
38+
Eigen::Quaternion<T> q_target(w, x, y, z);
39+
T_target.linear() = q_target.normalized().toRotationMatrix();
40+
41+
auto T_error = T_target.inverse() * T_j;
42+
43+
Eigen::Matrix<T,3,1> pos_error = T_error.translation();
44+
45+
Eigen::Quaternion<T> q_error(T_error.linear());
46+
q_error.normalize();
47+
48+
residual[0] = pos_error.x() / T(STDDEV);
49+
residual[1] = pos_error.y() / T(STDDEV);
50+
residual[2] = pos_error.z() / T(STDDEV);
51+
52+
residual[3] = T(2.0) * q_error.x() / T(STDDEV);
53+
residual[4] = T(2.0) * q_error.y() / T(STDDEV);
54+
residual[5] = T(2.0) * q_error.z() / T(STDDEV);
3855

3956
return true;
4057
}

cpp/core/pose_graph.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,12 +25,13 @@ void PoseGraph::addConstraint(size_t idx_from,
2525
new ceres::AutoDiffCostFunction<AbsPoseError, 6, 7>(new AbsPoseError(measurement)),
2626
new ceres::TukeyLoss(1.0), poses_[idx_to].data());
2727
abs_residual_blocks_.emplace_back(abs_block_id);
28+
problem_.SetManifold(poses_[idx_to].data(), pose_manifold_);
2829
} else {
2930
ceres::ResidualBlockId rel_block_id = problem_.AddResidualBlock(
3031
new ceres::AutoDiffCostFunction<RelPoseError, 6, 7, 7>(new RelPoseError(measurement)),
3132
new ceres::CauchyLoss(1.0), poses_[idx_from].data(), poses_[idx_to].data());
3233
rel_residual_blocks_.emplace_back(rel_block_id);
33-
34+
problem_.SetManifold(poses_[idx_from].data(), pose_manifold_);
3435
problem_.SetManifold(poses_[idx_to].data(), pose_manifold_);
3536
}
3637

0 commit comments

Comments
 (0)