Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
beluga Namespace Reference

The main Beluga namespace. More...

Namespaces

 actions
 
 clusterizer_detail
 
 detail
 
 io
 
 policies
 
 state_detail
 
 testing
 
 views
 
 weight_detail
 

Classes

class  Amcl
 Implementation of the Adaptive Monte Carlo Localization (AMCL) algorithm. More...
 
struct  AmclParams
 Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation. More...
 
class  BaseDenseGrid2
 Dense 2D grid base type. More...
 
class  BaseLaserScan
 Laser scan 2D base type. More...
 
class  BaseLinearGrid2
 Linear 2D grid base type. More...
 
class  BaseOccupancyGrid2
 Occupancy 2D grid base type. More...
 
class  BaseRegularGrid
 Regularly spaced N dimensional grid base type. More...
 
struct  BeamModelParam
 Parameters used to construct a BeamSensorModel instance. More...
 
class  BeamSensorModel
 Beam sensor model for range finders. More...
 
struct  BearingModelParam
 Parameters used to construct a BearingSensorModel instance. More...
 
class  BearingSensorModel
 Generic bearing sensor model, for both 2D and 3D state types. More...
 
struct  BearingSensorModelTests
 
class  Bresenham2i
 Bresenham's 2D line drawing algorithm, optimized for integer arithmetic. More...
 
class  CircularArray
 An implementation of generic, non-threadsafe circular array. More...
 
struct  common_tuple_type
 Meta-function that computes a common tuple type given two tuple-like types T and U. More...
 
struct  common_tuple_type< T, U, std::index_sequence< I... > >
 common_tuple_type specialization for std::index_sequence. More...
 
struct  decay_tuple_like
 Meta-function that decays a tuple like type and its members. More...
 
struct  decay_tuple_like< TupleLike< Args... >, std::enable_if_t< is_tuple_like_v< std::decay_t< TupleLike< Args... > > > > >
 decay_tuple_like specialization for tuples. More...
 
class  DifferentialDriveModel
 Sampled odometry model for a differential drive. More...
 
struct  DifferentialDriveModelParam
 Parameters to construct a DifferentialDriveModel instance. More...
 
class  ExponentialFilter
 Callable type implementing an exponential filter. More...
 
struct  has_common_tuple_type
 Meta-function that checks for the existence of a common tuple type. More...
 
struct  has_common_tuple_type< T, U, std::void_t< common_tuple_type_t< T, U > > >
 has_common_tuple_type specialization for tuple-like types T and U for which a common tuple type exists. More...
 
struct  has_single_element
 Meta-function that returns true if there is a single element of type T in the tuple-like type. More...
 
struct  Hasher
 
class  IndexingIterator
 A random access iterator for any indexable container. More...
 
struct  is_tuple_like
 Meta-function that returns true if T is a tuple-like type. More...
 
struct  LandmarkBearingDetection
 Landmark bearing detection data. More...
 
class  LandmarkMap
 Basic 3D landmark map datatype. More...
 
struct  LandmarkModelParam
 Parameters used to construct a LandmarkSensorModel instance (both 2D and 3D). More...
 
struct  LandmarkPositionDetection
 Landmark bearing detection data. More...
 
class  LandmarkSensorModel
 Generic landmark model for discrete detection sensors (both 2D and 3D). More...
 
struct  Less
 
class  LikelihoodFieldModel
 Likelihood field sensor model for range finders. More...
 
struct  LikelihoodFieldModelParam
 Parameters used to construct a LikelihoodFieldModel instance. More...
 
struct  multivariate_distribution_traits
 Forward declaration of the multivariate_distribution_traits class template. More...
 
struct  multivariate_distribution_traits< T, std::enable_if_t< std::is_base_of_v< Eigen::EigenBase< T >, T > > >
 Specialization for types derived from Eigen::EigenBase. More...
 
struct  multivariate_distribution_traits< T, std::enable_if_t< std::is_base_of_v< Sophus::SE2Base< T >, T > > >
 Specialization for types derived from Sophus::SE2Base. More...
 
struct  multivariate_distribution_traits< T, std::enable_if_t< std::is_base_of_v< Sophus::SE3Base< T >, T > > >
 Specialization for types derived from Sophus::SE3Base. More...
 
struct  multivariate_distribution_traits< T, std::enable_if_t< std::is_base_of_v< Sophus::SO2Base< T >, T > > >
 Specialization for types derived from Sophus::SO2Base. More...
 
struct  multivariate_distribution_traits< T, std::enable_if_t< std::is_base_of_v< Sophus::SO3Base< T >, T > > >
 Specialization for types derived from Sophus::SO3Base. More...
 
class  MultivariateNormalDistribution
 Multivariate normal distribution. More...
 
class  MultivariateNormalDistributionParam
 Multivariate normal distribution parameter set class. More...
 
class  MultivariateUniformDistribution
 Primary template for a multivariate uniform distribution. More...
 
class  MultivariateUniformDistribution< Sophus::SE2d, Eigen::AlignedBox2d >
 Specialization of multivariate uniform distribution for bounding regions in 2D space. More...
 
class  MultivariateUniformDistribution< Sophus::SE2d, OccupancyGrid >
 Specialization of multivariate uniform distribution for occupancy grids. More...
 
class  MultivariateUniformDistribution< Sophus::SE3d, Eigen::AlignedBox3d >
 Specialization of multivariate uniform distribution for bounding regions in 3D space. More...
 
struct  NDTCell
 Representation for a cell of a N dimensional NDT cell. More...
 
struct  NDTModelParam
 Parameters used to construct a NDTSensorModel instance. More...
 
class  NDTSensorModel
 NDT sensor model for range finders. More...
 
class  Numeric
 Helper for creating strongly typed numeric types. More...
 
class  OmnidirectionalDriveModel
 Sampled odometry model for an omnidirectional drive. More...
 
struct  OmnidirectionalDriveModelParam
 Parameters to construct an OmnidirectionalDriveModel instance. More...
 
struct  particle_traits
 Common traits of all particle types. See Page requirements as well. More...
 
class  ParticleClusterizer
 Particle clusterizer implementation. More...
 
struct  ParticleClusterizerParam
 Parameters used to construct a ParticleClusterizer instance. More...
 
struct  policy
 Forward declaration of policy. More...
 
struct  policy_base
 Implementation detail for a policy base object. More...
 
class  Ray2d
 Castable 2D ray. More...
 
class  SparseGridTests
 
class  SparseValueGrid
 Generic N dimensional sparse value regular grid. More...
 
struct  spatial_hash
 Callable class, allowing to calculate the hash of a particle state. More...
 
class  spatial_hash< Sophus::SE2d, void >
 
struct  spatial_hash< State >
 
class  spatial_hash< std::array< T, N >, std::enable_if_t< std::is_arithmetic_v< T >, void > >
 Specialization for arrays. More...
 
class  spatial_hash< Tuple< Types... >, std::enable_if_t<(std::is_arithmetic_v< Types > &&...), void > >
 Specialization for tuples. More...
 
class  StationaryModel
 A stationary motion model. More...
 
class  ThrunRecoveryProbabilityEstimator
 Random particle probability estimator. More...
 
struct  tuple_index
 Meta-function that returns the tuple index of the element whose type is T. More...
 
class  TupleContainer
 Primary template for a tuple of containers. More...
 
class  TupleContainer< InternalContainer, std::tuple< Types... > >
 An implementation of a tuple of containers, with an interface that looks like a container of tuples. More...
 
class  TupleVector
 Shorthand for a tuple of vectors with the default allocator. More...
 
class  ValueGrid2
 Generic 2D linear value grid. More...
 

Typedefs

template<class... Args>
using any_policy = policy< std::function< bool(Args...)> >
 Type erased policy. More...
 
