|
void | force_path (const std::string &path) |
|
| AMCLLocalizer () |
| Default constructor.
|
|
nav_msgs::msg::Odometry | get_pose () |
| Gets the current estimated pose as an Odometry message.
|
|
tf2::Transform | getEstimatedPose () const |
| Gets the current estimated pose as a transform.
|
|
virtual std::expected< void, std::string > | on_initialize () override |
| Initializes the localization method.
|
|
void | update (NavState &nav_state) override |
| General update of the localization state.
|
|
void | update_rt (NavState &nav_state) override |
| Real-time update of the localization state.
|
|
| ~AMCLLocalizer () |
| Destructor.
|
|
|
void | correct (NavState &nav_state) |
| Applies the sensor model to update particle weights.
|
|
void | initializeParticles () |
| Initializes the set of particles.
|
|
void | odom_callback (nav_msgs::msg::Odometry::UniquePtr msg) |
| Callback for receiving odometry updates.
|
|
void | predict (NavState &nav_state) |
| Applies the motion model to update particle poses.
|
|
void | publishEstimatedPose (const tf2::Transform &est_pose) |
| Publishes the estimated pose with covariance.
|
|
void | publishParticles () |
| Publishes the current set of particles.
|
|
void | publishTF (const tf2::Transform &map2bf) |
| Publishes a TF transform between map and base footprint.
|
|
void | reseed () |
| Re-initializes the particle cloud if necessary.
|
|
rclcpp::Publisher< geometry_msgs::msg::PoseWithCovarianceStamped >::SharedPtr | estimate_pub_ |
| Publisher for the estimated robot pose with covariance.
|
|
bool | initialized_odom_ = false |
| Flag indicating if the odometry has been initialized.
|
|
tf2::Transform | last_odom_ {tf2::Transform::getIdentity()} |
| Previous odometry transform (used to compute deltas).
|
|
rclcpp::Time | last_reseed_ |
| Timestamp of the last reseed event.
|
|
double | min_noise_xy_ {0.05} |
| Minimum translation noise threshold.
|
|
double | min_noise_yaw_ {0.05} |
| Minimum yaw noise threshold.
|
|
double | noise_rotation_ {0.01} |
| Rotational noise standard deviation.
|
|
double | noise_translation_ {0.01} |
| Translational noise standard deviation.
|
|
double | noise_translation_to_rotation_ {0.01} |
| Coupling noise between translation and rotation.
|
|
tf2::Transform | odom_ {tf2::Transform::getIdentity()} |
| Last odometry transform received.
|
|
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr | odom_sub_ |
| Subscriber for odometry messages.
|
|
std::vector< Particle > | particles_ |
| List of particles representing the belief distribution.
|
|
rclcpp::Publisher< geometry_msgs::msg::PoseArray >::SharedPtr | particles_pub_ |
| Publisher for visualization of the particle cloud.
|
|
nav_msgs::msg::Odometry | pose_ |
| Current estimated odometry-based pose.
|
|
double | reseed_time_ |
| Time interval (in seconds) after which the particles should be reseeded.
|
|
std::default_random_engine | rng_ |
| Random number generator used for sampling noise.
|
|
std::unique_ptr< tf2_ros::TransformBroadcaster > | tf_broadcaster_ |
| TF broadcaster to publish map to base_footprint transform.
|
|