Go to the documentation of this file.
15 #ifndef BELUGA_ALGORITHM_AMCL_CORE_HPP
16 #define BELUGA_ALGORITHM_AMCL_CORE_HPP
20 #include <type_traits>
26 #include <range/v3/range/concepts.hpp>
27 #include <range/v3/view/any_view.hpp>
28 #include <range/v3/view/take_exactly.hpp>
76 class RandomStateGenerator,
78 class ParticleType = std::tuple<typename SensorModel::state_type, WeightT>,
79 class ExecutionPolicy = std::execution::sequenced_policy>
82 std::is_same_v<ExecutionPolicy, std::execution::parallel_policy> or
83 std::is_same_v<ExecutionPolicy, std::execution::sequenced_policy>);
88 using map_type =
typename SensorModel::map_type;
92 std::invoke_result_t<decltype(
beluga::estimate<std::vector<state_type>>), std::vector<state_type>>;
106 MotionModel motion_model,
107 SensorModel sensor_model,
108 RandomStateGenerator random_state_generator,
111 ExecutionPolicy execution_policy = std::execution::seq)
130 template <
class Distribution>
133 ranges::views::transform(beluga::make_from_state<particle_type>) |
135 ranges::to<beluga::TupleVector>;
144 template <
class CovarianceT>
184 if (random_state_probability > 0.0) {
209 if constexpr (std::is_invocable_v<random_state_generator_type>) {
237 #endif // BELUGA_ALGORITHM_AMCL_CORE_HPP
decltype(auto) get_random_state_generator() const
Gets a callable that will produce a random state.
std::invoke_result_t< decltype(beluga::estimate< std::vector< state_type > >), std::vector< state_type > > estimation_type
ParticleType particle_type
void force_update()
Force a manual update of the particles on the next iteration of the filter.
random_state_generator_type random_state_generator_
constexpr detail::every_n_fn every_n
Policy that triggers an action every N calls.
Amcl(MotionModel motion_model, SensorModel sensor_model, RandomStateGenerator random_state_generator, spatial_hasher_type spatial_hasher, const AmclParams ¶ms=AmclParams{}, ExecutionPolicy execution_policy=std::execution::seq)
Construct a AMCL instance.
Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation.
void initialize(state_type pose, CovarianceT covariance)
Initialize particles with a given pose and covariance.
bool selective_resampling
Whether to use selective resampling or not.
constexpr detail::assign_fn assign
constexpr detail::propagate_fn propagate
constexpr detail::reweight_fn reweight
ExecutionPolicy execution_policy_
typename SensorModel::map_type map_type
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.
std::size_t min_particles
Minimum number of particles in the filter at any point in time.
beluga::TupleVector< particle_type > particles_
std::size_t max_particles
Maximum number of particles in the filter at any point in time.
beluga::RollingWindow< state_type, 2 > control_action_window_
Includes all the Beluga API.
SensorModel sensor_model_
typename SensorModel::state_type state_type
MotionModel motion_model_
An implementation of generic, non-threadsafe circular array.
Numeric< double, struct WeightTag > Weight
Weight type, as a strongly typed double.
void update_map(map_type map)
Update the map used for localization.
Random particle probability estimator.
RandomStateGenerator random_state_generator_type
std::size_t resample_interval
Filter iterations interval at which a resampling will happen, unitless.
typename SensorModel::measurement_type measurement_type
double update_min_a
Min angular distance in radians between updates.
void initialize(Distribution distribution)
Initialize particles using a custom distribution.
constexpr ranges::actions::action_closure< detail::normalize_fn > normalize
auto update(state_type control_action, measurement_type measurement) -> std::optional< estimation_type >
Update particles based on motion and sensor information.
constexpr detail::random_intersperse_fn random_intersperse
Forward declaration of policy.
double alpha_fast
Used as part of the recovery mechanism when considering how many random particles to insert.
spatial_hasher_type spatial_hasher_
Multivariate normal distribution.
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.
double kld_epsilon
Used as part of the kld sampling mechanism.
beluga::any_policy< state_type > update_policy_
double alpha_slow
Used as part of the recovery mechanism when considering how many random particles to insert.
double kld_z
Used as part of the kld sampling mechanism.
constexpr detail::on_motion_fn on_motion
Policy that triggers an action based on motion.
beluga::ThrunRecoveryProbabilityEstimator random_probability_estimator_
beluga::any_policy< decltype(particles_)> resample_policy_
constexpr detail::take_while_kld_fn take_while_kld
const auto & particles() const
Returns a reference to the current set of particles.
constexpr void reset() noexcept
Reset the internal state of the estimator.
Implementation of the Adaptive Monte Carlo Localization (AMCL) algorithm.
double update_min_d
Min distance in meters between updates.
The main Beluga namespace.
constexpr ranges::views::view_closure< detail::sample_fn > sample
beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53