template<typename Derived >
using BaseRegularGrid2 = BaseRegularGrid< Derived, 2 >
 Convenience alias for a 2D base regular grid. More...
 
template<typename Derived >
using BaseRegularGrid3 = BaseRegularGrid< Derived, 3 >
 Convenience alias for a 3D base regular grid. More...
 
template<class LandmarkMap >
using BearingSensorModel2d = BearingSensorModel< LandmarkMap, Sophus::SE2d >
 Sensor model based on discrete landmarks bearing detection for 2D state types. More...
 
template<class LandmarkMap >
using BearingSensorModel3d = BearingSensorModel< LandmarkMap, Sophus::SE3d >
 Sensor model based on discrete landmarks bearing detection for 3D state types. More...
 
using BearingSensorModelTestsTypes = ::testing::Types< Sensor2D, Sensor3D >
 
using Cluster = Numeric< std::size_t, struct ClusterTag >
 Cluster type, as a strongly typed std::size_t. More...
 
template<typename T , typename U >
using common_tuple_type_t = typename common_tuple_type< T, U >::type
 Convenience template type alias for common_tuple_type. More...
 
template<class T >
using decay_tuple_like_t = typename decay_tuple_like< T >::type
 Convenience template type alias for decay_tuple_like. More...
 
using DifferentialDriveModel2d = DifferentialDriveModel< Sophus::SE2d >
 Alias for a 2D differential drive model, for convinience. More...
 
using DifferentialDriveModel3d = DifferentialDriveModel< Sophus::SE3d >
 Alias for a 3D differential drive model, for convinience. More...
 
using LandmarkBearing3 = Eigen::Vector3d
 Bearing of a landmark in the sensor reference frame. More...
 
using LandmarkCategory = uint32_t
 Type used to represent landmark categories. More...
 
using LandmarkMapBoundaries = Eigen::AlignedBox3d
 Boundaries of a landmark map. More...
 
using LandmarkPosition3 = Eigen::Vector3d
 Position of a landmark in the world reference frame. More...
 
template<class LandmarkMap >
using LandmarkSensorModel2d = LandmarkSensorModel< LandmarkMap, Sophus::SE2d >
 Sensor model based on discrete landmarks for 2D state types. More...
 
template<class LandmarkMap >
using LandmarkSensorModel3d = LandmarkSensorModel< LandmarkMap, Sophus::SE3d >
 Sensor model based on discrete landmarks for 3D state types. More...
 
using NDTCell2d = NDTCell< 2, double >
 Convenience alias for a 2D NDT cell with double representation. More...
 
using NDTCell2f = NDTCell< 2, float >
 Convenience alias for a 2D NDT cell with float representation. More...
 
using NDTCell3d = NDTCell< 3, double >
 Convenience alias for a 3D NDT cell with double representation. More...
 
using NDTCell3f = NDTCell< 3, float >
 Convenience alias for a 3D NDT cell with float representation. More...
 
using NDTModelParam2d = NDTModelParam< 2 >
 Convenience alias for a 2d parameters struct for the NDT sensor model. More...
 
using NDTModelParam3d = NDTModelParam< 3 >
 Convenience alias for a 3d parameters struct for the NDT sensor model. More...
 
template<typename T , std::size_t N>
using RollingWindow = CircularArray< T, N, CircularArrayFeatureFlags::kRolloverOnWrite|CircularArrayFeatureFlags::kExtrapolateOnRead|CircularArrayFeatureFlags::kLayoutReversal >
 Convenient type alias for a circular array that behaves like a rolling window. More...
 
using Sensor2D = beluga::BearingSensorModel2d< LandmarkMap >
 
using Sensor3D = beluga::BearingSensorModel3d< LandmarkMap >
 
using SparseGridTestCases = testing::Types< std::unordered_map< Eigen::Vector2i, int, Hasher >, std::map< Eigen::Vector2i, int, Less > >
 
template<typename MapType >
using SparseValueGrid2 = SparseValueGrid< MapType, 2 >
 Convenience alias for 2D sparse value grids. More...
 
template<typename MapType >
using SparseValueGrid3 = SparseValueGrid< MapType, 3 >
 Convenience alias for 3D sparse value grids. More...
 
template<class T >
using state_t = typename particle_traits< T >::state_type
 Type trait that returns the state type given a particle type. More...
 
using strong_double = Numeric< double, struct StrongDoubleTag >
 
using strong_size_t = Numeric< std::size_t, struct StrongSizeTTag >
 
using strong_size_t_2 = Numeric< std::size_t, struct StrongSizeTTag2 >
 
template<class T , class TupleLike >
using tuple_index_t = typename tuple_index< T, TupleLike >::type
 Convenience template type alias for tuple_index. More...
 
using UUT = beluga::BeamSensorModel< StaticOccupancyGrid< 5, 5 > >
 
template<class T >
using Vector = std::vector< T, std::allocator< T > >
 Shorthand for a vector with the default allocator. More...
 
using Weight = Numeric< double, struct WeightTag >
 Weight type, as a strongly typed double. More...
 
template<class T >
using weight_t = typename particle_traits< T >::weight_type
 Type trait that returns the weight type given a particle type. More...
 

Enumerations

enum  CircularArrayFeatureFlags : std::int8_t { CircularArrayFeatureFlags::kNone = 0x00, CircularArrayFeatureFlags::kRolloverOnWrite = 0x01, CircularArrayFeatureFlags::kExtrapolateOnRead = 0x02, CircularArrayFeatureFlags::kLayoutReversal = 0x04 }
 Feature flags for circular arrays. More...
 

Functions

template<class Range , class Scalar >
Sophus::Matrix2< Scalar > calculate_covariance (Range &&range, const Sophus::Vector2< Scalar > &mean)
 
template<class Range , class WeightsRange , class Scalar >
Sophus::Matrix2< Scalar > calculate_covariance (Range &&range, WeightsRange &&normalized_weights, const Sophus::Vector2< Scalar > &mean)
 Calculates the covariance of a range given its mean and the weights of each element. More...
 
template<class States , class Weights >
auto cluster_based_estimate (States &&states, Weights &&weights, ParticleClusterizerParam parameters={})
 Computes a cluster-based estimate from a particle set. More...
 
template<class Range , std::enable_if_t<!is_particle_range_v< Range >, int > = 0>
auto effective_sample_size (Range &&range)
 Calculate the ESS of a given a range of weights. More...
 
template<class T , class TupleLike >
constexpr decltype(auto) element (TupleLike &&tuple) noexcept
 Returns element of a tuple like object whose type is T (or a possibly const reference to T). More...
 
template<class Poses , class Pose = ranges::range_value_t<Poses>, class Scalar = typename Pose::Scalar, typename = std::enable_if_t<std::is_same_v<Pose, typename Sophus::SE2<Scalar>>>>
std::pair< Sophus::SE2< Scalar >, Sophus::Matrix3< Scalar > > estimate (Poses &&poses)
 Returns a pair consisting of the estimated mean pose and its covariance. More...
 
template<class Poses , class Weights , class Pose = ranges::range_value_t<Poses>, class Scalar = typename Pose::Scalar, typename = std::enable_if_t<std::is_same_v<Pose, typename Sophus::SE2<Scalar>>>>
std::pair< Sophus::SE2< Scalar >, Sophus::Matrix3< Scalar > > estimate (Poses &&poses, Weights &&weights)
 Returns a pair consisting of the estimated mean pose and its covariance. More...
 
template<class Scalars , class Weights , class Scalar = ranges::range_value_t<Scalars>, typename = std::enable_if_t<std::is_arithmetic_v<Scalar>>>
std::pair< Scalar, Scalar > estimate (Scalars &&scalars, Weights &&weights)
 Computes mean and variance of a range of weighted scalars. More...
 
