/home/runner/work/beluga/beluga/beluga_ros/include/beluga_ros/amcl.hpp Source File

/home/runner/work/beluga/beluga/beluga_ros/include/beluga_ros/amcl.hpp Source File#

Beluga ROS: /home/runner/work/beluga/beluga/beluga_ros/include/beluga_ros/amcl.hpp Source File
Beluga ROS
amcl.hpp
Go to the documentation of this file.
1 // Copyright 2024 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_ROS_AMCL_HPP
16 #define BELUGA_ROS_AMCL_HPP
17 
18 #include <optional>
19 #include <utility>
20 #include <variant>
21 
22 #include <range/v3/range/conversion.hpp>
23 #include <range/v3/view/take_exactly.hpp>
24 
25 #include <sophus/se2.hpp>
26 
28 #include <beluga/algorithm/thrun_recovery_probability_estimator.hpp>
29 #include <beluga/containers.hpp>
30 #include <beluga/motion.hpp>
31 #include <beluga/policies.hpp>
32 #include <beluga/random.hpp>
33 #include <beluga/sensor.hpp>
35 #include <beluga/sensor/primitives.hpp>
36 #include <beluga/views/sample.hpp>
37 
40 
46 namespace beluga_ros {
47 
49 struct AmclParams {
51  double update_min_d = 0.25;
52 
54  double update_min_a = 0.2;
55 
57  std::size_t resample_interval = 1UL;
58 
64  bool selective_resampling = false;
65 
67  std::size_t min_particles = 500UL;
68 
70  std::size_t max_particles = 2000UL;
71 
74  double alpha_slow = 0.001;
75 
78  double alpha_fast = 0.1;
79 
83  double kld_epsilon = 0.05;
84 
87  double kld_z = 3.0;
88 
90  double spatial_resolution_x = 0.5;
91 
93  double spatial_resolution_y = 0.5;
94 
96  double spatial_resolution_theta = 10 * Sophus::Constants<double>::pi() / 180;
97 };
98 
101 class Amcl {
102  public:
104  using particle_type = std::tuple<Sophus::SE2d, beluga::Weight>;
105 
107  using motion_model_variant = std::variant<
111 
113  using sensor_model_variant = std::variant<
117 
119  using execution_policy_variant = std::variant<std::execution::sequenced_policy, std::execution::parallel_policy>;
120 
122 
131  motion_model_variant motion_model,
132  sensor_model_variant sensor_model,
133  const AmclParams& params,
134  execution_policy_variant execution_policy);
135 
137  [[nodiscard]] const auto& particles() const { return particles_; }
138 
140  [[nodiscard]] const auto& likelihood_field() const {
141  std::optional<std::reference_wrapper<const beluga::ValueGrid2<float>>> result;
142 
143  std::visit(
144  [&result](const auto& sensor_model) {
145  using T = std::decay_t<decltype(sensor_model)>;
146  if constexpr (beluga::has_likelihood_field_v<T>) {
147  result = std::cref(sensor_model.likelihood_field());
148  }
149  },
150  sensor_model_);
151 
152  if (!result) {
153  throw std::runtime_error("The current sensor model does not support likelihood field");
154  }
155 
156  return result->get();
157  }
158 
160  [[nodiscard]] auto likelihood_field_origin() const {
161  std::optional<Sophus::SE2<double>> result;
162 
163  std::visit(
164  [&result](const auto& sensor_model) {
165  using T = std::decay_t<decltype(sensor_model)>;
166  if constexpr (beluga::has_likelihood_field_v<T>) {
167  result = sensor_model.likelihood_field_origin();
168  }
169  },
170  sensor_model_);
171 
172  if (!result) {
173  throw std::runtime_error("The current sensor model does not support likelihood field");
174  }
175 
176  return *result; // return by value
177  }
178 
180  [[nodiscard]] bool has_likelihood_field() const {
181  return std::visit(
182  [](const auto& sensor_model) {
183  using T = std::decay_t<decltype(sensor_model)>;
184  return beluga::has_likelihood_field_v<T>;
185  },
186  sensor_model_);
187  }
188 
190  template <class Distribution>
191  void initialize(Distribution distribution) {
192  particles_ = beluga::views::sample(std::move(distribution)) | //
193  ranges::views::transform(beluga::make_from_state<particle_type>) | //
194  ranges::views::take_exactly(params_.max_particles) | //
195  ranges::to<beluga::TupleVector>;
196  force_update_ = true;
197  }
198 
200 
203  void initialize(Sophus::SE2d pose, Sophus::Matrix3d covariance) {
205  }
206 
208  void initialize_from_map() { initialize(std::ref(map_distribution_)); }
209 
212 
214 
226  auto update(Sophus::SE2d base_pose_in_odom, beluga_ros::LaserScan laser_scan)
227  -> std::optional<std::pair<Sophus::SE2d, Sophus::Matrix3d>>;
228 
230  void force_update() { force_update_ = true; }
231 
232  private:
234 
235  AmclParams params_;
237  motion_model_variant motion_model_;
238  sensor_model_variant sensor_model_;
239  execution_policy_variant execution_policy_;
240 
241  beluga::spatial_hash<Sophus::SE2d> spatial_hasher_;
242  beluga::ThrunRecoveryProbabilityEstimator random_probability_estimator_;
243  beluga::any_policy<Sophus::SE2d> update_policy_;
244  beluga::any_policy<decltype(particles_)> resample_policy_;
245 
246  beluga::RollingWindow<Sophus::SE2d, 2> control_action_window_;
247 
248  bool force_update_{true};
249 };
250 
251 } // namespace beluga_ros
252 
253 #endif // BELUGA_ROS_AMCL_HPP
Definition: amcl.hpp:101
const auto & likelihood_field() const
Returns a reference to the current likelihood field.
Definition: amcl.hpp:140
void initialize_from_map()
Initialize particles using the default map distribution.
Definition: amcl.hpp:208
std::variant< beluga::DifferentialDriveModel2d, beluga::OmnidirectionalDriveModel, beluga::StationaryModel > motion_model_variant
Motion model variant type for runtime selection support.
Definition: amcl.hpp:110
std::variant< std::execution::sequenced_policy, std::execution::parallel_policy > execution_policy_variant
Execution policy variant type for runtime selection support.
Definition: amcl.hpp:119
void update_map(beluga_ros::OccupancyGrid map)
Update the map used for localization.
bool has_likelihood_field() const
Check if the sensor model bears a likelihood field.
Definition: amcl.hpp:180
auto likelihood_field_origin() const
Returns the current likelihood field origin transform.
Definition: amcl.hpp:160
const auto & particles() const
Returns a reference to the current set of particles.
Definition: amcl.hpp:137
std::tuple< Sophus::SE2d, beluga::Weight > particle_type
Weighted SE(2) state particle type.
Definition: amcl.hpp:104
void initialize(Sophus::SE2d pose, Sophus::Matrix3d covariance)
Initialize particles with a given pose and covariance.
Definition: amcl.hpp:203
void initialize(Distribution distribution)
Initialize particles using a custom distribution.
Definition: amcl.hpp:191
std::variant< beluga::LikelihoodFieldModel< beluga_ros::OccupancyGrid >, beluga::LikelihoodFieldProbModel< beluga_ros::OccupancyGrid >, beluga::BeamSensorModel< beluga_ros::OccupancyGrid > > sensor_model_variant
Sensor model variant type for runtime selection support.
Definition: amcl.hpp:116
auto update(Sophus::SE2d base_pose_in_odom, beluga_ros::LaserScan laser_scan) -> std::optional< std::pair< Sophus::SE2d, Sophus::Matrix3d >>
Update particles based on motion and sensor information.
Amcl(beluga_ros::OccupancyGrid map, motion_model_variant motion_model, sensor_model_variant sensor_model, const AmclParams &params, execution_policy_variant execution_policy)
Constructor.
void force_update()
Force a manual update of the particles on the next iteration of the filter.
Definition: amcl.hpp:230
Thin wrapper type for 2D sensor_msgs/LaserScan messages.
Definition: laser_scan.hpp:34
Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.
Definition: occupancy_grid.hpp:47
Implementation of sensor_msgs/LaserScan wrapper type.
The main Beluga ROS namespace.
Definition: amcl.hpp:46
constexpr detail::covariance_fn covariance
DifferentialDriveModel< Sophus::SE2d > DifferentialDriveModel2d
Implementation of nav_msgs/OccupancyGrid wrapper type.
Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation.
Definition: amcl.hpp:49
std::size_t max_particles
Maximum allowed number of particles.
Definition: amcl.hpp:70
std::size_t resample_interval
Number of filter updates required before resampling.
Definition: amcl.hpp:57
double kld_epsilon
Maximum particle filter population error between the true distribution and the estimated distribution...
Definition: amcl.hpp:83
double kld_z
Upper standard normal quantile for , where is the probability that the error in the estimated distri...
Definition: amcl.hpp:87
double alpha_fast
Exponential decay rate for the fast average weight filter, used in deciding when to recover from a ba...
Definition: amcl.hpp:78
double update_min_a
Rotational movement required from last resample for resampling to happen again.
Definition: amcl.hpp:54
double alpha_slow
Exponential decay rate for the slow average weight filter, used in deciding when to recover from a ba...
Definition: amcl.hpp:74
double spatial_resolution_theta
Spatial resolution around the z-axis to create buckets for KLD resampling.
Definition: amcl.hpp:96
double spatial_resolution_x
Spatial resolution along the x-axis to create buckets for KLD resampling.
Definition: amcl.hpp:90
std::size_t min_particles
Minimum allowed number of particles.
Definition: amcl.hpp:67
double spatial_resolution_y
Spatial resolution along the y-axis to create buckets for KLD resampling.
Definition: amcl.hpp:93
bool selective_resampling
Whether to enable selective resampling to help avoid loss of diversity in the particle population....
Definition: amcl.hpp:64
double update_min_d
Translational movement required from last resample for resampling to happen again.
Definition: amcl.hpp:51