Skip to content

Commit fdf5a94

Browse files
PostRedPostRed
andauthored
use rtee for icp edges (#205)
* use rtee for icp edges * small fix (remove break from loop + remove filter param) * pr fixes * remove ktree number * pr fixes * small fix --------- Co-authored-by: PostRed <s21v_kolomnikova@179.ru>
1 parent 73c063d commit fdf5a94

File tree

5 files changed

+95
-12
lines changed

5 files changed

+95
-12
lines changed

packages/geom/include/geom/distance.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,4 +27,6 @@ double distanceSq(const MotionState& a, const MotionState& b) noexcept;
2727

2828
double distance(const MotionState& a, const MotionState& b) noexcept;
2929

30+
double distance(const Segment& a, const Segment& b) noexcept;
31+
3032
} // namespace truck::geom

packages/geom/src/distance.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
#include "geom/distance.h"
2+
#include "geom/intersection.h"
23

34
#include "common/math.h"
45

@@ -50,4 +51,15 @@ double distance(const MotionState& a, const MotionState& b) noexcept {
5051
return distance(a.pos, b.pos);
5152
}
5253

54+
double distance(const Segment& a, const Segment& b) noexcept {
55+
if (intersect(a, b)) {
56+
return 0.0;
57+
}
58+
return std::min(
59+
{distance(a.begin, projection(a.begin, b)),
60+
distance(a.end, projection(a.end, b)),
61+
distance(b.begin, projection(b.begin, a)),
62+
distance(b.end, projection(b.end, a))});
63+
}
64+
5365
} // namespace truck::geom

packages/lidar_map/include/lidar_map/builder.h

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,12 +2,20 @@
22

33
#include "geom/pose.h"
44
#include "lidar_map/common.h"
5+
#include "geom/bounding_box.h"
6+
#include "geom/segment.h"
7+
#include "geom/vector.h"
8+
#include "geom/boost/box.h"
59

10+
#include <boost/geometry.hpp>
11+
#include <boost/geometry/index/rtree.hpp>
612
#include <g2o/core/sparse_optimizer.h>
713
#include <g2o/core/hyper_graph.h>
814