template<class States , class Weights , class Clusters >
auto estimate_clusters (States &&states, Weights &&weights, Clusters &&clusters)
 For each cluster, estimate the mean and covariance of the states that belong to it. More...
 
double expected_aggregate_probability (std::vector< double > landmark_probs)
 
template<class T , class U >
constexpr auto && forward_like (U &&value) noexcept
 Returns a reference to a value which has similar properties to T&&. More...
 
template<std::size_t I, class T , std::size_t N, CircularArrayFeatureFlags F>
constexpr T && get (CircularArray< T, N, F > &&array) noexcept
 Gets an rvalue reference to the ith value in a given array. More...
 
template<std::size_t I, class T , std::size_t N, CircularArrayFeatureFlags F>
constexpr T & get (CircularArray< T, N, F > &array) noexcept
 Gets an lvalue reference to the ith value in a given array. More...
 
template<std::size_t I, class T , std::size_t N, CircularArrayFeatureFlags F>
constexpr const T && get (const CircularArray< T, N, F > &&array) noexcept
 Gets a constant rvalue reference to the ith value in a given array. More...
 
template<std::size_t I, class T , std::size_t N, CircularArrayFeatureFlags F>
constexpr const T & get (const CircularArray< T, N, F > &array) noexcept
 Gets a constant lvalue reference to the ith value in a given array. More...
 
BearingModelParam get_default_model_params ()
 
template<typename T >
get_robot_pose_in_world ()
 
template<>
Sophus::SE2d get_robot_pose_in_world< Sophus::SE2d > ()
 
template<>
Sophus::SE3d get_robot_pose_in_world< Sophus::SE3d > ()
 
BeamModelParam GetParams ()
 
auto kld_condition (std::size_t min, double epsilon, double z=beluga::detail::kDefaultKldZ)
 Returns a callable object that verifies if the KLD condition is being satisfied. More...
 
auto make_sensor_data (std::vector< std::tuple< double, double, double, uint32_t >> detections)
 
template<class T >
 MultivariateNormalDistribution (const T &, const typename multivariate_distribution_traits< T >::covariance_type &) -> MultivariateNormalDistribution< typename multivariate_distribution_traits< T >::result_type >
 Deduction guide to deduce the correct result type. More...
 
template<class Derived >
 MultivariateUniformDistribution (const BaseOccupancyGrid2< Derived > &) -> MultivariateUniformDistribution< Sophus::SE2d, Derived >
 Deduction guide for 2D occupancy grids. More...
 
 MultivariateUniformDistribution (const Eigen::AlignedBox2d &) -> MultivariateUniformDistribution< Sophus::SE2d, Eigen::AlignedBox2d >
 Deduction guide for bounding regions in SE2 space. More...
 
 MultivariateUniformDistribution (const Eigen::AlignedBox3d &) -> MultivariateUniformDistribution< Sophus::SE3d, Eigen::AlignedBox3d >
 Deduction guide for bounding regions in SE3 space. More...
 
template<class Range , class DistanceFunction , class NeighborsFunction >
auto nearest_obstacle_distance_map (Range &&obstacle_map, DistanceFunction &&distance_function, NeighborsFunction &&neighbors_function)
 Returns a map where the value of each cell is the distance to the nearest obstacle. More...
 
constexpr bool operator& (CircularArrayFeatureFlags mask, CircularArrayFeatureFlags flag)
 Bitwise AND operator overload to check of the presence of a feature flag in a feature mask. More...
 
template<typename T , std::size_t N, CircularArrayFeatureFlags F>
CircularArray< T, N, F > & operator<< (CircularArray< T, N, F > &array, T value)
 Convenient stream operator overload to push a value to a circular array. More...
 
constexpr CircularArrayFeatureFlags operator| (CircularArrayFeatureFlags lflag, CircularArrayFeatureFlags rflag)
 Bitwise OR operator overload to combine two feature flags in a single mask-like flag. More...
 
template<typename T , std::size_t N, CircularArrayFeatureFlags F, CircularArrayFeatureFlags G>
constexpr void swap (CircularArray< T, N, F > &a, CircularArray< T, N, G > &b)
 Swaps arrays a and b. More...
 
 TEST (BaselineRaycasting, Nominal)
 
 TEST (BeamSensorModel, GridUpdates)
 
 TEST (BeamSensorModel, ImportanceWeight)
 
 TEST (Bresenham, Modified)
 
 TEST (Bresenham, MultiPassGuarantee)
 
 TEST (Bresenham, Standard)
 
 TEST (Embed3DTests, Se2ToSe3)
 
 TEST (Embed3DTests, Se3ToSe2)
 
 TEST (NDTCellTests, Ostream)
 
 TEST (NDTCellTests, Product)
 
 TEST (NDTSensorModel2DTests, CanConstruct)
 
 TEST (NDTSensorModel2DTests, FitPoints)
 
 TEST (NDTSensorModel2DTests, Likelihoood)
 
 TEST (NDTSensorModel2DTests, LoadFromHDF5HappyPath)
 
 TEST (NDTSensorModel2DTests, LoadFromHDF5NonExistingFile)
 
 TEST (NDTSensorModel2DTests, MinLikelihood)
 
 TEST (NDTSensorModel2DTests, SensorModel)
 
 TEST (NDTSensorModel2DTests, ToCellsNotEnoughPointsInCell)
 
 TEST (NDTSensorModel3DTests, FitPoints)
 
 TEST (NDTSensorModel3DTests, LoadFromHDF5HappyPath)
 
 TEST (NDTSensorModel3DTests, LoadFromHDF5NonExistingFile)
 
 TEST (NDTSensorModel3DTests, SensorModel)
 
 TEST (NDTSensorModel3DTests, ToCellsNotEnoughPointsInCell)
 
 TEST (NumericTypeDef, hash)
 
 TEST (NumericTypeDef, implicitCasts)
 
 TEST (NumericTypeDef, numericLimits)
 
 TEST (Raycasting, Nominal)
 
 TEST (Raycasting, NonIdentityGridOrigin)
 
 TEST (TestAmclCore, InitializeFromPose)
 
 TEST (TestAmclCore, InitializeWithNoParticles)
 
 TEST (TestAmclCore, ParticlesDependentRandomStateGenerator)
 
 TEST (TestAmclCore, SelectiveResampleCanBeConstructed)
 
 TEST (TestAmclCore, TestRandomParticlesInserting)
 
 TEST (TestAmclCore, Update)
 
 TEST (TestAmclCore, UpdateWithNoParticles)
 
 TEST (TestAmclCore, UpdateWithParticles)
 
 TEST (TestAmclCore, UpdateWithParticlesForced)
 
 TEST (TestAmclCore, UpdateWithParticlesNoMotion)
 
Sophus::SE2d To2d (const Sophus::SE3d &tf)
 Transforms a SE3 transform into a SE2 transform, by flattening the Z axis. More...
 
Sophus::SE3d To3d (const Sophus::SE2d &tf)
 Embed a SE2 transform into 3D space with zero Z translation and only rotation about the Z axis. More...
 
template<class I , class S , typename = std::enable_if_t<ranges::input_iterator<I> && ranges::input_iterator<S>>>
 TupleVector (I, S) -> TupleVector< decay_tuple_like_t< ranges::iter_value_t< I >>>
 Deduction guide to construct from iterators. More...
 
 TYPED_TEST (BearingSensorModelTests, BullsEyeDetection)
 
 TYPED_TEST (BearingSensorModelTests, MapUpdate)
 
 TYPED_TEST (BearingSensorModelTests, MultipleBullsEyeDetections)
 
 TYPED_TEST (BearingSensorModelTests, NoSuchLandmark)
 
 TYPED_TEST (BearingSensorModelTests, OneStdInBearing)
 
 TYPED_TEST (BearingSensorModelTests, SmokeTest)
 
 TYPED_TEST (SparseGridTests, AllAccessorMethodsAreEquivalent)
 
 TYPED_TEST (SparseGridTests, CanBeConstructedEmpty)
 
 TYPED_TEST (SparseGridTests, DataAccessing)
 
 TYPED_TEST (SparseGridTests, NotPresent)
 
 TYPED_TEST (SparseGridTests, Resolution)
 
 TYPED_TEST (SparseGridTests, Size)
 
 TYPED_TEST_SUITE (BearingSensorModelTests, BearingSensorModelTestsTypes,)
 
 TYPED_TEST_SUITE (SparseGridTests, SparseGridTestCases,)
 

