$darkmode
clothoid_fit.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2023 Robert Bosch GmbH
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  * SPDX-License-Identifier: Apache-2.0
17  */
23 #pragma once
24 
25 #include <math.h> // for atan
26 #include <Eigen/Geometry> // for Isometry3d
27 #include <map> // for map
28 #include <memory> // for shared_ptr<>
29 #include <string> // for string
30 #include <vector> // for vector
31 
32 #include <cloe/component.hpp> // for Component, Json
33 #include <cloe/component/frustum.hpp> // for Frustum
34 #include <cloe/component/lane_boundary.hpp> // for LaneBoundary
35 #include <cloe/component/lane_sensor.hpp> // for LaneBoundarySensor
36 #include <cloe/conf/action.hpp> // for actions::ConfigureFactory
37 #include <cloe/handler.hpp> // for FromJson, ToJson
38 #include <cloe/registrar.hpp> // for Registrar
39 #include <cloe/sync.hpp> // for Sync
40 #include <cloe/trigger/set_action.hpp> // for actions::SetVariableActionFactory
41 
42 #include "g1_fitting.hpp" // for calc_clothoid
43 
44 namespace cloe {
45 
46 struct ClothoidFitConf : public Confable {
47  bool enabled = true;
48  bool frustum_culling = true;
49 
50  public:
51  ClothoidFitConf() = default;
52  virtual ~ClothoidFitConf() noexcept = default;
53 
54  CONFABLE_SCHEMA(ClothoidFitConf) {
55  return fable::Schema{
56  {"enable", make_schema(&enabled, "enable or disable component")},
57  {"frustum_culling", make_schema(&frustum_culling, "enable or disable frustum culling")},
58  };
59  }
60 };
61 
62 namespace component {
63 
69 double estimate_lane_boundary_length(const std::vector<Eigen::Vector3d>& points) {
70  double length = 0.0;
71  for (uint64_t i = 1; i < points.size(); ++i) {
72  length += (points[i] - points[i - 1]).norm();
73  }
74  return length;
75 }
76 
77 void cleanup_lane_boundary_points(std::vector<Eigen::Vector3d>& points) {
78  // Points shall have at least 1cm distance for robust clothoid estimation.
79  const double min_dist = 0.01;
80  std::vector<Eigen::Vector3d> pts_mod{points.front()};
81  for (uint64_t i = 1; i < points.size(); ++i) {
82  if ((points[i] - points[i - 1]).norm() > min_dist) {
83  pts_mod.push_back(points[i]);
84  }
85  }
86  points = pts_mod;
87 }
88 
89 // Keep track on which side of each frustum plane a point is located
90 const uint8_t PLANE_RIGHT_OK{0b0000'0001};
91 const uint8_t PLANE_LEFT_OK{0b0000'0010};
92 const uint8_t PLANE_LOW_OK{0b0000'0100};
93 const uint8_t PLANE_HIGH_OK{0b0000'1000};
94 const uint8_t PLANE_NEAR_OK{0b0001'0000};
95 const uint8_t PLANE_FAR_OK{0b0010'0000};
96 const uint8_t all_set =
97  PLANE_RIGHT_OK | PLANE_LEFT_OK | PLANE_LOW_OK | PLANE_HIGH_OK | PLANE_NEAR_OK | PLANE_FAR_OK;
98 
99 uint8_t get_plane_mask(const Frustum& frustum, const Eigen::Vector3d& pt) {
100  double fov_h_l = -0.5 * frustum.fov_h + frustum.offset_h;
101  double fov_h_u = 0.5 * frustum.fov_h + frustum.offset_h;
102  double fov_v_l = -0.5 * frustum.fov_v + frustum.offset_v;
103  double fov_v_u = 0.5 * frustum.fov_v + frustum.offset_v;
104  double range_mult = cos(frustum.offset_h) * cos(frustum.offset_v);
105  uint8_t plane_mask{0};
106  // Horizontal field of view.
107  double x = pt.x() == 0.0 ? 1.0e-10 : pt.x();
108  double phi = atan2(pt.y(), x);
109  if (phi >= fov_h_l) {
110  // Right plane.
111  plane_mask |= PLANE_RIGHT_OK;
112  }
113  if (phi <= fov_h_u) {
114  // Left plane.
115  plane_mask |= PLANE_LEFT_OK;
116  }
117  // Vertical field of view.
118  phi = atan2(pt.z(), x);
119  if (phi >= fov_v_l) {
120  // Lower plane.
121  plane_mask |= PLANE_LOW_OK;
122  }
123  if (phi <= fov_v_u) {
124  // Upper plane.
125  plane_mask |= PLANE_HIGH_OK;
126  }
127  // Field of view distance range.
128  x = pt.x() * range_mult;
129  if (x >= frustum.clip_near) {
130  // Near plane.
131  plane_mask |= PLANE_NEAR_OK;
132  }
133  if (x <= frustum.clip_far) {
134  // Far plane.
135  plane_mask |= PLANE_FAR_OK;
136  }
137  return plane_mask;
138 }
139 
140 std::vector<Eigen::Vector3d> interpolate_to_frustum_planes(const Frustum& frustum,
141  const Eigen::Vector3d& pt1,
142  uint8_t mask1,
143  const Eigen::Vector3d& pt2,
144  uint8_t mask2) {
145  auto interpolate_point_on_plane = [](const Eigen::Vector3d& x1, const Eigen::Vector3d& x2,
146  const Eigen::Vector3d& xp,
147  const Eigen::Vector3d& nv) -> Eigen::Vector3d {
148  // Define line on which the interpolation point is located.
149  Eigen::Vector3d dir = x2 - x1; // direction of interplation line
150  double int_loc = nv.dot((xp - x1)) / nv.dot(dir);
151  return x1 + int_loc * dir;
152  };
153  // Shift interpolated points by 1 mm to the inside of the frustum.
154  double offset = 0.001;
155  std::vector<Eigen::Vector3d> pts_intrp;
156  // Use exclusive OR to check for candidates plane by plane.
157  if (((mask1 ^ mask2) & PLANE_RIGHT_OK) == PLANE_RIGHT_OK) {
158  // Interpolate to right plane.
159  double fov_h_l = -0.5 * frustum.fov_h + frustum.offset_h;
160  // Normal vector pointing towards the inside of the frustum.
161  Eigen::Vector3d nvec =
162  Eigen::Vector3d(cos(fov_h_l), sin(fov_h_l), 0).cross(Eigen::Vector3d(0, 0, -1));
163  nvec = nvec / nvec.norm();
164  Eigen::Vector3d pt = interpolate_point_on_plane(pt1, pt2, Eigen::Vector3d(0, 0, 0), nvec);
165  pts_intrp.push_back(pt + offset * nvec);
166  }
167  if (((mask1 ^ mask2) & PLANE_LEFT_OK) == PLANE_LEFT_OK) {
168  // Interpolate to left plane.
169  double fov_h_u = 0.5 * frustum.fov_h + frustum.offset_h;
170  // Normal vector pointing towards the inside of the frustum.
171  Eigen::Vector3d nvec =
172  Eigen::Vector3d(cos(fov_h_u), sin(fov_h_u), 0).cross(Eigen::Vector3d(0, 0, 1));
173  nvec = nvec / nvec.norm();
174  Eigen::Vector3d pt = interpolate_point_on_plane(pt1, pt2, Eigen::Vector3d(0, 0, 0), nvec);
175  pts_intrp.push_back(pt + offset * nvec);
176  }
177  if (((mask1 ^ mask2) & PLANE_LOW_OK) == PLANE_LOW_OK) {
178  // Interpolate to lower plane.
179  double fov_v_l = -0.5 * frustum.fov_v + frustum.offset_v;
180  // Normal vector pointing towards the inside of the frustum.
181  Eigen::Vector3d nvec =
182  Eigen::Vector3d(cos(fov_v_l), 0, sin(fov_v_l)).cross(Eigen::Vector3d(0, 1, 0));
183  nvec = nvec / nvec.norm();
184  Eigen::Vector3d pt = interpolate_point_on_plane(pt1, pt2, Eigen::Vector3d(0, 0, 0), nvec);
185  pts_intrp.push_back(pt + offset * nvec);
186  }
187  if (((mask1 ^ mask2) & PLANE_HIGH_OK) == PLANE_HIGH_OK) {
188  // Interpolate to higher plane.
189  double fov_v_u = 0.5 * frustum.fov_v + frustum.offset_v;
190  // Normal vector pointing towards the inside of the frustum.
191  Eigen::Vector3d nvec =
192  Eigen::Vector3d(cos(fov_v_u), 0, sin(fov_v_u)).cross(Eigen::Vector3d(0, -1, 0));
193  nvec = nvec / nvec.norm();
194  Eigen::Vector3d pt = interpolate_point_on_plane(pt1, pt2, Eigen::Vector3d(0, 0, 0), nvec);
195  pts_intrp.push_back(pt + offset * nvec);
196  }
197  if (((mask1 ^ mask2) & PLANE_NEAR_OK) == PLANE_NEAR_OK) {
198  // Interpolate to near plane.
199  double a = cos(frustum.offset_v);
200  Eigen::Vector3d nvec = Eigen::Vector3d(a * cos(frustum.offset_h), a * sin(frustum.offset_h),
201  sin(frustum.offset_v));
202  // Normal vector pointing towards the inside of the frustum.
203  nvec = nvec / nvec.norm();
204  Eigen::Vector3d pt = interpolate_point_on_plane(pt1, pt2, frustum.clip_near * nvec, nvec);
205  pts_intrp.push_back(pt + offset * nvec);
206  }
207  if (((mask1 ^ mask2) & PLANE_FAR_OK) == PLANE_FAR_OK) {
208  // Interpolate to far plane.
209  double a = cos(frustum.offset_v);
210  Eigen::Vector3d nvec = Eigen::Vector3d(a * cos(frustum.offset_h), a * sin(frustum.offset_h),
211  sin(frustum.offset_v));
212  // Normal vector pointing towards the inside of the frustum.
213  nvec = -1.0 * nvec / nvec.norm();
214  Eigen::Vector3d pt = interpolate_point_on_plane(pt1, pt2, -1.0 * frustum.clip_far * nvec, nvec);
215  pts_intrp.push_back(pt + offset * nvec);
216  }
217  // Remove points that are not on frustum boundary.
218  auto it_rm = std::remove_if(
219  pts_intrp.begin(), pts_intrp.end(),
220  [&frustum](const Eigen::Vector3d& pt) { return get_plane_mask(frustum, pt) != all_set; });
221  pts_intrp.erase(it_rm, pts_intrp.end());
222  return pts_intrp;
223 }
224 
225 // Frustum culling radar approach adapted from
226 // https://cgvr.cs.uni-bremen.de/teaching/cg_literatur/lighthouse3d_view_frustum_culling/index.html
227 void lane_boundary_point_culling(const Frustum& frustum, std::vector<Eigen::Vector3d>& points,
228  std::vector<Eigen::Vector3d>& pts_out_start,
229  std::vector<Eigen::Vector3d>& pts_out_end) {
230  std::vector<uint8_t> mask_out_start, mask_out_end;
231  // Keep only points inside the frustum.
232  std::vector<Eigen::Vector3d> pts_frustum;
233  pts_frustum.reserve(points.size());
234  bool found_pts{false};
235  for (const auto& pt : points) {
236  uint8_t plane_mask = get_plane_mask(frustum, pt);
237  // Remove point if not in frustum.
238  if (plane_mask == all_set) {
239  if (pts_out_end.size() > 0) {
240  // In case multiple segments of the polyline are inside the frustum, only keep the first visible segment.
241  break;
242  }
243  if (pts_frustum.size() == 0 && pts_out_start.size() > 0) {
244  // First point inside frustum and points outside frustum were found previously. Interpolate to frustum boundary.
245  auto pt_intrp = interpolate_to_frustum_planes(frustum, pts_out_start.back(),
246  mask_out_start.back(), pt, plane_mask);
247  if (pt_intrp.size() == 1) {
248  pts_frustum.push_back(pt_intrp.front());
249  } else {
250  throw cloe::ModelError("Interpolation of first point inside frustum should be unique.");
251  }
252  }
253  pts_frustum.push_back(pt);
254  found_pts = true;
255  } else if (!found_pts) {
256  // Point is outside field of view and no point inside frustum was found previously.
257  if (pts_out_start.size() == 0) {
258  // First point, no additional checks necessary.
259  pts_out_start.push_back(pt);
260  mask_out_start.push_back(plane_mask);
261  } else {
262  // Check special case where the lane boundary crosses the frustum, but none of the given points is located inside.
263  Eigen::Vector3d pt_prev = pts_out_start.back();
264  // If any of the frustum planes is crossed by the line between previous point and this point, interpolate to frustum boundary.
265  auto pts_intrp =
266  interpolate_to_frustum_planes(frustum, pt_prev, mask_out_start.back(), pt, plane_mask);
267  if (pts_intrp.size() > 0) {
268  // If there are multiple points, sort them by distance to the previous point.
269  std::sort(pts_intrp.begin(), pts_intrp.end(),
270  [pt_prev](const Eigen::Vector3d& pt1, const Eigen::Vector3d& pt2) {
271  return ((pt1 - pt_prev).norm() < (pt2 - pt_prev).norm());
272  });
273  // Append to points inside frustum.
274  pts_frustum.insert(pts_frustum.end(), pts_intrp.begin(), pts_intrp.end());
275  // This point is outside the frustum towards the end of the lane boundary.
276  pts_out_end.push_back(pt);
277  mask_out_end.push_back(plane_mask);
278  } else {
279  // No special case.
280  pts_out_start.push_back(pt);
281  mask_out_start.push_back(plane_mask);
282  }
283  }
284  } else {
285  // Point is outside field of view and at least one point inside was found previously.
286  if (pts_out_end.size() == 0) {
287  // Interpolate additional point to the frustum boundary.
288  auto pt_intrp =
289  interpolate_to_frustum_planes(frustum, pts_frustum.back(), all_set, pt, plane_mask);
290  if (pt_intrp.size() == 1) {
291  pts_frustum.push_back(pt_intrp.front());
292  } else {
293  throw cloe::ModelError("Interpolation of last point inside frustum should be unique.");
294  }
295  }
296  pts_out_end.push_back(pt);
297  mask_out_end.push_back(plane_mask);
298  }
299  }
300  points = pts_frustum;
301 }
302 
309 double calc_heading_angle(const Eigen::Vector3d& pt0, const Eigen::Vector3d& pt1) {
310  double dx = pt1.x() - pt0.x();
311  dx = dx == 0.0 ? 1.0e-10 : dx;
312  double slope = (pt1.y() - pt0.y()) / dx;
313  return atan(slope);
314 }
315 
316 // https://repository.uantwerpen.be/docman/irua/fb388b/3959.pdf
317 double calc_heading_angle_adv(const Eigen::Vector3d& ptm1, const Eigen::Vector3d& pt0,
318  const Eigen::Vector3d& pt1) {
319  double dx1 = pt1.x() - pt0.x();
320  dx1 = dx1 == 0.0 ? 1.0e-10 : dx1;
321  double dx0 = pt0.x() - ptm1.x();
322  dx0 = dx0 == 0.0 ? 1.0e-10 : dx0;
323  double dx = dx1 + dx0;
324  dx = dx == 0.0 ? 1.0e-10 : dx;
325  double slope = -1.0 * dx1 / (dx0 * dx) * ptm1.y() + (dx1 - dx0) / (dx0 * dx1) * pt0.y() +
326  dx0 / (dx1 * dx) * pt1.y();
327  return atan(slope);
328 }
329 
337 bool fit_clothoid(const cloe::Logger& logger, bool frustum_culling, const Frustum& frustum,
338  LaneBoundary& lb) {
339  if (estimate_lane_boundary_length(lb.points) < 0.5) {
340  // Discard tiny lane boundary snippets.
341  logger->debug("Discarding short lane boundary segment < 0.5m.");
342  return false;
343  }
344  cleanup_lane_boundary_points(lb.points);
345  // Store discarded points for advanced heading angle estimation.
346  std::vector<Eigen::Vector3d> pts_out_start, pts_out_end;
347  if (frustum_culling) {
348  lane_boundary_point_culling(frustum, lb.points, pts_out_start, pts_out_end);
349  }
350  if (lb.points.size() < 2) {
351  logger->debug("Clothoid fit requires at least two points.");
352  return false;
353  }
354  Eigen::Vector3d x0 = lb.points.at(0);
355  lb.dx_start = x0.x();
356  lb.dy_start = x0.y();
357  double hdg0;
358  if (pts_out_start.size() > 0) {
359  hdg0 = calc_heading_angle_adv(pts_out_start.back(), lb.points.at(0), lb.points.at(1));
360  } else {
361  hdg0 = calc_heading_angle(lb.points.at(0), lb.points.at(1));
362  }
363  lb.heading_start = hdg0;
364  int n = lb.points.size() - 1;
365  Eigen::Vector3d x1 = lb.points.at(n);
366  double hdg1;
367  if (pts_out_end.size() > 0) {
368  hdg1 = calc_heading_angle_adv(lb.points.at(n - 1), lb.points.at(n), pts_out_end.front());
369  } else {
370  hdg1 = calc_heading_angle(lb.points.at(n - 1), lb.points.at(n));
371  }
372  // Compute clothoid parameters curv_hor_start, curv_hor_change and dx_end.
373  g1_fit::calc_clothoid(x0.x(), x0.y(), hdg0, x1.x(), x1.y(), hdg1, lb.curv_hor_start,
374  lb.curv_hor_change, lb.dx_end);
375 
376  return true;
377 }
378 
380  public:
381  LaneBoundaryClothoidFit(const std::string& name, const ClothoidFitConf& conf,
382  std::shared_ptr<LaneBoundarySensor> sensor)
383  : LaneBoundarySensor(name), config_(conf), sensor_in_(sensor) {}
384  virtual ~LaneBoundaryClothoidFit() noexcept = default;
385 
386  void enroll(Registrar& r) override {
387  r.register_action(std::make_unique<actions::ConfigureFactory>(
388  &this->config_, "config", "configure clothoid fitting component"));
390  "activation", "switch clothoid fitting on/off", "enable", &config_.enabled);
391  }
392 
393  const LaneBoundaries& sensed_lane_boundaries() const override {
394  if (cached_) {
395  return lbs_;
396  }
397  if (config_.enabled) {
398  for (auto& kv : sensor_in_->sensed_lane_boundaries()) {
399  auto lb = kv.second;
400  if (fit_clothoid(logger(), config_.frustum_culling, this->frustum(), lb)) {
401  lbs_[kv.first] = lb;
402  }
403  }
404  } else {
405  // Copy all lane boundaries from the source sensor component.
406  lbs_ = sensor_in_->sensed_lane_boundaries();
407  }
408  cached_ = true;
409  return lbs_;
410  }
411 
412  const Frustum& frustum() const override { return sensor_in_->frustum(); }
413 
414  const Eigen::Isometry3d& mount_pose() const override { return sensor_in_->mount_pose(); }
415 
422  Duration process(const Sync& sync) override {
423  // This currently shouldn't do anything, but this class acts as a prototype
424  // for How It Should Be Done.
426  if (t < sync.time()) {
427  return t;
428  }
429 
430  // Process the underlying sensor and clear the cache.
431  t = sensor_in_->process(sync);
432  time_ = t;
433  clear_cache();
434  return t;
435  }
436 
437  void reset() override {
439  sensor_in_->reset();
440  clear_cache();
441  }
442 
443  void abort() override {
445  sensor_in_->abort();
446  }
447 
448  protected:
449  void clear_cache() {
450  lbs_.clear();
451  cached_ = false;
452  }
453 
454  private:
455  ClothoidFitConf config_;
456  std::shared_ptr<LaneBoundarySensor> sensor_in_; // provides input data
457  mutable bool cached_;
458  mutable LaneBoundaries lbs_;
459  Duration time_{0};
460 };
461 
462 } // namespace component
463 } // namespace cloe
Duration process(const Sync &sync) override
Definition: component.hpp:181
void abort() override
Definition: component.hpp:191
void reset() override
Definition: component.hpp:186
virtual Logger logger() const
Definition: entity.hpp:101
const std::string & name() const
Definition: entity.hpp:67
Definition: lane_sensor.hpp:33
Definition: lane_boundary.hpp:36
Definition: model.hpp:62
Definition: registrar.hpp:116
virtual void register_action(std::unique_ptr< ActionFactory > &&)=0
Definition: sync.hpp:34
virtual Duration time() const =0
Definition: set_action.hpp:86
Definition: clothoid_fit.hpp:379
void enroll(Registrar &r) override
Definition: clothoid_fit.hpp:386
const LaneBoundaries & sensed_lane_boundaries() const override
Definition: clothoid_fit.hpp:393
void abort() override
Definition: clothoid_fit.hpp:443
const Eigen::Isometry3d & mount_pose() const override
Definition: clothoid_fit.hpp:414
const Frustum & frustum() const override
Definition: clothoid_fit.hpp:412
void reset() override
Definition: clothoid_fit.hpp:437
Duration process(const Sync &sync) override
Definition: clothoid_fit.hpp:422
Definition: confable.hpp:98
Definition: schema.hpp:173
std::chrono::nanoseconds Duration
Definition: cloe_fwd.hpp:36
double estimate_lane_boundary_length(const std::vector< Eigen::Vector3d > &points)
Definition: clothoid_fit.hpp:69
bool fit_clothoid(const cloe::Logger &logger, bool frustum_culling, const Frustum &frustum, LaneBoundary &lb)
Definition: clothoid_fit.hpp:337
double calc_heading_angle(const Eigen::Vector3d &pt0, const Eigen::Vector3d &pt1)
Definition: clothoid_fit.hpp:309
Definition: clothoid_fit.hpp:46
Definition: frustum.hpp:37