/home/runner/work/beluga/beluga/beluga_amcl/include/beluga_amcl/ndt_amcl_node.hpp File Reference

/home/runner/work/beluga/beluga/beluga_amcl/include/beluga_amcl/ndt_amcl_node.hpp File Reference#

Beluga AMCL: /home/runner/work/beluga/beluga/beluga_amcl/include/beluga_amcl/ndt_amcl_node.hpp File Reference
Beluga AMCL
ndt_amcl_node.hpp File Reference

ROS 2 integration of the 2D NDT-AMCL algorithm. More...

#include <tf2_ros/buffer.h>
#include <tf2_ros/message_filter.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
#include <beluga/beluga.hpp>
#include <beluga/motion/differential_drive_model.hpp>
#include <beluga/motion/omnidirectional_drive_model.hpp>
#include <beluga/motion/stationary_model.hpp>
#include <beluga/primitives.hpp>
#include <beluga/sensor/data/ndt_cell.hpp>
#include <beluga/sensor/data/sparse_value_grid.hpp>
#include <beluga/sensor/ndt_sensor_model.hpp>
#include <execution>
#include <functional>
#include <optional>
#include <rclcpp/callback_group.hpp>
#include <rclcpp/subscription_options.hpp>
#include <sophus/se2.hpp>
#include <tuple>
#include <variant>
#include <Eigen/src/Core/Matrix.h>
#include <H5Cpp.h>
#include <beluga/algorithm/amcl_core.hpp>
#include <bondcpp/bond.hpp>
#include <geometry_msgs/msg/pose_array.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
#include <std_srvs/srv/empty.hpp>
#include <beluga_ros/laser_scan.hpp>
#include "beluga_amcl/ros2_common.hpp"
#include <message_filters/subscriber.h>
Include dependency graph for ndt_amcl_node.hpp:

Go to the source code of this file.

Classes

class  beluga_amcl::NdtAmclNode
 2D NDT AMCL as a ROS 2 composable lifecycle node. More...
 

Typedefs

using beluga_amcl::NDTMapRepresentation = beluga::SparseValueGrid2< std::unordered_map< Eigen::Vector2i, beluga::NDTCell2d, beluga::detail::CellHasher< 2 > >>
 Underlying map representation for the NDT sensor model.
 
using beluga_amcl::RandomStateGenerator = std::function< std::function< beluga::NDTSensorModel< NDTMapRepresentation >::state_type()>(const beluga::TupleVector< std::tuple< beluga::NDTSensorModel< NDTMapRepresentation >::state_type, beluga::Weight > >)>
 Type of a particle-dependent random state generator.
 
template<class MotionModel , class ExecutionPolicy >
using beluga_amcl::NdtAmcl = beluga::Amcl< MotionModel, beluga::NDTSensorModel< NDTMapRepresentation >, RandomStateGenerator, beluga::Weight, std::tuple< typename beluga::NDTSensorModel< NDTMapRepresentation >::state_type, beluga::Weight >, ExecutionPolicy >
 Partial specialization of the core AMCL pipeline for convinience.
 
using beluga_amcl::NdtAmclVariant = std::variant< NdtAmcl< beluga::StationaryModel, std::execution::parallel_policy >, NdtAmcl< beluga::StationaryModel, std::execution::sequenced_policy >, NdtAmcl< beluga::DifferentialDriveModel2d, std::execution::parallel_policy >, NdtAmcl< beluga::DifferentialDriveModel2d, std::execution::sequenced_policy >, NdtAmcl< beluga::OmnidirectionalDriveModel, std::execution::parallel_policy >, NdtAmcl< beluga::OmnidirectionalDriveModel, std::execution::sequenced_policy > >
 All combinations of supported NDT AMCL variants. More...
 
using beluga_amcl::MotionModelVariant = std::variant< beluga::DifferentialDriveModel2d, beluga::StationaryModel, beluga::OmnidirectionalDriveModel >
 Supported motion models.
 
using beluga_amcl::ExecutionPolicyVariant = std::variant< std::execution::sequenced_policy, std::execution::parallel_policy >
 Supported execution policies.
 

Detailed Description

ROS 2 integration of the 2D NDT-AMCL algorithm.

Typedef Documentation

◆ NdtAmclVariant

typedef std::variant< NdtAmcl< beluga::DifferentialDriveModel3d, std::execution::parallel_policy >, NdtAmcl< beluga::DifferentialDriveModel3d, std::execution::sequenced_policy > > beluga_amcl::NdtAmclVariant

All combinations of supported NDT AMCL variants.

All combinations of supported 3D NDT AMCL variants.