Variables

LandmarkMapBoundaries default_map_boundaries {Eigen::Vector3d{-10.0, -10.0, 0.0}, Eigen::Vector3d{10.0, 10.0, 0.0}}
 
template<typename T , typename U >
constexpr bool has_common_tuple_type_v = has_common_tuple_type<T, U>::value
 Convenience template variable for has_common_tuple_type. More...
 
template<class T , class TupleLike >
constexpr bool has_single_element_v = has_single_element<T, TupleLike>::value
 Convenience template variable for has_single_element. More...
 
template<class T >
constexpr bool is_tuple_like_v = is_tuple_like<T>::value
 Convenience template variable for is_tuple_like. More...
 
template<class Particle >
constexpr detail::make_from_state_fn< Particle > make_from_state
 A function object to create a particle from a given state. More...
 
constexpr detail::make_policy_fn make_policy
 Make policy function objects. More...
 
constexpr state_detail::state_fn state
 Customization point object for accessing the state of a particle. More...
 
template<class T , class TupleLike >
constexpr std::size_t tuple_index_v = tuple_index<T, TupleLike>::value
 Convenience template variable for tuple_index. More...
 
constexpr weight_detail::weight_fn weight
 Customization point object for accessing the weight of a particle. More...
 

Detailed Description

The main Beluga namespace.

Typedef Documentation

◆ any_policy

template<class... Args>
using beluga::any_policy = typedef policy<std::function<bool(Args...)> >

Type erased policy.

Definition at line 129 of file policy.hpp.

◆ BaseRegularGrid2

template<typename Derived >
using beluga::BaseRegularGrid2 = typedef BaseRegularGrid<Derived, 2>

Convenience alias for a 2D base regular grid.

Definition at line 102 of file regular_grid.hpp.

◆ BaseRegularGrid3

template<typename Derived >
using beluga::BaseRegularGrid3 = typedef BaseRegularGrid<Derived, 3>

Convenience alias for a 3D base regular grid.

Definition at line 106 of file regular_grid.hpp.

◆ BearingSensorModel2d

template<class LandmarkMap >
using beluga::BearingSensorModel2d = typedef BearingSensorModel<LandmarkMap, Sophus::SE2d>

Sensor model based on discrete landmarks bearing detection for 2D state types.

Definition at line 153 of file bearing_sensor_model.hpp.

◆ BearingSensorModel3d

template<class LandmarkMap >
using beluga::BearingSensorModel3d = typedef BearingSensorModel<LandmarkMap, Sophus::SE3d>

Sensor model based on discrete landmarks bearing detection for 3D state types.

Definition at line 157 of file bearing_sensor_model.hpp.

◆ BearingSensorModelTestsTypes

using beluga::BearingSensorModelTestsTypes = typedef ::testing::Types<Sensor2D, Sensor3D>

Definition at line 80 of file test_bearing_sensor_model.cpp.

◆ Cluster

using beluga::Cluster = typedef Numeric<std::size_t, struct ClusterTag>

Cluster type, as a strongly typed std::size_t.

Definition at line 59 of file primitives.hpp.

◆ common_tuple_type_t

template<typename T , typename U >
using beluga::common_tuple_type_t = typedef typename common_tuple_type<T, U>::type

Convenience template type alias for common_tuple_type.

Definition at line 78 of file tuple_traits.hpp.

◆ decay_tuple_like_t

template<class T >
using beluga::decay_tuple_like_t = typedef typename decay_tuple_like<T>::type

Convenience template type alias for decay_tuple_like.

Definition at line 187 of file tuple_traits.hpp.

◆ DifferentialDriveModel2d

Alias for a 2D differential drive model, for convinience.

Definition at line 177 of file differential_drive_model.hpp.

◆ DifferentialDriveModel3d

Alias for a 3D differential drive model, for convinience.

Definition at line 180 of file differential_drive_model.hpp.

◆ LandmarkBearing3

Bearing of a landmark in the sensor reference frame.

Definition at line 34 of file landmark_detection_types.hpp.

◆ LandmarkCategory

using beluga::LandmarkCategory = typedef uint32_t

Type used to represent landmark categories.

Definition at line 32 of file landmark_detection_types.hpp.

◆ LandmarkMapBoundaries

using beluga::LandmarkMapBoundaries = typedef Eigen::AlignedBox3d

Boundaries of a landmark map.

Definition at line 36 of file landmark_detection_types.hpp.

◆ LandmarkPosition3

Position of a landmark in the world reference frame.

Definition at line 33 of file landmark_detection_types.hpp.

◆ LandmarkSensorModel2d

template<class LandmarkMap >
using beluga::LandmarkSensorModel2d = typedef LandmarkSensorModel<LandmarkMap, Sophus::SE2d>

Sensor model based on discrete landmarks for 2D state types.

Definition at line 168 of file landmark_sensor_model.hpp.

◆ LandmarkSensorModel3d

template<class LandmarkMap >
using beluga::LandmarkSensorModel3d = typedef LandmarkSensorModel<LandmarkMap, Sophus::SE3d>

Sensor model based on discrete landmarks for 3D state types.

Definition at line 172 of file landmark_sensor_model.hpp.

◆ NDTCell2d

using beluga::NDTCell2d = typedef NDTCell<2, double>

Convenience alias for a 2D NDT cell with double representation.

Definition at line 80 of file ndt_cell.hpp.

◆ NDTCell2f

using beluga::NDTCell2f = typedef NDTCell<2, float>

Convenience alias for a 2D NDT cell with float representation.

Definition at line 82 of file ndt_cell.hpp.

◆ NDTCell3d

using beluga::NDTCell3d = typedef NDTCell<3, double>

Convenience alias for a 3D NDT cell with double representation.

Definition at line 84 of file ndt_cell.hpp.

◆ NDTCell3f

using beluga::NDTCell3f = typedef NDTCell<3, float>

Convenience alias for a 3D NDT cell with float representation.

Definition at line 86 of file ndt_cell.hpp.

◆ NDTModelParam2d

Convenience alias for a 2d parameters struct for the NDT sensor model.

Definition at line 161 of file ndt_sensor_model.hpp.

◆ NDTModelParam3d

Convenience alias for a 3d parameters struct for the NDT sensor model.

Definition at line 164 of file ndt_sensor_model.hpp.

◆ RollingWindow

Convenient type alias for a circular array that behaves like a rolling window.

A rolling window automatically overwrites older values, it extrapolates its last value to always seem full, and it is accessed by the front.

Definition at line 465 of file circular_array.hpp.

◆ Sensor2D

Definition at line 39 of file test_bearing_sensor_model.cpp.

◆ Sensor3D

Definition at line 40 of file test_bearing_sensor_model.cpp.

◆ SparseGridTestCases

using beluga::SparseGridTestCases = typedef testing::Types<std::unordered_map<Eigen::Vector2i, int, Hasher>, std::map<Eigen::Vector2i, int, Less> >

Definition at line 42 of file test_sparse_value_grid.cpp.

◆ SparseValueGrid2

template<typename MapType >
using beluga::SparseValueGrid2 = typedef SparseValueGrid<MapType, 2>

