landmark_map.hpp
Go to the documentation of this file.
1 // Copyright 2023 Ekumen, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef BELUGA_SENSOR_DATA_LANDMARK_MAP_HPP
16 #define BELUGA_SENSOR_DATA_LANDMARK_MAP_HPP
17 
18 // external
19 #include <range/v3/view/filter.hpp>
20 #include <sophus/se3.hpp>
21 
22 // standard library
23 #include <algorithm>
24 #include <cstdint>
25 #include <utility>
26 #include <vector>
27 
28 // project
30 
36 namespace beluga {
37 
39 class LandmarkMap {
40  public:
42  using landmarks_set_position_data = std::vector<LandmarkPositionDetection>;
45 
50  : landmarks_(std::move(landmarks)), map_boundaries_(std::move(boundaries)) {}
51 
54  [[nodiscard]] LandmarkMapBoundaries map_limits() const { return map_boundaries_; }
55 
60  [[nodiscard]] std::optional<LandmarkPosition3> find_nearest_landmark(
61  const LandmarkPosition3& detection_position_in_world,
62  const LandmarkCategory& detection_category) const {
63  // only consider those that have the same id
64  auto same_category_landmarks_view =
65  landmarks_ | ranges::views::filter([detection_category = detection_category](const auto& l) {
66  return detection_category == l.category;
67  });
68 
69  // find the landmark that minimizes the distance to the detection position
70  // This is O(n). A spatial data structure should be used instead.
71  auto min = std::min_element(
72  same_category_landmarks_view.begin(), same_category_landmarks_view.end(),
73  [&detection_position_in_world](const auto& a, const auto& b) {
74  const auto& landmark_a_position_in_world = a.detection_position_in_robot;
75  const auto& landmark_b_position_in_world = b.detection_position_in_robot;
76 
77  const auto landmark_b_squared_in_world_squared =
78  (landmark_a_position_in_world - detection_position_in_world).squaredNorm();
79  const auto landmark_b_distance_in_world_squared =
80  (landmark_b_position_in_world - detection_position_in_world).squaredNorm();
81  return landmark_b_squared_in_world_squared < landmark_b_distance_in_world_squared;
82  });
83 
84  if (min == same_category_landmarks_view.end()) {
85  return std::nullopt;
86  }
87 
88  return min->detection_position_in_robot;
89  }
90 
96  [[nodiscard]] std::optional<LandmarkBearing3> find_closest_bearing_landmark(
97  const LandmarkBearing3& detection_bearing_in_sensor,
98  const LandmarkCategory& detection_category,
99  const world_pose_type& sensor_pose_in_world) const {
100  // only consider those that have the same detection id (category)
101  auto same_category_landmarks_view =
102  landmarks_ | ranges::views::filter([detection_category = detection_category](const auto& l) {
103  return detection_category == l.category;
104  });
105 
106  // find the landmark that minimizes the bearing error
107  const auto world_in_sensor_transform = sensor_pose_in_world.inverse();
108 
109  // This whole search thing is very expensive, with objects getting created, normalized and
110  // destroyed multiple times and the same transformations being calculated over and over again.
111  // This will only work as a proof-of-concept, but it needs to be optimized for large numbers of
112  // landmarks.
113  const auto minimization_function = [&detection_bearing_in_sensor, &world_in_sensor_transform](
114  const auto& a, const auto& b) {
115  const auto& landmark_a_position_in_world = a.detection_position_in_robot;
116  const auto& landmark_b_position_in_world = b.detection_position_in_robot;
117 
118  // convert the landmark locations relative to the sensor frame
119  const auto landmark_a_bearing_in_sensor = (world_in_sensor_transform * landmark_a_position_in_world).normalized();
120  const auto landmark_b_bearing_in_sensor = (world_in_sensor_transform * landmark_b_position_in_world).normalized();
121 
122  // find the landmark that minimizes the bearing error by maximizing the dot product against the
123  // detection bearing vector
124  const auto dot_product_a = landmark_a_bearing_in_sensor.dot(detection_bearing_in_sensor);
125  const auto dot_product_b = landmark_b_bearing_in_sensor.dot(detection_bearing_in_sensor);
126 
127  return dot_product_a > dot_product_b;
128  };
129 
130  auto min = std::min_element(
131  same_category_landmarks_view.begin(), same_category_landmarks_view.end(), minimization_function);
132 
133  if (min == same_category_landmarks_view.end()) {
134  return std::nullopt;
135  }
136 
137  // find the normalized bearing vector to the landmark, relative to the sensor frame
138  const auto landmark_position_in_sensor = world_in_sensor_transform * min->detection_position_in_robot;
139  return landmark_position_in_sensor.normalized();
140  }
141 
142  private:
145 };
146 
147 } // namespace beluga
148 
149 #endif
beluga::LandmarkBearing3
Eigen::Vector3d LandmarkBearing3
Bearing of a landmark in the sensor reference frame.
Definition: landmark_detection_types.hpp:34
beluga::LandmarkMap::find_closest_bearing_landmark
std::optional< LandmarkBearing3 > find_closest_bearing_landmark(const LandmarkBearing3 &detection_bearing_in_sensor, const LandmarkCategory &detection_category, const world_pose_type &sensor_pose_in_world) const
Finds the landmark that minimizes the bearing error to a given detection and returns its data.
Definition: landmark_map.hpp:96
beluga::LandmarkMap::map_limits
LandmarkMapBoundaries map_limits() const
Returns the map boundaries.
Definition: landmark_map.hpp:54
beluga::LandmarkCategory
uint32_t LandmarkCategory
Type used to represent landmark categories.
Definition: landmark_detection_types.hpp:32
beluga::LandmarkMap::landmarks_set_position_data
std::vector< LandmarkPositionDetection > landmarks_set_position_data
Vector of landmarks.
Definition: landmark_map.hpp:42
beluga::LandmarkMap::LandmarkMap
LandmarkMap(const LandmarkMapBoundaries &boundaries, landmarks_set_position_data landmarks)
Constructor.
Definition: landmark_map.hpp:49
landmark_detection_types.hpp
Auxiliar types for landmark models.
beluga::LandmarkMap::find_nearest_landmark
std::optional< LandmarkPosition3 > find_nearest_landmark(const LandmarkPosition3 &detection_position_in_world, const LandmarkCategory &detection_category) const
Finds the nearest landmark to a given detection and returns it's data.
Definition: landmark_map.hpp:60
Sophus::SE3
beluga::LandmarkMap::map_boundaries_
LandmarkMapBoundaries map_boundaries_
Definition: landmark_map.hpp:144
beluga::LandmarkMap::landmarks_
landmarks_set_position_data landmarks_
Definition: landmark_map.hpp:143
beluga::LandmarkMap
Basic 3D landmark map datatype.
Definition: landmark_map.hpp:39
beluga::LandmarkPosition3
Eigen::Vector3d LandmarkPosition3
Position of a landmark in the world reference frame.
Definition: landmark_detection_types.hpp:33
std
Definition: circular_array.hpp:529
Sophus::SE3d
SE3< double > SE3d
beluga::LandmarkMapBoundaries
Eigen::AlignedBox3d LandmarkMapBoundaries
Boundaries of a landmark map.
Definition: landmark_detection_types.hpp:36
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21
se3.hpp


beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53