Classes | Functions | Variables
beluga::detail Namespace Reference

Classes

struct  CellHasher
 
struct  make_from_state_fn
 Function object type to create a particle from a given state. More...
 

Functions

template<int NDim, typename Scalar = double>
NDTCell< NDim, Scalar > fit_points (const std::vector< Eigen::Vector< Scalar, NDim >> &points)
 Fit a vector of points to an NDT cell, by computing its mean and covariance. More...
 
template<std::size_t N, std::size_t I>
constexpr std::size_t floor_and_fibo_hash (double value)
 Returns the hashed and rotated floor of a value. More...
 
template<int NDim>
constexpr std::conditional_t< NDim==2, std::vector< Eigen::Vector2i >, std::vector< Eigen::Vector3i > > get_default_neighbors_kernel ()
 Helper to get the default neighbors kernel. More...
 
template<class T , std::size_t... Ids>
constexpr std::size_t hash_impl (const T &value, const std::array< double, sizeof...(Ids)> &resolution, [[maybe_unused]] std::index_sequence< Ids... > index_sequence)
 
template<int NDim, typename Scalar = double>
std::vector< NDTCell< NDim, Scalar > > to_cells (const std::vector< Eigen::Vector< Scalar, NDim >> &points, const double resolution)
 
template<class T , class... Args>
constexpr bool tuple_index_found () noexcept
 Help method that returns true if a tuple element index that matches an input type is found. More...
 
template<class T , class... Args>
constexpr std::size_t tuple_index_helper () noexcept
 Help method that finds a tuple element index that matches an input type. More...
 

Variables

constexpr double kDefaultKldZ = 3.
 Default upper standard normal quantile, P = 0.999. More...
 
const std::vector< Eigen::Vector2i > kDefaultNeighborKernel2d
 Default neighbor kernel for the 2D NDT sensor model. More...
 
const std::vector< Eigen::Vector3i > kDefaultNeighborKernel3d
 Default neighbor kernel for the 3D NDT sensor model. More...
 
static constexpr std::size_t kTupleIndexAmbiguous = static_cast<std::size_t>(-2)
 Constant value to return when there are multiple indices that match the input type. More...
 
static constexpr std::size_t kTupleIndexNotFound = static_cast<std::size_t>(-1)
 Constant value to return when the index was not found. More...
 

Function Documentation

◆ fit_points()

template<int NDim, typename Scalar = double>
NDTCell<NDim, Scalar> beluga::detail::fit_points ( const std::vector< Eigen::Vector< Scalar, NDim >> &  points)
inline

Fit a vector of points to an NDT cell, by computing its mean and covariance.

Definition at line 60 of file ndt_sensor_model.hpp.

◆ floor_and_fibo_hash()

template<std::size_t N, std::size_t I>
constexpr std::size_t beluga::detail::floor_and_fibo_hash ( double  value)
constexpr

Returns the hashed and rotated floor of a value.

Template Parameters
NNumber of bits to be used from the integer result, the least significant will be used.
IResult will be shifted by I*N.
Parameters
valueInput value to be hashed.
Returns
The calculated result.

Definition at line 45 of file spatial_hash.hpp.

◆ get_default_neighbors_kernel()

template<int NDim>
constexpr std::conditional_t<NDim == 2, std::vector<Eigen::Vector2i>, std::vector<Eigen::Vector3i> > beluga::detail::get_default_neighbors_kernel ( )
constexpr

Helper to get the default neighbors kernel.

Definition at line 135 of file ndt_sensor_model.hpp.

◆ hash_impl()

template<class T , std::size_t... Ids>
constexpr std::size_t beluga::detail::hash_impl ( const T &  value,
const std::array< double, sizeof...(Ids)> &  resolution,
[[maybe_unused] ] std::index_sequence< Ids... >  index_sequence 
)
constexpr

Hashes a tuple or array of scalar types, using a resolution for each element and using the same amount of bits for them.

Template Parameters
TTuple or array of scalar types.
...IdsIndexes of the array/tuple to be used to calculate the hash.
Parameters
valueThe array/tuple to be hashed.
resolutionThe resolution to be used.
index_sequenceUnused, only to allow unpacking ...Ids.
Returns
The calculated hash.

Definition at line 88 of file spatial_hash.hpp.

◆ to_cells()

template<int NDim, typename Scalar = double>
std::vector<NDTCell<NDim, Scalar> > beluga::detail::to_cells ( const std::vector< Eigen::Vector< Scalar, NDim >> &  points,
const double  resolution 
)
inline

Given a number of N dimensional points and a resolution, constructs a vector of NDT cells, by clusterizing the points using 'resolution' and fitting a normal distribution to each of the resulting clusters if they contain a minimum number of points in them.

Definition at line 81 of file ndt_sensor_model.hpp.

◆ tuple_index_found()

template<class T , class... Args>
constexpr bool beluga::detail::tuple_index_found ( )
constexprnoexcept

Help method that returns true if a tuple element index that matches an input type is found.

Definition at line 124 of file tuple_traits.hpp.

◆ tuple_index_helper()

template<class T , class... Args>
constexpr std::size_t beluga::detail::tuple_index_helper ( )
constexprnoexcept

Help method that finds a tuple element index that matches an input type.

Tuple types will be decayed before comparing, so tuple_index_helper<T, Args...> can find T&, const T& and other variants in the tuple types.

Definition at line 106 of file tuple_traits.hpp.

Variable Documentation

◆ kDefaultKldZ

constexpr double beluga::detail::kDefaultKldZ = 3.
constexpr

Default upper standard normal quantile, P = 0.999.

Definition at line 36 of file take_while_kld.hpp.

◆ kDefaultNeighborKernel2d

const std::vector<Eigen::Vector2i> beluga::detail::kDefaultNeighborKernel2d
Initial value:
= {
Eigen::Vector2i{-1, -1},
Eigen::Vector2i{-1, -0},
Eigen::Vector2i{-1, 1},
Eigen::Vector2i{0, -1},
Eigen::Vector2i{0, 0},
Eigen::Vector2i{0, 1},
Eigen::Vector2i{1, -1},
Eigen::Vector2i{1, 0},
Eigen::Vector2i{1, 1},
}

Default neighbor kernel for the 2D NDT sensor model.

Definition at line 107 of file ndt_sensor_model.hpp.

◆ kDefaultNeighborKernel3d

const std::vector<Eigen::Vector3i> beluga::detail::kDefaultNeighborKernel3d
Initial value:
= {
Eigen::Vector3i{0, 0, 0},
Eigen::Vector3i{0, 0, 1},
Eigen::Vector3i{0, 0, -1},
Eigen::Vector3i{0, 1, 0},
Eigen::Vector3i{0, -1, 0},
Eigen::Vector3i{-1, 0, 0},
Eigen::Vector3i{1, 0, 0},
}

Default neighbor kernel for the 3D NDT sensor model.

Definition at line 120 of file ndt_sensor_model.hpp.

◆ kTupleIndexAmbiguous

constexpr std::size_t beluga::detail::kTupleIndexAmbiguous = static_cast<std::size_t>(-2)
staticconstexpr

Constant value to return when there are multiple indices that match the input type.

Definition at line 98 of file tuple_traits.hpp.

◆ kTupleIndexNotFound

constexpr std::size_t beluga::detail::kTupleIndexNotFound = static_cast<std::size_t>(-1)
staticconstexpr

Constant value to return when the index was not found.

Definition at line 95 of file tuple_traits.hpp.



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