Convenience alias for 2D sparse value grids.

Definition at line 97 of file sparse_value_grid.hpp.

◆ SparseValueGrid3

template<typename MapType >
using beluga::SparseValueGrid3 = typedef SparseValueGrid<MapType, 3>

Convenience alias for 3D sparse value grids.

Definition at line 101 of file sparse_value_grid.hpp.

◆ state_t

template<class T >
using beluga::state_t = typedef typename particle_traits<T>::state_type

Type trait that returns the state type given a particle type.

Definition at line 40 of file particle_traits.hpp.

◆ strong_double

using beluga::strong_double = typedef Numeric<double, struct StrongDoubleTag>

Definition at line 24 of file test_strongly_typed_numeric.cpp.

◆ strong_size_t

using beluga::strong_size_t = typedef Numeric<std::size_t, struct StrongSizeTTag>

Definition at line 25 of file test_strongly_typed_numeric.cpp.

◆ strong_size_t_2

using beluga::strong_size_t_2 = typedef Numeric<std::size_t, struct StrongSizeTTag2>

Definition at line 26 of file test_strongly_typed_numeric.cpp.

◆ tuple_index_t

template<class T , class TupleLike >
using beluga::tuple_index_t = typedef typename tuple_index<T, TupleLike>::type

Convenience template type alias for tuple_index.

Definition at line 149 of file tuple_traits.hpp.

◆ UUT

Definition at line 27 of file test_beam_model.cpp.

◆ Vector

template<class T >
using beluga::Vector = typedef std::vector<T, std::allocator<T> >

Shorthand for a vector with the default allocator.

Definition at line 216 of file tuple_vector.hpp.

◆ Weight

using beluga::Weight = typedef Numeric<double, struct WeightTag>

Weight type, as a strongly typed double.

Definition at line 56 of file primitives.hpp.

◆ weight_t

template<class T >
using beluga::weight_t = typedef typename particle_traits<T>::weight_type

Type trait that returns the weight type given a particle type.

Definition at line 44 of file particle_traits.hpp.

Enumeration Type Documentation

◆ CircularArrayFeatureFlags

enum beluga::CircularArrayFeatureFlags : std::int8_t
strong

Feature flags for circular arrays.

Enumerator
kNone 
kRolloverOnWrite 

! If enabled, older values in the array are overwritten by newer values if the array has reached its maximum size already.

kExtrapolateOnRead 

! If enabled, the back value is extrapolated for constant accesses up to the array maximum size.

kLayoutReversal 

! If enabled, the circular array memory layout is reversed so that values can be pushed to the front rather than the back of the array.

Definition at line 35 of file circular_array.hpp.

Function Documentation

◆ calculate_covariance() [1/2]

template<class Range , class Scalar >
Sophus::Matrix2<Scalar> beluga::calculate_covariance ( Range &&  range,
const Sophus::Vector2< Scalar > &  mean 
)

Convenience overload that calculates the covariance of a range given its mean for the case where all samples have the same weight.

Template Parameters
RangeA sized range type whose value type is Sophus::Vector2<Scalar>.
ScalarA scalar type, e.g. double or float.
Parameters
rangeRange to be used to calculate the covariance.
meanThe previously calculated mean of range. The value must be correct for the resulting covariance to be correct.
Returns
The calculated covariance, as a Sophus::Matrix2<Scalar>.

Definition at line 97 of file estimation.hpp.

◆ calculate_covariance() [2/2]

template<class Range , class WeightsRange , class Scalar >
Sophus::Matrix2<Scalar> beluga::calculate_covariance ( Range &&  range,
WeightsRange &&  normalized_weights,
const Sophus::Vector2< Scalar > &  mean 
)

Calculates the covariance of a range given its mean and the weights of each element.

Template Parameters
RangeA sized range type whose value type is Sophus::Vector2<Scalar>.
WeightsRangeA sized range type whose value type is Scalar.
ScalarA scalar type, e.g. double or float.
Parameters
rangeRange to be used to calculate the covariance.
normalized_weightsRange with the normalized (total weight 1.0) weights of the samples in 'range'.
meanThe previously calculated mean of range. The value must be correct for the resulting covariance to be correct.
Returns
The calculated covariance, as a Sophus::Matrix2<Scalar>.

Definition at line 53 of file estimation.hpp.

◆ cluster_based_estimate()

template<class States , class Weights >
auto beluga::cluster_based_estimate ( States &&  states,
Weights &&  weights,
ParticleClusterizerParam  parameters = {} 
)

Computes a cluster-based estimate from a particle set.

Particles are grouped into clusters around local maxima. The state mean and covariance of the cluster with the highest total weight is returned. If no clusters are found, the overall mean and covariance of the particles are calculated and returned.

Template Parameters
StatesRange type of the states.
WeightsRange type of the weights.
Parameters
statesRange containing the states of the particles.
weightsRange containing the weights of the particles.
parametersParameters for the particle clusterizer (optional).
Returns
A pair consisting of the state mean and covariance of the cluster with the highest total weight.

Definition at line 414 of file cluster_based_estimation.hpp.

◆ effective_sample_size()

template<class Range , std::enable_if_t<!is_particle_range_v< Range >, int > = 0>
auto beluga::effective_sample_size ( Range &&  range)

Calculate the ESS of a given a range of weights.

Overload for particle ranges.

The effective sample size (ESS) is a figure of merit for importance sampling methods' output. It characterizes how well the target posterior distribution is approximated (as it is proportional to the efficiency of distribution parameter estimators, [kong1994sequentialimputations], section 4.1). It can be interpreted as the number of samples effectively approximating the distribution, and thus comparing with the total number of samples makes for a good mechanism to detect and react to performance degradation e.g. triggering a resample when the ESS falls below a fraction of the total number of samples.

The algorithm is based on [grisetti2007selectiveresampling], according to the description given in [tiacheng2015resamplingmethods].

Template Parameters
RangeA forward range.
Parameters
rangeThe range of weights.

Definition at line 46 of file effective_sample_size.hpp.

◆ element()

template<class T , class TupleLike >
constexpr decltype(auto) beluga::element ( TupleLike &&  tuple)
constexprnoexcept

Returns element of a tuple like object whose type is T (or a possibly const reference to T).

Definition at line 169 of file tuple_traits.hpp.

◆ estimate() [1/3]

template<class Poses , class Pose = ranges::range_value_t<Poses>, class Scalar = typename Pose::Scalar, typename = std::enable_if_t<std::is_same_v<Pose, typename Sophus::SE2<Scalar>>>>
std::pair<Sophus::SE2<Scalar>, Sophus::Matrix3<Scalar> > beluga::estimate ( Poses &&  poses)

Returns a pair consisting of the estimated mean pose and its covariance.

Given a range of poses, computes the estimated pose by averaging the translation and rotation parts, assuming all poses are equally weighted. Computes the covariance matrix of the translation parts and the circular variance of the rotation angles to create a 3x3 covariance matrix. It does not take into account the particle weights. This is appropriate for use with filter update cycles that resample the particle set at every iteration, since in that case the belief is fully represented by the spatial distribution of the particles, and the particle weights provide no additional information.

Template Parameters
PosesA sized range type whose value type is Sophus::SE2<Scalar>.
PoseThe pose value type of the given range.
ScalarA scalar type, e.g. double or float.
Parameters
posesPoses of equally weighted 2D poses.
Returns
The estimated pose and its 3x3 covariance matrix.

Definition at line 240 of file estimation.hpp.

◆ estimate() [2/3]

template<class Poses , class Weights , class Pose = ranges::range_value_t<Poses>, class Scalar = typename Pose::Scalar, typename = std::enable_if_t<std::is_same_v<Pose, typename Sophus::SE2<Scalar>>>>
std::pair<Sophus::SE2<Scalar>, Sophus::Matrix3<Scalar> > beluga::estimate ( Poses &&  poses,
Weights &&  weights 
)

