amcl_core.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_ALGORITHM_AMCL_CORE_HPP
16 #define BELUGA_ALGORITHM_AMCL_CORE_HPP
17 
18 #include <execution>
19 #include <optional>
20 #include <type_traits>
21 #include <utility>
22 #include <vector>
23 
24 #include <beluga/beluga.hpp>
25 
26 #include <range/v3/range/concepts.hpp>
27 #include <range/v3/view/any_view.hpp>
28 #include <range/v3/view/take_exactly.hpp>
29 
30 namespace beluga {
31 
33 struct AmclParams {
35  double update_min_d = 0.25;
37  double update_min_a = 0.2;
39  std::size_t resample_interval = 1UL;
41  bool selective_resampling = false;
43  std::size_t min_particles = 500UL;
45  std::size_t max_particles = 2000UL;
47  double alpha_slow = 0.001;
49  double alpha_fast = 0.1;
51  double kld_epsilon = 0.05;
53  double kld_z = 3.0;
54 };
55 
57 
73 template <
74  class MotionModel,
75  class SensorModel,
76  class RandomStateGenerator,
77  typename WeightT = beluga::Weight,
78  class ParticleType = std::tuple<typename SensorModel::state_type, WeightT>,
79  class ExecutionPolicy = std::execution::sequenced_policy>
80 class Amcl {
81  static_assert(
82  std::is_same_v<ExecutionPolicy, std::execution::parallel_policy> or
83  std::is_same_v<ExecutionPolicy, std::execution::sequenced_policy>);
84 
85  using particle_type = ParticleType;
86  using measurement_type = typename SensorModel::measurement_type;
87  using state_type = typename SensorModel::state_type;
88  using map_type = typename SensorModel::map_type;
90  using random_state_generator_type = RandomStateGenerator;
91  using estimation_type =
92  std::invoke_result_t<decltype(beluga::estimate<std::vector<state_type>>), std::vector<state_type>>;
93 
94  public:
96 
106  MotionModel motion_model,
107  SensorModel sensor_model,
108  RandomStateGenerator random_state_generator,
109  spatial_hasher_type spatial_hasher,
110  const AmclParams& params = AmclParams{},
111  ExecutionPolicy execution_policy = std::execution::seq)
112  : params_{params},
113  motion_model_{std::move(motion_model)},
114  sensor_model_{std::move(sensor_model)},
115  execution_policy_{std::move(execution_policy)},
116  spatial_hasher_{std::move(spatial_hasher)},
120  random_state_generator_(std::move(random_state_generator)) {
123  }
124  }
125 
127  [[nodiscard]] const auto& particles() const { return particles_; }
128 
130  template <class Distribution>
131  void initialize(Distribution distribution) {
132  particles_ = beluga::views::sample(std::move(distribution)) | //
133  ranges::views::transform(beluga::make_from_state<particle_type>) | //
134  ranges::views::take_exactly(params_.max_particles) | //
135  ranges::to<beluga::TupleVector>;
136  force_update_ = true;
137  }
138 
140 
144  template <class CovarianceT>
145  void initialize(state_type pose, CovarianceT covariance) {
147  }
148 
150  void update_map(map_type map) { sensor_model_.update_map(std::move(map)); }
151 
153 
165  auto update(state_type control_action, measurement_type measurement) -> std::optional<estimation_type> {
166  if (particles_.empty()) {
167  return std::nullopt;
168  }
169 
170  if (!update_policy_(control_action) && !force_update_) {
171  return std::nullopt;
172  }
173 
175  execution_policy_, motion_model_(control_action_window_ << std::move(control_action))) | //
176  beluga::actions::reweight(execution_policy_, sensor_model_(std::move(measurement))) | //
178 
179  const double random_state_probability = random_probability_estimator_(particles_);
180 
182  auto random_state = ranges::compose(beluga::make_from_state<particle_type>, get_random_state_generator());
183 
184  if (random_state_probability > 0.0) {
186  }
187 
189  beluga::views::random_intersperse(std::move(random_state), random_state_probability) |
191  spatial_hasher_, //
194  params_.kld_epsilon, //
195  params_.kld_z) |
197  }
198 
199  force_update_ = false;
201  }
202 
204  void force_update() { force_update_ = true; }
205 
206  private:
208  [[nodiscard]] decltype(auto) get_random_state_generator() const {
209  if constexpr (std::is_invocable_v<random_state_generator_type>) {
211  } else {
213  }
214  }
216 
218 
219  MotionModel motion_model_;
220  SensorModel sensor_model_;
221  ExecutionPolicy execution_policy_;
222 
227 
229 
231 
232  bool force_update_{true};
233 };
234 
235 } // namespace beluga
236 
237 #endif // BELUGA_ALGORITHM_AMCL_CORE_HPP
beluga::Amcl::get_random_state_generator
decltype(auto) get_random_state_generator() const
Gets a callable that will produce a random state.
Definition: amcl_core.hpp:208
beluga::Amcl::estimation_type
std::invoke_result_t< decltype(beluga::estimate< std::vector< state_type > >), std::vector< state_type > > estimation_type
Definition: amcl_core.hpp:92
beluga::Amcl::particle_type
ParticleType particle_type
Definition: amcl_core.hpp:85
beluga::Amcl::force_update
void force_update()
Force a manual update of the particles on the next iteration of the filter.
Definition: amcl_core.hpp:204
beluga::Amcl::random_state_generator_
random_state_generator_type random_state_generator_
Definition: amcl_core.hpp:228
beluga::policies::every_n
constexpr detail::every_n_fn every_n
Policy that triggers an action every N calls.
Definition: every_n.hpp:70
beluga::Amcl::Amcl
Amcl(MotionModel motion_model, SensorModel sensor_model, RandomStateGenerator random_state_generator, spatial_hasher_type spatial_hasher, const AmclParams &params=AmclParams{}, ExecutionPolicy execution_policy=std::execution::seq)
Construct a AMCL instance.
Definition: amcl_core.hpp:105
beluga::AmclParams
Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation.
Definition: amcl_core.hpp:33
beluga::Amcl::initialize
void initialize(state_type pose, CovarianceT covariance)
Initialize particles with a given pose and covariance.
Definition: amcl_core.hpp:145
beluga::AmclParams::selective_resampling
bool selective_resampling
Whether to use selective resampling or not.
Definition: amcl_core.hpp:41
beluga::actions::assign
constexpr detail::assign_fn assign
Definition: assign.hpp:99
beluga::Amcl::params_
AmclParams params_
Definition: amcl_core.hpp:217
beluga::actions::propagate
constexpr detail::propagate_fn propagate
Definition: propagate.hpp:131
beluga::actions::reweight
constexpr detail::reweight_fn reweight
Definition: reweight.hpp:115
beluga::TupleVector< particle_type >
beluga::Amcl::force_update_
bool force_update_
Definition: amcl_core.hpp:232
beluga::Amcl::execution_policy_
ExecutionPolicy execution_policy_
Definition: amcl_core.hpp:221
beluga::Amcl::map_type
typename SensorModel::map_type map_type
Definition: amcl_core.hpp:88
beluga::policies::on_effective_size_drop
constexpr policy< detail::on_effective_size_drop_policy > on_effective_size_drop
Policy that can be used to trigger an action based on the Effective Sample Size (ESS) metric.
Definition: on_effective_size_drop.hpp:64
beluga::AmclParams::min_particles
std::size_t min_particles
Minimum number of particles in the filter at any point in time.
Definition: amcl_core.hpp:43
beluga::Amcl::particles_
beluga::TupleVector< particle_type > particles_
Definition: amcl_core.hpp:215
beluga::AmclParams::max_particles
std::size_t max_particles
Maximum number of particles in the filter at any point in time.
Definition: amcl_core.hpp:45
beluga::Amcl::control_action_window_
beluga::RollingWindow< state_type, 2 > control_action_window_
Definition: amcl_core.hpp:230
beluga.hpp
Includes all the Beluga API.
beluga::Amcl::sensor_model_
SensorModel sensor_model_
Definition: amcl_core.hpp:220
beluga::Amcl::state_type
typename SensorModel::state_type state_type
Definition: amcl_core.hpp:87
beluga::Amcl::motion_model_
MotionModel motion_model_
Definition: amcl_core.hpp:219
beluga::CircularArray
An implementation of generic, non-threadsafe circular array.
Definition: circular_array.hpp:76
beluga::Weight
Numeric< double, struct WeightTag > Weight
Weight type, as a strongly typed double.
Definition: primitives.hpp:56
beluga::Amcl::update_map
void update_map(map_type map)
Update the map used for localization.
Definition: amcl_core.hpp:150
beluga::ThrunRecoveryProbabilityEstimator
Random particle probability estimator.
Definition: thrun_recovery_probability_estimator.hpp:38
beluga::Amcl::random_state_generator_type
RandomStateGenerator random_state_generator_type
Definition: amcl_core.hpp:90
beluga::spatial_hash< state_type >
beluga::AmclParams::resample_interval
std::size_t resample_interval
Filter iterations interval at which a resampling will happen, unitless.
Definition: amcl_core.hpp:39
beluga::Amcl::measurement_type
typename SensorModel::measurement_type measurement_type
Definition: amcl_core.hpp:86
beluga::AmclParams::update_min_a
double update_min_a
Min angular distance in radians between updates.
Definition: amcl_core.hpp:37
beluga::Amcl::initialize
void initialize(Distribution distribution)
Initialize particles using a custom distribution.
Definition: amcl_core.hpp:131
beluga::actions::normalize
constexpr ranges::actions::action_closure< detail::normalize_fn > normalize
Definition: normalize.hpp:162
beluga::Amcl::update
auto update(state_type control_action, measurement_type measurement) -> std::optional< estimation_type >
Update particles based on motion and sensor information.
Definition: amcl_core.hpp:165
beluga::views::random_intersperse
constexpr detail::random_intersperse_fn random_intersperse
Definition: random_intersperse.hpp:190
beluga::policy
Forward declaration of policy.
Definition: policy.hpp:24
beluga::AmclParams::alpha_fast
double alpha_fast
Used as part of the recovery mechanism when considering how many random particles to insert.
Definition: amcl_core.hpp:49
beluga::Amcl::spatial_hasher_
spatial_hasher_type spatial_hasher_
Definition: amcl_core.hpp:223
beluga::MultivariateNormalDistribution
Multivariate normal distribution.
Definition: multivariate_normal_distribution.hpp:137
beluga::estimate
std::pair< Sophus::SE2< Scalar >, Sophus::Matrix3< Scalar > > estimate(Poses &&poses, Weights &&weights)
Returns a pair consisting of the estimated mean pose and its covariance.
Definition: estimation.hpp:129
beluga::AmclParams::kld_epsilon
double kld_epsilon
Used as part of the kld sampling mechanism.
Definition: amcl_core.hpp:51
beluga::views::weights
constexpr auto weights
Definition: particles.hpp:34
beluga::Amcl::update_policy_
beluga::any_policy< state_type > update_policy_
Definition: amcl_core.hpp:225
beluga::AmclParams::alpha_slow
double alpha_slow
Used as part of the recovery mechanism when considering how many random particles to insert.
Definition: amcl_core.hpp:47
beluga::AmclParams::kld_z
double kld_z
Used as part of the kld sampling mechanism.
Definition: amcl_core.hpp:53
beluga::policies::on_motion
constexpr detail::on_motion_fn on_motion
Policy that triggers an action based on motion.
Definition: on_motion.hpp:121
beluga::Amcl::random_probability_estimator_
beluga::ThrunRecoveryProbabilityEstimator random_probability_estimator_
Definition: amcl_core.hpp:224
beluga::Amcl::resample_policy_
beluga::any_policy< decltype(particles_)> resample_policy_
Definition: amcl_core.hpp:226
beluga::views::take_while_kld
constexpr detail::take_while_kld_fn take_while_kld
Definition: take_while_kld.hpp:170
beluga::Amcl::particles
const auto & particles() const
Returns a reference to the current set of particles.
Definition: amcl_core.hpp:127
beluga::ThrunRecoveryProbabilityEstimator::reset
constexpr void reset() noexcept
Reset the internal state of the estimator.
Definition: thrun_recovery_probability_estimator.hpp:56
beluga::Amcl
Implementation of the Adaptive Monte Carlo Localization (AMCL) algorithm.
Definition: amcl_core.hpp:80
beluga::views::states
constexpr auto states
Definition: particles.hpp:30
beluga::AmclParams::update_min_d
double update_min_d
Min distance in meters between updates.
Definition: amcl_core.hpp:35
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21
beluga::views::sample
constexpr ranges::views::view_closure< detail::sample_fn > sample
Definition: sample.hpp:240


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