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>
1718namespace truck ::lidar_map {
1819
1920namespace bg = boost::geometry;
21+ namespace bgi = boost::geometry::index;
2022
2123using IndexPoint = std::pair<geom::Vec2, size_t >;
2224using IndexPoints = std::vector<IndexPoint>;
@@ -25,6 +27,8 @@ using RTree = bg::index::rtree<IndexPoint, bg::index::rstar<16>>;
2527using BlockSolverType = g2o::BlockSolver<g2o::BlockSolverTraits<3 , 3 >>;
2628using LinearSolverType = g2o::LinearSolverDense<BlockSolverType::PoseMatrixType>;
2729
30+ using SegmentValue = std::pair<geom::BoundingBox, geom::Segment>;
31+
2832namespace {
2933
3034void 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}
0 commit comments