Returns a pair consisting of the estimated mean pose and its covariance.

Given a range of poses, computes the estimated pose by averaging the translation and rotation parts. Computes the covariance matrix of the translation parts and the circular variance of the rotation angles to create a 3x3 covariance matrix. It does not take into account the particle weights.

Template Parameters
PosesA sized range type whose value type is Sophus::SE2<Scalar>.
WeightsA sized range type whose value type is Scalar.
PoseThe pose value type of the given range.
ScalarA scalar type, e.g. double or float.
Parameters
posesPoses of equally weighted 2D poses.
weightsPoses of equally weighted 2D poses.
Returns
The estimated pose and its 3x3 covariance matrix.

Definition at line 129 of file estimation.hpp.

◆ estimate() [3/3]

template<class Scalars , class Weights , class Scalar = ranges::range_value_t<Scalars>, typename = std::enable_if_t<std::is_arithmetic_v<Scalar>>>
std::pair<Scalar, Scalar> beluga::estimate ( Scalars &&  scalars,
Weights &&  weights 
)

Computes mean and variance of a range of weighted scalars.

Given a range of scalars, computes the scalar mean and variance.

Template Parameters
ScalarsA sized range type whose value type is std::vector<Scalar>.
WeightsA sized range type whose value type is Scalar.
ScalarThe scalar value type of the given range of Scalars.
Parameters
scalarsRange of scalars.
weightsRange of weights.
Returns
The estimated mean and variance.

Definition at line 193 of file estimation.hpp.

◆ estimate_clusters()

template<class States , class Weights , class Clusters >
auto beluga::estimate_clusters ( States &&  states,
Weights &&  weights,
Clusters &&  clusters 
)

For each cluster, estimate the mean and covariance of the states that belong to it.

Template Parameters
StatesRange type of the states.
WeightsRange type of the weights.
HashesRange type of the hashes.
Parameters
statesRange containing the states of the particles.
weightsRange containing the weights of the particles.
clustersCluster ids of the particles.
Returns
A vector of elements, containing the weight, mean and covariance of each cluster, in no particular order.

Convenient factory method to pass to zip_with.

Definition at line 336 of file cluster_based_estimation.hpp.

◆ expected_aggregate_probability()

double beluga::expected_aggregate_probability ( std::vector< double >  landmark_probs)

Definition at line 44 of file test_bearing_sensor_model.cpp.

◆ forward_like()

template<class T , class U >
constexpr auto&& beluga::forward_like ( U &&  value)
constexprnoexcept

Returns a reference to a value which has similar properties to T&&.

Implementation taken from https://en.cppreference.com/w/cpp/utility/forward_like since this feature is only available starting with C++23.

The program is ill-formed if T&& is not a valid type.

Template Parameters
TThe type from which to take the properties.
UThe type of the input value.
Parameters
valueA value that needs to be forwarded like type T.
Returns
A reference to value of the determined type.

Definition at line 33 of file forward_like.hpp.

◆ get() [1/4]

template<std::size_t I, class T , std::size_t N, CircularArrayFeatureFlags F>
constexpr T&& beluga::get ( CircularArray< T, N, F > &&  array)
constexprnoexcept

Gets an rvalue reference to the ith value in a given array.

This is an std::get overload that relies on argument-dependent lookup (ADL).

Definition at line 496 of file circular_array.hpp.

◆ get() [2/4]

template<std::size_t I, class T , std::size_t N, CircularArrayFeatureFlags F>
constexpr T& beluga::get ( CircularArray< T, N, F > &  array)
constexprnoexcept

Gets an lvalue reference to the ith value in a given array.

This is an std::get overload that relies on argument-dependent lookup (ADL).

Definition at line 487 of file circular_array.hpp.

◆ get() [3/4]

template<std::size_t I, class T , std::size_t N, CircularArrayFeatureFlags F>
constexpr const T&& beluga::get ( const CircularArray< T, N, F > &&  array)
constexprnoexcept

Gets a constant rvalue reference to the ith value in a given array.

This is an std::get overload that relies on argument-dependent lookup (ADL).

Definition at line 514 of file circular_array.hpp.

◆ get() [4/4]

template<std::size_t I, class T , std::size_t N, CircularArrayFeatureFlags F>
constexpr const T& beluga::get ( const CircularArray< T, N, F > &  array)
constexprnoexcept

Gets a constant lvalue reference to the ith value in a given array.

This is an std::get overload that relies on argument-dependent lookup (ADL).

Definition at line 505 of file circular_array.hpp.

◆ get_default_model_params()

BearingModelParam beluga::get_default_model_params ( )

Definition at line 49 of file test_bearing_sensor_model.cpp.

◆ get_robot_pose_in_world()

template<typename T >
T beluga::get_robot_pose_in_world ( )

◆ get_robot_pose_in_world< Sophus::SE2d >()

Definition at line 68 of file test_bearing_sensor_model.cpp.

◆ get_robot_pose_in_world< Sophus::SE3d >()

Definition at line 73 of file test_bearing_sensor_model.cpp.

◆ GetParams()

BeamModelParam beluga::GetParams ( )

Definition at line 29 of file test_beam_model.cpp.

◆ kld_condition()

auto beluga::kld_condition ( std::size_t  min,
double  epsilon,
double  z = beluga::detail::kDefaultKldZ 
)
inline

Returns a callable object that verifies if the KLD condition is being satisfied.

The callable object will compute the minimum number of samples based on a Kullback-Leibler distance epsilon between the maximum likelihood estimate and the true distribution.
Z is the upper standard normal quantile for P, where P is the probability that the error in the estimated distribution will be less than epsilon.

Here are some examples:

P Z
0.900 1.28155156327703
0.950 1.64485362793663
0.990 2.32634787735669
0.999 3.09023224677087

If the computed value is less than what the min argument specifies, then min will be returned.

See KLD-Sampling: Adaptive Particle Filters [fox2001adaptivekldsampling].

Parameters
minMinimum number of particles that the callable object will return.
epsilonMaximum distance epsilon between the maximum likelihood estimate and the true distrubution.
zUpper standard normal quantile for the probability that the error in the estimated distribution is less than epsilon.
Returns
A callable object with prototype (std::size_t hash) -> bool. hash is the spatial hash of the particle being added.
The returned callable object is stateful, tracking the total number of particles and the particle clusters based on the spatial hash.
The return value of the callable will be false when the number of particles is more than the minimum and the KLD condition is satisfied, if not it will be true.
i.e. A return value of true means that you need to keep sampling to satisfy the condition.

Definition at line 72 of file take_while_kld.hpp.

◆ make_sensor_data()

auto beluga::make_sensor_data ( std::vector< std::tuple< double, double, double, uint32_t >>  detections)

Definition at line 56 of file test_bearing_sensor_model.cpp.

◆ MultivariateNormalDistribution()

template<class T >
beluga::MultivariateNormalDistribution ( const T &  ,
const typename multivariate_distribution_traits< T >::covariance_type &   
) -> MultivariateNormalDistribution< typename multivariate_distribution_traits< T >::result_type >

Deduction guide to deduce the correct result type.

◆ MultivariateUniformDistribution() [1/3]

template<class Derived >
beluga::MultivariateUniformDistribution ( const BaseOccupancyGrid2< Derived > &  ) -> MultivariateUniformDistribution< Sophus::SE2d, Derived >

Deduction guide for 2D occupancy grids.

◆ MultivariateUniformDistribution() [2/3]

beluga::MultivariateUniformDistribution ( const Eigen::AlignedBox2d &  ) -> MultivariateUniformDistribution< Sophus::SE2d, Eigen::AlignedBox2d >

Deduction guide for bounding regions in SE2 space.

