19#ifndef EASYNAV_SIMPLE_LOCALIZER__AMCLLOCALIZER_HPP_
20#define EASYNAV_SIMPLE_LOCALIZER__AMCLLOCALIZER_HPP_
24#include <Eigen/Geometry>
26#include "geometry_msgs/msg/pose_array.hpp"
27#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
28#include "nav_msgs/msg/odometry.hpp"
30#include "tf2/LinearMath/Transform.hpp"
31#include "tf2_ros/transform_broadcaster.hpp"
33#include "easynav_core/LocalizerMethodBase.hpp"
86 void update(NavState & nav_state)
override;
150 rclcpp::Publisher<geometry_msgs::msg::PoseArray>::SharedPtr
particles_pub_;
153 rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
estimate_pub_;
156 rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr
odom_sub_;
169 std::default_random_engine
rng_;
172 nav_msgs::msg::Odometry
pose_;
190 tf2::Transform
odom_{tf2::Transform::getIdentity()};
193 tf2::Transform
last_odom_{tf2::Transform::getIdentity()};
A localization method implementing a simplified AMCL (Adaptive Monte Carlo Localization) approach.
Definition AMCLLocalizer.hpp:49
double min_noise_yaw_
Minimum yaw noise threshold.
Definition AMCLLocalizer.hpp:204
virtual void on_initialize() override
Initializes the localization method.
std::unique_ptr< tf2_ros::TransformBroadcaster > tf_broadcaster_
TF broadcaster to publish map to base_footprint transform.
Definition AMCLLocalizer.hpp:147
void update(NavState &nav_state) override
General update of the localization state.
double min_noise_xy_
Minimum translation noise threshold.
Definition AMCLLocalizer.hpp:201
nav_msgs::msg::Odometry pose_
Current estimated odometry-based pose.
Definition AMCLLocalizer.hpp:189
~AMCLLocalizer()
Destructor.
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odom_sub_
Subscriber for odometry messages.
Definition AMCLLocalizer.hpp:156
rclcpp::Publisher< geometry_msgs::msg::PoseArray >::SharedPtr particles_pub_
Publisher for visualization of the particle cloud.
Definition AMCLLocalizer.hpp:150
rclcpp::Time last_reseed_
Timestamp of the last reseed event.
Definition AMCLLocalizer.hpp:225
double reseed_time_
Time interval (in seconds) after which the particles should be reseeded.
Definition AMCLLocalizer.hpp:219
void update_rt(NavState &nav_state) override
Real-time update of the localization state.
void publishEstimatedPose(const tf2::Transform &est_pose)
Publishes the estimated pose with covariance.
rclcpp::Time last_input_time_
Timestamp of the last input message (odometry or initial pose).
Definition AMCLLocalizer.hpp:222
double noise_translation_to_rotation_
Coupling noise between translation and rotation.
Definition AMCLLocalizer.hpp:198
void publishTF(const tf2::Transform &map2bf)
Publishes a TF transform between map and base footprint.
void odom_callback(nav_msgs::msg::Odometry::UniquePtr msg)
Callback for receiving odometry updates.
tf2::Transform odom_
Last odometry transform received.
Definition AMCLLocalizer.hpp:210
tf2::Transform last_odom_
Previous odometry transform (used to compute deltas).
Definition AMCLLocalizer.hpp:213
void predict(NavState &nav_state)
Applies the motion model to update particle poses.
nav_msgs::msg::Odometry get_pose()
Gets the current estimated pose as an Odometry message.
double noise_rotation_
Rotational noise standard deviation.
Definition AMCLLocalizer.hpp:195
std::mt19937 rng_
Random number generator used for sampling noise.
Definition AMCLLocalizer.hpp:186
void publishParticles()
Publishes the current set of particles.
rclcpp::Publisher< geometry_msgs::msg::PoseWithCovarianceStamped >::SharedPtr estimate_pub_
Publisher for the estimated robot pose with covariance.
Definition AMCLLocalizer.hpp:153
tf2::Transform getEstimatedPose() const
Gets the current estimated pose as a transform.
double noise_translation_
Translational noise standard deviation.
Definition AMCLLocalizer.hpp:192
bool initialized_odom_
Flag indicating if the odometry has been initialized.
Definition AMCLLocalizer.hpp:216
void reseed()
Re-initializes the particle cloud if necessary.
void correct(NavState &nav_state)
Applies the sensor model to update particle weights.
AMCLLocalizer()
Default constructor.
std::vector< Particle > particles_
List of particles representing the belief distribution.
Definition AMCLLocalizer.hpp:183
void initializeParticles()
Initializes the set of particles.
Provides a mapping for often used cost values.
Definition cost_values.hpp:41
Structure representing a single particle in the AMCL algorithm.
Definition AMCLLocalizer.hpp:40
int hits
Number of sensor matches (hits) for this particle.
Definition AMCLLocalizer.hpp:42
double weight
Normalized importance weight of the particle.
Definition AMCLLocalizer.hpp:44
int possible_hits
Maximum number of possible hits.
Definition AMCLLocalizer.hpp:43
tf2::Transform pose
Estimated pose of the particle.
Definition AMCLLocalizer.hpp:41