Go to the documentation of this file.
15 #ifndef BELUGA_ROS_AMCL_HPP
16 #define BELUGA_ROS_AMCL_HPP
26 #include <range/v3/view/take_exactly.hpp>
139 template <
class Distribution>
142 ranges::views::transform(beluga::make_from_state<particle_type>) |
144 ranges::to<beluga::TupleVector>;
162 std::visit([&](
auto& sensor_model) { sensor_model.update_map(std::move(map)); },
sensor_model_);
179 -> std::optional<std::pair<Sophus::SE2d, Sophus::Matrix3d>> {
189 auto measurement = laser_scan.points_in_cartesian_coordinates() |
190 ranges::views::transform([&laser_scan](
const auto& p) {
194 ranges::to<std::vector>;
197 [&,
this](
auto& policy,
auto& motion_model,
auto& sensor_model) {
208 auto random_state = ranges::compose(beluga::make_from_state<particle_type>, std::ref(
map_distribution_));
210 if (random_state_probability > 0.0) {
253 #endif // BELUGA_ROS_AMCL_HPP
Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.
double spatial_resolution_theta
Spatial resolution around the z-axis to create buckets for KLD resampling.
double update_min_d
Translational movement required from last resample for resampling to happen again.
std::tuple< Sophus::SE2d, beluga::Weight > particle_type
Weighted SE(2) state particle type.
std::variant< beluga::DifferentialDriveModel2d, beluga::OmnidirectionalDriveModel, beluga::StationaryModel > motion_model_variant
Motion model variant type for runtime selection support.
beluga::MultivariateUniformDistribution< Sophus::SE2d, beluga_ros::OccupancyGrid > map_distribution_
std::variant< std::execution::sequenced_policy, std::execution::parallel_policy > execution_policy_variant
Execution policy variant type for runtime selection support.
void initialize(Sophus::SE2d pose, Sophus::Matrix3d covariance)
Initialize particles with a given pose and covariance.
const auto & particles() const
Returns a reference to the current set of particles.
Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation.
double alpha_fast
Exponential decay rate for the fast average weight filter, used in deciding when to recover from a ba...
constexpr detail::every_n_fn every_n
beluga::ThrunRecoveryProbabilityEstimator random_probability_estimator_
constexpr detail::assign_fn assign
beluga::any_policy< Sophus::SE2d > update_policy_
constexpr detail::propagate_fn propagate
Matrix3< double > Matrix3d
constexpr detail::reweight_fn reweight
std::variant< beluga::LikelihoodFieldModel< beluga_ros::OccupancyGrid >, beluga::BeamSensorModel< beluga_ros::OccupancyGrid > > sensor_model_variant
Sensor model variant type for runtime selection support.
Amcl(beluga_ros::OccupancyGrid map, motion_model_variant motion_model, sensor_model_variant sensor_model, const AmclParams ¶ms=AmclParams(), execution_policy_variant execution_policy=std::execution::seq)
Constructor.
void force_update()
Force a manual update of the particles on the next iteration of the filter.
std::size_t max_particles
Maximum allowed number of particles.
std::size_t min_particles
Minimum allowed number of particles.
Vector3< double > Vector3d
double kld_z
Upper standard normal quantile for , where is the probability that the error in the estimated distri...
constexpr policy< detail::on_effective_size_drop_policy > on_effective_size_drop
DifferentialDriveModel< Sophus::SE2d > DifferentialDriveModel2d
beluga::spatial_hash< Sophus::SE2d > spatial_hasher_
double update_min_a
Rotational movement required from last resample for resampling to happen again.
void initialize_from_map()
Initialize particles using the default map distribution.
std::size_t resample_interval
Number of filter updates required before resampling.
bool selective_resampling
Whether to enable selective resampling to help avoid loss of diversity in the particle population....
Implementation of sensor_msgs/LaserScan wrapper type.
sensor_model_variant sensor_model_
Implementation of nav_msgs/OccupancyGrid wrapper type.
double kld_epsilon
Maximum particle filter population error between the true distribution and the estimated distribution...
void update_map(beluga_ros::OccupancyGrid map)
Update the map used for localization.
constexpr ranges::actions::action_closure< detail::normalize_fn > normalize
constexpr detail::random_intersperse_fn random_intersperse
motion_model_variant motion_model_
void initialize(Distribution distribution)
Initialize particles using a custom distribution.
Thin wrapper type for 2D sensor_msgs/LaserScan messages.
static SOPHUS_FUNC Scalar pi()
beluga::any_policy< decltype(particles_)> resample_policy_
beluga::TupleVector< particle_type > particles_
execution_policy_variant execution_policy_
double spatial_resolution_x
Spatial resolution along the x-axis to create buckets for KLD resampling.
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.
double alpha_slow
Exponential decay rate for the slow average weight filter, used in deciding when to recover from a ba...
constexpr detail::on_motion_fn on_motion
constexpr detail::take_while_kld_fn take_while_kld
constexpr void reset() noexcept
std::pair< Sophus::SE2< Scalar >, Sophus::Matrix3< Scalar > > estimate(Poses &&poses)
beluga::RollingWindow< Sophus::SE2d, 2 > control_action_window_
double spatial_resolution_y
Spatial resolution along the y-axis to create buckets for KLD resampling.
The main Beluga ROS namespace.
constexpr ranges::views::view_closure< detail::sample_fn > sample
beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02