◆ MultivariateUniformDistribution() [3/3]

beluga::MultivariateUniformDistribution ( const Eigen::AlignedBox3d &  ) -> MultivariateUniformDistribution< Sophus::SE3d, Eigen::AlignedBox3d >

Deduction guide for bounding regions in SE3 space.

◆ nearest_obstacle_distance_map()

template<class Range , class DistanceFunction , class NeighborsFunction >
auto beluga::nearest_obstacle_distance_map ( Range &&  obstacle_map,
DistanceFunction &&  distance_function,
NeighborsFunction &&  neighbors_function 
)

Returns a map where the value of each cell is the distance to the nearest obstacle.

The algorithm uses O(N) time and memory, where N=ranges::size(obstacle_map).

Template Parameters
RangeA sized range. Its value type must be bool.
DistanceFunctionA callable type, its prototype must be (std::size_t, std::size_t) -> DistanceType. DistanceType must be an scalar type.
NeighborsFunctionA callabe type, its prototype must be (std::size_t) -> NeighborsT, where NeighborsT is a Range with value type std::size_t.
Parameters
obstacle_mapA map that represents obstacles in an environment. If the value of a cell is True, the cell has an obstacle.
distance_functionGiven the indexes of two cells in the map i and j, obstacle_map(i, j) must return the distance between the two cells.
neighbors_functionGiven the index i of one cell in the map, neighbors_function(i) returns the cell indexes of neighbor cells in the obstacle map.
Returns
A map where each cell value is the distance to the nearest object.

Definition at line 54 of file distance_map.hpp.

◆ operator&()

constexpr bool beluga::operator& ( CircularArrayFeatureFlags  mask,
CircularArrayFeatureFlags  flag 
)
constexpr

Bitwise AND operator overload to check of the presence of a feature flag in a feature mask.

Definition at line 53 of file circular_array.hpp.

◆ operator<<()

template<typename T , std::size_t N, CircularArrayFeatureFlags F>
CircularArray<T, N, F>& beluga::operator<< ( CircularArray< T, N, F > &  array,
value 
)

Convenient stream operator overload to push a value to a circular array.

Functionally equivalent to a push_back() (or push_front() if the layout reversal feature is enabled).

Definition at line 473 of file circular_array.hpp.

◆ operator|()

constexpr CircularArrayFeatureFlags beluga::operator| ( CircularArrayFeatureFlags  lflag,
CircularArrayFeatureFlags  rflag 
)
constexpr

Bitwise OR operator overload to combine two feature flags in a single mask-like flag.

Definition at line 46 of file circular_array.hpp.

◆ swap()

template<typename T , std::size_t N, CircularArrayFeatureFlags F, CircularArrayFeatureFlags G>
constexpr void beluga::swap ( CircularArray< T, N, F > &  a,
CircularArray< T, N, G > &  b 
)
constexpr

Swaps arrays a and b.

This is an std::swap overload that relies on argument-dependent lookup (ADL).

Definition at line 523 of file circular_array.hpp.

◆ TEST() [1/38]

beluga::TEST ( BaselineRaycasting  ,
Nominal   
)

Definition at line 133 of file test_raycasting.cpp.

◆ TEST() [2/38]

beluga::TEST ( BeamSensorModel  ,
GridUpdates   
)

Definition at line 84 of file test_beam_model.cpp.

◆ TEST() [3/38]

beluga::TEST ( BeamSensorModel  ,
ImportanceWeight   
)

Definition at line 40 of file test_beam_model.cpp.

◆ TEST() [4/38]

beluga::TEST ( Bresenham  ,
Modified   
)

Definition at line 127 of file test_bresenham.cpp.

◆ TEST() [5/38]

beluga::TEST ( Bresenham  ,
MultiPassGuarantee   
)

Definition at line 27 of file test_bresenham.cpp.

◆ TEST() [6/38]

beluga::TEST ( Bresenham  ,
Standard   
)

Definition at line 47 of file test_bresenham.cpp.

◆ TEST() [7/38]

beluga::TEST ( Embed3DTests  ,
Se2ToSe3   
)

Definition at line 53 of file test_3d_embedding.cpp.

◆ TEST() [8/38]

beluga::TEST ( Embed3DTests  ,
Se3ToSe2   
)

Definition at line 26 of file test_3d_embedding.cpp.

◆ TEST() [9/38]

beluga::TEST ( NDTCellTests  ,
Ostream   
)

Definition at line 65 of file test_ndt_cell.cpp.

◆ TEST() [10/38]

beluga::TEST ( NDTCellTests  ,
Product   
)

Definition at line 35 of file test_ndt_cell.cpp.

◆ TEST() [11/38]

beluga::TEST ( NDTSensorModel2DTests  ,
CanConstruct   
)

Definition at line 41 of file test_ndt_model.cpp.

◆ TEST() [12/38]

beluga::TEST ( NDTSensorModel2DTests  ,
FitPoints   
)

Definition at line 101 of file test_ndt_model.cpp.

◆ TEST() [13/38]

beluga::TEST ( NDTSensorModel2DTests  ,
Likelihoood   
)

Definition at line 66 of file test_ndt_model.cpp.

◆ TEST() [14/38]

beluga::TEST ( NDTSensorModel2DTests  ,
LoadFromHDF5HappyPath   
)

Definition at line 238 of file test_ndt_model.cpp.

◆ TEST() [15/38]

beluga::TEST ( NDTSensorModel2DTests  ,
LoadFromHDF5NonExistingFile   
)

Definition at line 243 of file test_ndt_model.cpp.

◆ TEST() [16/38]

beluga::TEST ( NDTSensorModel2DTests  ,
MinLikelihood   
)

Definition at line 45 of file test_ndt_model.cpp.

◆ TEST() [17/38]

beluga::TEST ( NDTSensorModel2DTests  ,
SensorModel   
)

Definition at line 213 of file test_ndt_model.cpp.

◆ TEST() [18/38]

beluga::TEST ( NDTSensorModel2DTests  ,
ToCellsNotEnoughPointsInCell   
)

Definition at line 124 of file test_ndt_model.cpp.

◆ TEST() [19/38]

beluga::TEST ( NDTSensorModel3DTests  ,
FitPoints   
)

Definition at line 146 of file test_ndt_model.cpp.

◆ TEST() [20/38]

beluga::TEST ( NDTSensorModel3DTests  ,
LoadFromHDF5HappyPath   
)

Definition at line 251 of file test_ndt_model.cpp.

◆ TEST() [21/38]

beluga::TEST ( NDTSensorModel3DTests  ,
LoadFromHDF5NonExistingFile   
)

Definition at line 247 of file test_ndt_model.cpp.

◆ TEST() [22/38]

beluga::TEST ( NDTSensorModel3DTests  ,
SensorModel   
)

Definition at line 170 of file test_ndt_model.cpp.

◆ TEST() [23/38]

beluga::TEST ( NDTSensorModel3DTests  ,
ToCellsNotEnoughPointsInCell   
)

Definition at line 135 of file test_ndt_model.cpp.

◆ TEST() [24/38]

beluga::TEST ( NumericTypeDef  ,
hash   
)

Definition at line 49 of file test_strongly_typed_numeric.cpp.

◆ TEST() [25/38]

beluga::TEST ( NumericTypeDef  ,
implicitCasts   
)

Definition at line 28 of file test_strongly_typed_numeric.cpp.

◆ TEST() [26/38]

beluga::TEST ( NumericTypeDef  ,
numericLimits   
)

Definition at line 44 of file test_strongly_typed_numeric.cpp.

◆ TEST() [27/38]

beluga::TEST ( Raycasting  ,
Nominal   
)

Definition at line 31 of file test_raycasting.cpp.

◆ TEST() [28/38]

