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 <beluga/beluga.hpp>
25 
26 #include <range/v3/view/take_exactly.hpp>
27 
33 namespace beluga_ros {
34 
36 struct AmclParams {
38  double update_min_d = 0.25;
39 
41  double update_min_a = 0.2;
42 
44  std::size_t resample_interval = 1UL;
45 
51  bool selective_resampling = false;
52 
54  std::size_t min_particles = 500UL;
55 
57  std::size_t max_particles = 2000UL;
58 
61  double alpha_slow = 0.001;
62 
65  double alpha_fast = 0.1;
66 
70  double kld_epsilon = 0.05;
71 
74  double kld_z = 3.0;
75 
77  double spatial_resolution_x = 0.5;
78 
80  double spatial_resolution_y = 0.5;
81 
84 };
85 
88 class Amcl {
89  public:
91  using particle_type = std::tuple<Sophus::SE2d, beluga::Weight>;
92 
94  using motion_model_variant = std::variant<
98 
100  using sensor_model_variant = std::variant<
103 
105  using execution_policy_variant = std::variant<std::execution::sequenced_policy, std::execution::parallel_policy>;
106 
108 
117  motion_model_variant motion_model,
118  sensor_model_variant sensor_model,
119  const AmclParams& params = AmclParams(),
120  execution_policy_variant execution_policy = std::execution::seq)
121  : params_{params},
122  map_distribution_{map},
123  motion_model_{std::move(motion_model)},
124  sensor_model_{std::move(sensor_model)},
125  execution_policy_{std::move(execution_policy)},
132  }
133  }
134 
136  [[nodiscard]] const auto& particles() const { return particles_; }
137 
139  template <class Distribution>
140  void initialize(Distribution distribution) {
141  particles_ = beluga::views::sample(std::move(distribution)) | //
142  ranges::views::transform(beluga::make_from_state<particle_type>) | //
143  ranges::views::take_exactly(params_.max_particles) | //
144  ranges::to<beluga::TupleVector>;
145  force_update_ = true;
146  }
147 
149 
152  void initialize(Sophus::SE2d pose, Sophus::Matrix3d covariance) {
154  }
155 
158 
162  std::visit([&](auto& sensor_model) { sensor_model.update_map(std::move(map)); }, sensor_model_);
163  }
164 
166 
178  auto update(Sophus::SE2d base_pose_in_odom, beluga_ros::LaserScan laser_scan)
179  -> std::optional<std::pair<Sophus::SE2d, Sophus::Matrix3d>> {
180  if (particles_.empty()) {
181  return std::nullopt;
182  }
183 
184  if (!update_policy_(base_pose_in_odom) && !force_update_) {
185  return std::nullopt;
186  }
187 
188  // TODO(nahuel): Remove this once we update the measurement type.
189  auto measurement = laser_scan.points_in_cartesian_coordinates() | //
190  ranges::views::transform([&laser_scan](const auto& p) {
191  const auto result = laser_scan.origin() * Sophus::Vector3d{p.x(), p.y(), 0};
192  return std::make_pair(result.x(), result.y());
193  }) |
194  ranges::to<std::vector>;
195 
196  std::visit(
197  [&, this](auto& policy, auto& motion_model, auto& sensor_model) {
198  particles_ |=
199  beluga::actions::propagate(policy, motion_model(control_action_window_ << base_pose_in_odom)) | //
200  beluga::actions::reweight(policy, sensor_model(std::move(measurement))) | //
202  },
204 
205  const double random_state_probability = random_probability_estimator_(particles_);
206 
208  auto random_state = ranges::compose(beluga::make_from_state<particle_type>, std::ref(map_distribution_));
209 
210  if (random_state_probability > 0.0) {
212  }
213 
215  beluga::views::random_intersperse(std::move(random_state), random_state_probability) |
217  spatial_hasher_, //
220  params_.kld_epsilon, //
221  params_.kld_z) |
223  }
224 
225  force_update_ = false;
227  }
228 
230  void force_update() { force_update_ = true; }
231 
232  private:
234 
240 
245 
247 
248  bool force_update_{true};
249 };
250 
251 } // namespace beluga_ros
252 
253 #endif // BELUGA_ROS_AMCL_HPP
result
result[0]
beluga_ros::OccupancyGrid
Thin wrapper type for 2D nav_msgs/OccupancyGrid messages.
Definition: occupancy_grid.hpp:47
beluga_ros::AmclParams::spatial_resolution_theta
double spatial_resolution_theta
Spatial resolution around the z-axis to create buckets for KLD resampling.
Definition: amcl.hpp:83
beluga_ros::AmclParams::update_min_d
double update_min_d
Translational movement required from last resample for resampling to happen again.
Definition: amcl.hpp:38
beluga_ros::Amcl::particle_type
std::tuple< Sophus::SE2d, beluga::Weight > particle_type
Weighted SE(2) state particle type.
Definition: amcl.hpp:91
beluga_ros::Amcl::motion_model_variant
std::variant< beluga::DifferentialDriveModel2d, beluga::OmnidirectionalDriveModel, beluga::StationaryModel > motion_model_variant
Motion model variant type for runtime selection support.
Definition: amcl.hpp:97
beluga_ros::Amcl::map_distribution_
beluga::MultivariateUniformDistribution< Sophus::SE2d, beluga_ros::OccupancyGrid > map_distribution_
Definition: amcl.hpp:236
beluga_ros::Amcl::execution_policy_variant
std::variant< std::execution::sequenced_policy, std::execution::parallel_policy > execution_policy_variant
Execution policy variant type for runtime selection support.
Definition: amcl.hpp:105
beluga_ros::Amcl::initialize
void initialize(Sophus::SE2d pose, Sophus::Matrix3d covariance)
Initialize particles with a given pose and covariance.
Definition: amcl.hpp:152
beluga_ros::Amcl::particles
const auto & particles() const
Returns a reference to the current set of particles.
Definition: amcl.hpp:136
beluga_ros::Amcl::params_
AmclParams params_
Definition: amcl.hpp:235
beluga_ros::AmclParams
Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation.
Definition: amcl.hpp:36
beluga_ros::AmclParams::alpha_fast
double alpha_fast
Exponential decay rate for the fast average weight filter, used in deciding when to recover from a ba...
Definition: amcl.hpp:65
beluga::policies::every_n
constexpr detail::every_n_fn every_n
beluga_ros::Amcl::random_probability_estimator_
beluga::ThrunRecoveryProbabilityEstimator random_probability_estimator_
Definition: amcl.hpp:242
beluga::actions::assign
constexpr detail::assign_fn assign
beluga.hpp
beluga_ros::Amcl::update_policy_
beluga::any_policy< Sophus::SE2d > update_policy_
Definition: amcl.hpp:243
beluga::actions::propagate
constexpr detail::propagate_fn propagate
Sophus::Matrix3d
Matrix3< double > Matrix3d
beluga::actions::reweight
constexpr detail::reweight_fn reweight
beluga_ros::Amcl::sensor_model_variant
std::variant< beluga::LikelihoodFieldModel< beluga_ros::OccupancyGrid >, beluga::BeamSensorModel< beluga_ros::OccupancyGrid > > sensor_model_variant
Sensor model variant type for runtime selection support.
Definition: amcl.hpp:102
beluga::TupleVector
beluga_ros::Amcl::Amcl
Amcl(beluga_ros::OccupancyGrid map, motion_model_variant motion_model, sensor_model_variant sensor_model, const AmclParams &params=AmclParams(), execution_policy_variant execution_policy=std::execution::seq)
Constructor.
Definition: amcl.hpp:115
beluga_ros::Amcl::force_update
void force_update()
Force a manual update of the particles on the next iteration of the filter.
Definition: amcl.hpp:230
beluga_ros::AmclParams::max_particles
std::size_t max_particles
Maximum allowed number of particles.
Definition: amcl.hpp:57
beluga_ros::AmclParams::min_particles
std::size_t min_particles
Minimum allowed number of particles.
Definition: amcl.hpp:54
Sophus::Vector3d
Vector3< double > Vector3d
beluga_ros::AmclParams::kld_z
double kld_z
Upper standard normal quantile for , where is the probability that the error in the estimated distri...
Definition: amcl.hpp:74
beluga::policies::on_effective_size_drop
constexpr policy< detail::on_effective_size_drop_policy > on_effective_size_drop
beluga::DifferentialDriveModel2d
DifferentialDriveModel< Sophus::SE2d > DifferentialDriveModel2d
beluga_ros::Amcl::spatial_hasher_
beluga::spatial_hash< Sophus::SE2d > spatial_hasher_
Definition: amcl.hpp:241
beluga_ros::AmclParams::update_min_a
double update_min_a
Rotational movement required from last resample for resampling to happen again.
Definition: amcl.hpp:41
beluga::LikelihoodFieldModel
beluga_ros::Amcl::initialize_from_map
void initialize_from_map()
Initialize particles using the default map distribution.
Definition: amcl.hpp:157
beluga::CircularArray
beluga_ros::AmclParams::resample_interval
std::size_t resample_interval
Number of filter updates required before resampling.
Definition: amcl.hpp:44
Sophus::SE2
beluga::ThrunRecoveryProbabilityEstimator
beluga::spatial_hash
beluga_ros::AmclParams::selective_resampling
bool selective_resampling
Whether to enable selective resampling to help avoid loss of diversity in the particle population....
Definition: amcl.hpp:51
laser_scan.hpp
Implementation of sensor_msgs/LaserScan wrapper type.
beluga_ros::Amcl::sensor_model_
sensor_model_variant sensor_model_
Definition: amcl.hpp:238
occupancy_grid.hpp
Implementation of nav_msgs/OccupancyGrid wrapper type.
beluga_ros::AmclParams::kld_epsilon
double kld_epsilon
Maximum particle filter population error between the true distribution and the estimated distribution...
Definition: amcl.hpp:70
beluga_ros::Amcl::update_map
void update_map(beluga_ros::OccupancyGrid map)
Update the map used for localization.
Definition: amcl.hpp:160
beluga_ros::Amcl
Definition: amcl.hpp:88
beluga::actions::normalize
constexpr ranges::actions::action_closure< detail::normalize_fn > normalize
beluga::views::random_intersperse
constexpr detail::random_intersperse_fn random_intersperse
beluga_ros::Amcl::motion_model_
motion_model_variant motion_model_
Definition: amcl.hpp:237
beluga::OmnidirectionalDriveModel
beluga_ros::Amcl::initialize
void initialize(Distribution distribution)
Initialize particles using a custom distribution.
Definition: amcl.hpp:140
beluga::policy
beluga_ros::LaserScan
Thin wrapper type for 2D sensor_msgs/LaserScan messages.
Definition: laser_scan.hpp:34
Sophus::Constants::pi
static SOPHUS_FUNC Scalar pi()
beluga::MultivariateNormalDistribution
beluga_ros::Amcl::resample_policy_
beluga::any_policy< decltype(particles_)> resample_policy_
Definition: amcl.hpp:244
beluga_ros::Amcl::force_update_
bool force_update_
Definition: amcl.hpp:248
beluga_ros::Amcl::particles_
beluga::TupleVector< particle_type > particles_
Definition: amcl.hpp:233
beluga_ros::Amcl::execution_policy_
execution_policy_variant execution_policy_
Definition: amcl.hpp:239
beluga::views::weights
constexpr auto weights
beluga_ros::AmclParams::spatial_resolution_x
double spatial_resolution_x
Spatial resolution along the x-axis to create buckets for KLD resampling.
Definition: amcl.hpp:77
beluga::BeamSensorModel
beluga_ros::Amcl::update
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.
Definition: amcl.hpp:178
beluga_ros::AmclParams::alpha_slow
double alpha_slow
Exponential decay rate for the slow average weight filter, used in deciding when to recover from a ba...
Definition: amcl.hpp:61
beluga::StationaryModel
beluga::policies::on_motion
constexpr detail::on_motion_fn on_motion
beluga::MultivariateUniformDistribution
beluga::views::take_while_kld
constexpr detail::take_while_kld_fn take_while_kld
beluga::ThrunRecoveryProbabilityEstimator::reset
constexpr void reset() noexcept
beluga::estimate
std::pair< Sophus::SE2< Scalar >, Sophus::Matrix3< Scalar > > estimate(Poses &&poses)
beluga_ros::Amcl::control_action_window_
beluga::RollingWindow< Sophus::SE2d, 2 > control_action_window_
Definition: amcl.hpp:246
beluga_ros::AmclParams::spatial_resolution_y
double spatial_resolution_y
Spatial resolution along the y-axis to create buckets for KLD resampling.
Definition: amcl.hpp:80
beluga_ros
The main Beluga ROS namespace.
Definition: amcl.hpp:33
beluga::views::states
constexpr auto states
beluga::views::sample
constexpr ranges::views::view_closure< detail::sample_fn > sample


beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02