915
namespace truck::lidar_map {
1016

17+
namespace bgi = boost::geometry::index;
18+
1119
class EdgeData : public g2o::HyperGraph::Data {
1220
public:
1321
EdgeData(int value) : _value(value) {}
@@ -36,6 +44,8 @@ struct PoseInfo {
3644

3745
using EdgesInfo = std::vector<EdgeInfo>;
3846
using PosesInfo = std::vector<PoseInfo>;
47+
using SegmentValue = std::pair<geom::BoundingBox, geom::Segment>;
48+
using ICPRTree = bgi::rtree<SegmentValue, bgi::quadratic<16>>;
3949

4050
struct PoseGraphInfo {
4151
EdgesInfo edges;
@@ -45,8 +55,10 @@ struct PoseGraphInfo {
4555
struct BuilderParams {
4656
std::string icp_config;
4757
double icp_edge_max_dist = 0.6;
58+
double icp_edge_min_dist = 1.0;
4859
double odom_edge_weight = 1.0;
4960
double icp_edge_weight = 3.0;
61+
double min_poses_dist = 1.0;
5062
bool verbose = true;
5163
};
5264

@@ -57,6 +69,8 @@ class Builder {
5769
std::pair<geom::Poses, Clouds> sliceDataByPosesProximity(
5870
const geom::Poses& poses, const Clouds& clouds, double poses_min_dist) const;
5971

72+
geom::BoundingBox computeBoundingBox(const geom::Segment& segment);
73+
6074
void initPoseGraph(const geom::Poses& poses, const Clouds& clouds);
6175

6276
geom::Poses optimizePoseGraph(size_t iterations = 1);
@@ -83,6 +97,7 @@ class Builder {
8397
ICP icp_;
8498
g2o::SparseOptimizer optimizer_;
8599
BuilderParams params_;
100+
ICPRTree icp_edges_rtree_;
86101
};
87102

88103
} // namespace truck::lidar_map

packages/lidar_map/src/builder.cpp

Lines changed: 51 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
#include "geom/distance.h"
88

99
#include <boost/geometry.hpp>
10+
#include <boost/geometry/index/rtree.hpp>
1011
#include <g2o/core/block_solver.h>
1112
#include <g2o/core/optimization_algorithm_levenberg.h>
1213
#include <g2o/solvers/dense/linear_solver_dense.h>
@@ -17,6 +18,7 @@
1718
namespace truck::lidar_map {
1819

1920
namespace bg = boost::geometry;
21+
namespace bgi = boost::geometry::index;
2022

2123
using IndexPoint = std::pair<geom::Vec2, size_t>;
2224
using IndexPoints = std::vector<IndexPoint>;
@@ -25,6 +27,8 @@ using RTree = bg::index::rtree<IndexPoint, bg::index::rstar<16>>;
2527
using BlockSolverType = g2o::BlockSolver<g2o::BlockSolverTraits<3, 3>>;
2628
using LinearSolverType = g2o::LinearSolverDense<BlockSolverType::PoseMatrixType>;
2729

30+
using SegmentValue = std::pair<geom::BoundingBox, geom::Segment>;
31+
2832
namespace {
2933

3034
void normalize(Cloud& cloud) {
@@ -172,6 +176,20 @@ std::pair<geom::Poses, Clouds> Builder::sliceDataByPosesProximity(
172176
return {filtered_poses, filtered_clouds};
173177
}
174178

179+
/**
180+
* Computes the bounding box for a given segment.
181+
*
182+
* @param segment The input line segment.
183+
* @return BoundingBox object that encloses the segment.
184+
*/
185+
geom::BoundingBox Builder::computeBoundingBox(const geom::Segment& segment) {
186+
return geom::BoundingBox(
187+
geom::Vec2(
188+
std::min(segment.begin.x, segment.end.x), std::min(segment.begin.y, segment.end.y)),
189+
geom::Vec2(
190+
std::max(segment.begin.x, segment.end.x), std::max(segment.begin.y, segment.end.y)));
191+
}
192+
175193
/**
176194
* Initialize pose graph
177195
*
@@ -214,11 +232,40 @@ void Builder::initPoseGraph(const geom::Poses& poses, const Clouds& clouds) {
214232
}
215233

216234
auto data_points_clouds = toDataPoints(clouds);
217-
218235
// Add ICP edges
219236
for (size_t i = 0; i < poses.size(); i++) {
220237
for (size_t j = i + 1; j < poses.size(); j++) {
221-
if (geom::distance(poses[i], poses[j]) > params_.icp_edge_max_dist) {
238+
// Distance between two poses exceeds the maximum allowed ICP edge distance
239+
bool is_distance_unused =
240+
geom::distance(poses[i], poses[j]) > params_.icp_edge_max_dist;
241+
// Indices of the poses are close enough based on the minimum pose distance
242+
double min_indices_dist = params_.icp_edge_max_dist / params_.min_poses_dist;
243+
bool are_indices_close =
244+
std::abs(static_cast<int>(i) - static_cast<int>(j)) <= min_indices_dist;
245+
246+
if (is_distance_unused || are_indices_close) {
247+
continue;
248+
}
249+
250+
geom::Vec2 start(poses[i].pos.x, poses[i].pos.y);
251+
geom::Vec2 end(poses[j].pos.x, poses[j].pos.y);
252+
geom::Segment segment(start, end);
253+
geom::BoundingBox bbox = computeBoundingBox(segment);
254+
255+
std::vector<SegmentValue> nearest_segments;
256+
icp_edges_rtree_.query(bgi::nearest(bbox, 1), std::back_inserter(nearest_segments));
257+
258+
bool can_add = true;
259+
if (!nearest_segments.empty()) {
260+
const auto& [existing_bbox, existing_segment] = nearest_segments.front();
261+
// If the distance between segments is less than the minimum allowed value or they
262+
// intersect, the new ICP edge is not added.
263+
if (geom::distance(segment, existing_segment) < params_.icp_edge_min_dist) {
264+
can_add = false;
265+
}
266+
}
267+
268+
if (!can_add) {
222269
continue;
223270
}
224271

@@ -239,6 +286,7 @@ void Builder::initPoseGraph(const geom::Poses& poses, const Clouds& clouds) {
239286
edge->setUserData(userData);
240287

241288
optimizer_.addEdge(edge);
289+
icp_edges_rtree_.insert(std::make_pair(bbox, segment));
242290
}
243291
}
244292

@@ -312,7 +360,7 @@ PoseGraphInfo Builder::calculatePoseGraphInfo() const {
312360
.id = vertex_se2->id(),
313361
.pose = {
314362
.pos = geom::Vec2{estimate[0], estimate[1]},
315-
.dir = truck::geom::Angle::fromRadians(estimate[2])}});
363+
.dir = geom::Angle::fromRadians(estimate[2])}});
316364
}
317365
return pose_graph_info;
318366
}

packages/lidar_map/src/main.cpp

Lines changed: 15 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,14 @@ const std::string kOutputTopicLidarMap = "/lidar_map";
2121
const std::string kOutputTopicPoses = "/poses";
2222
const std::string kOutputTopicClouds = "/clouds";
2323
const std::string kPkgPathLidarMap = ament_index_cpp::get_package_share_directory("lidar_map");
24+
const std::string kIcpConfigPath = kPkgPathLidarMap + "/config/icp.yaml";
2425
const int kPointsIntensityThreshold = 15;
26+
const double kMinPosesDist = 1.0;
27+
const double kIcpEdgeMaxDist = 3.0;
28+
const double kIcpEdgeMinDist = 1.0;
29+
const double kOdomEdgeWeight = 1.0;
30+
const double kIcpEdgeWeight = 3.0;
31+
const size_t kOptimizationSteps = 10;
2532

2633
int main(int argc, char* argv[]) {
2734
bool enable_mcap_log = false;
@@ -74,17 +81,16 @@ int main(int argc, char* argv[]) {
7481
}
7582

7683
const BuilderParams builder_params{
77-
.icp_config = kPkgPathLidarMap + "/config/icp.yaml",
78-
.icp_edge_max_dist = 3,
79-
.odom_edge_weight = 1.0,
80-
.icp_edge_weight = 3.0,
84+
.icp_config = kIcpConfigPath,
85+
.icp_edge_max_dist = kIcpEdgeMaxDist,
86+
.icp_edge_min_dist = kIcpEdgeMinDist,
87+
.odom_edge_weight = kOdomEdgeWeight,
88+
.icp_edge_weight = kIcpEdgeWeight,
89+
.min_poses_dist = kMinPosesDist,
8190
.verbose = true};
8291

8392
Builder builder = Builder(builder_params);
8493

85-
const size_t optimization_steps = 10;
86-
const double min_poses_dist = 4.0;
87-
8894
std::shared_ptr<serialization::writer::MCAPWriter> mcap_writer = nullptr;
8995

9096
if (enable_mcap_log) {
@@ -102,7 +108,7 @@ int main(int argc, char* argv[]) {
102108
{
103109
const auto [odom_msgs, point_cloud_msgs] =
104110
serialization::reader::readAndSyncOdomWithPointCloud(
105-
mcap_input_path, kInputTopicOdom, kInputTopicPointCloud, min_poses_dist);
111+
mcap_input_path, kInputTopicOdom, kInputTopicPointCloud, kMinPosesDist);
106112

107113
poses = toPoses(odom_msgs);
108114
clouds = toClouds(point_cloud_msgs);
@@ -135,7 +141,7 @@ int main(int argc, char* argv[]) {
135141
serialization::writer::writePoseGraphInfoToJSON(json_log_path, pose_graph_info, 0);
136142
}
137143

138-
for (size_t i = 1; i <= optimization_steps; i++) {
144+
for (size_t i = 1; i <= kOptimizationSteps; i++) {
139145
poses = builder.optimizePoseGraph();
140146

141147
if (enable_mcap_log) {

0 commit comments

Comments
 (0)