beluga::TEST ( Raycasting  ,
NonIdentityGridOrigin   
)

Definition at line 104 of file test_raycasting.cpp.

◆ TEST() [29/38]

beluga::TEST ( TestAmclCore  ,
InitializeFromPose   
)

Definition at line 82 of file test_amcl_core.cpp.

◆ TEST() [30/38]

beluga::TEST ( TestAmclCore  ,
InitializeWithNoParticles   
)

Definition at line 73 of file test_amcl_core.cpp.

◆ TEST() [31/38]

beluga::TEST ( TestAmclCore  ,
ParticlesDependentRandomStateGenerator   
)

Definition at line 127 of file test_amcl_core.cpp.

◆ TEST() [32/38]

beluga::TEST ( TestAmclCore  ,
SelectiveResampleCanBeConstructed   
)

Definition at line 164 of file test_amcl_core.cpp.

◆ TEST() [33/38]

beluga::TEST ( TestAmclCore  ,
TestRandomParticlesInserting   
)

Definition at line 174 of file test_amcl_core.cpp.

◆ TEST() [34/38]

beluga::TEST ( TestAmclCore  ,
Update   
)

Definition at line 77 of file test_amcl_core.cpp.

◆ TEST() [35/38]

beluga::TEST ( TestAmclCore  ,
UpdateWithNoParticles   
)

Definition at line 88 of file test_amcl_core.cpp.

◆ TEST() [36/38]

beluga::TEST ( TestAmclCore  ,
UpdateWithParticles   
)

Definition at line 95 of file test_amcl_core.cpp.

◆ TEST() [37/38]

beluga::TEST ( TestAmclCore  ,
UpdateWithParticlesForced   
)

Definition at line 115 of file test_amcl_core.cpp.

◆ TEST() [38/38]

beluga::TEST ( TestAmclCore  ,
UpdateWithParticlesNoMotion   
)

Definition at line 104 of file test_amcl_core.cpp.

◆ To2d()

Sophus::SE2d beluga::To2d ( const Sophus::SE3d tf)
inline

Transforms a SE3 transform into a SE2 transform, by flattening the Z axis.

Definition at line 24 of file 3d_embedding.hpp.

◆ To3d()

Sophus::SE3d beluga::To3d ( const Sophus::SE2d tf)
inline

Embed a SE2 transform into 3D space with zero Z translation and only rotation about the Z axis.

Definition at line 29 of file 3d_embedding.hpp.

◆ TupleVector()

template<class I , class S , typename = std::enable_if_t<ranges::input_iterator<I> && ranges::input_iterator<S>>>
beluga::TupleVector ( ,
 
) -> TupleVector< decay_tuple_like_t< ranges::iter_value_t< I >>>

Deduction guide to construct from iterators.

◆ TYPED_TEST() [1/12]

beluga::TYPED_TEST ( BearingSensorModelTests  ,
BullsEyeDetection   
)

Definition at line 89 of file test_bearing_sensor_model.cpp.

◆ TYPED_TEST() [2/12]

beluga::TYPED_TEST ( BearingSensorModelTests  ,
MapUpdate   
)

Definition at line 98 of file test_bearing_sensor_model.cpp.

◆ TYPED_TEST() [3/12]

beluga::TYPED_TEST ( BearingSensorModelTests  ,
MultipleBullsEyeDetections   
)

Definition at line 110 of file test_bearing_sensor_model.cpp.

◆ TYPED_TEST() [4/12]

beluga::TYPED_TEST ( BearingSensorModelTests  ,
NoSuchLandmark   
)

Definition at line 164 of file test_bearing_sensor_model.cpp.

◆ TYPED_TEST() [5/12]

beluga::TYPED_TEST ( BearingSensorModelTests  ,
OneStdInBearing   
)

Definition at line 132 of file test_bearing_sensor_model.cpp.

◆ TYPED_TEST() [6/12]

beluga::TYPED_TEST ( BearingSensorModelTests  ,
SmokeTest   
)

Definition at line 84 of file test_bearing_sensor_model.cpp.

◆ TYPED_TEST() [7/12]

beluga::TYPED_TEST ( SparseGridTests  ,
AllAccessorMethodsAreEquivalent   
)

Definition at line 112 of file test_sparse_value_grid.cpp.

◆ TYPED_TEST() [8/12]

beluga::TYPED_TEST ( SparseGridTests  ,
CanBeConstructedEmpty   
)

Definition at line 46 of file test_sparse_value_grid.cpp.

◆ TYPED_TEST() [9/12]

beluga::TYPED_TEST ( SparseGridTests  ,
DataAccessing   
)

Definition at line 84 of file test_sparse_value_grid.cpp.

◆ TYPED_TEST() [10/12]

beluga::TYPED_TEST ( SparseGridTests  ,
NotPresent   
)

Definition at line 63 of file test_sparse_value_grid.cpp.

◆ TYPED_TEST() [11/12]

beluga::TYPED_TEST ( SparseGridTests  ,
Resolution   
)

Definition at line 73 of file test_sparse_value_grid.cpp.

◆ TYPED_TEST() [12/12]

beluga::TYPED_TEST ( SparseGridTests  ,
Size   
)

Definition at line 51 of file test_sparse_value_grid.cpp.

◆ TYPED_TEST_SUITE() [1/2]

beluga::TYPED_TEST_SUITE ( BearingSensorModelTests  ,
BearingSensorModelTestsTypes   
)

◆ TYPED_TEST_SUITE() [2/2]

beluga::TYPED_TEST_SUITE ( SparseGridTests  ,
SparseGridTestCases   
)

Variable Documentation

◆ default_map_boundaries

LandmarkMapBoundaries beluga::default_map_boundaries {Eigen::Vector3d{-10.0, -10.0, 0.0}, Eigen::Vector3d{10.0, 10.0, 0.0}}

Definition at line 42 of file test_bearing_sensor_model.cpp.

◆ has_common_tuple_type_v

template<typename T , typename U >
constexpr bool beluga::has_common_tuple_type_v = has_common_tuple_type<T, U>::value
inlineconstexpr

Convenience template variable for has_common_tuple_type.

Definition at line 90 of file tuple_traits.hpp.

◆ has_single_element_v

template<class T , class TupleLike >
constexpr bool beluga::has_single_element_v = has_single_element<T, TupleLike>::value
inlineconstexpr

Convenience template variable for has_single_element.

Definition at line 165 of file tuple_traits.hpp.

◆ is_tuple_like_v

template<class T >
constexpr bool beluga::is_tuple_like_v = is_tuple_like<T>::value
inlineconstexpr

Convenience template variable for is_tuple_like.

Definition at line 53 of file tuple_traits.hpp.

◆ make_from_state

template<class Particle >
constexpr detail::make_from_state_fn<Particle> beluga::make_from_state
inlineconstexpr

A function object to create a particle from a given state.

Takes a state and returns a new particle with that state. The new particle is given a weight of 1.

Template Parameters
ParticleThe particle type to be created.

Definition at line 120 of file particle_traits.hpp.

◆ make_policy

constexpr detail::make_policy_fn beluga::make_policy
inlineconstexpr

Make policy function objects.

Definition at line 42 of file policy.hpp.

◆ state

constexpr state_detail::state_fn beluga::state
inlineconstexpr

Customization point object for accessing the state of a particle.

Definition at line 163 of file primitives.hpp.

◆ tuple_index_v

template<class T , class TupleLike >
constexpr std::size_t beluga::tuple_index_v = tuple_index<T, TupleLike>::value
inlineconstexpr

Convenience template variable for tuple_index.

Definition at line 145 of file tuple_traits.hpp.

◆ weight

constexpr weight_detail::weight_fn beluga::weight
inlineconstexpr

Customization point object for accessing the weight of a particle.

Definition at line 264 of file primitives.hpp.



beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53