|
| typedef policy< std::function< bool(Args...)> > | any_policy |
| |
| typedef BaseRegularGrid< Derived, 2 > | BaseRegularGrid2 |
| |
| typedef BaseRegularGrid< Derived, 3 > | BaseRegularGrid3 |
| |
| typedef BearingSensorModel< LandmarkMap, Sophus::SE2d > | BearingSensorModel2d |
| |
| typedef BearingSensorModel< LandmarkMap, Sophus::SE3d > | BearingSensorModel3d |
| |
| typedef ::testing::Types< Sensor2D, Sensor3D > | BearingSensorModelTestsTypes |
| |
| typedef Numeric< std::size_t, struct ClusterTag > | Cluster |
| |
| typedef typename common_tuple_type< T, U >::type | common_tuple_type_t |
| |
| typedef typename decay_tuple_like< T >::type | decay_tuple_like_t |
| |
| typedef DifferentialDriveModel< Sophus::SE2d > | DifferentialDriveModel2d |
| |
| typedef DifferentialDriveModel< Sophus::SE3d > | DifferentialDriveModel3d |
| |
| typedef Eigen::Vector3d | LandmarkBearing3 |
| |
| typedef uint32_t | LandmarkCategory |
| |
| typedef Eigen::AlignedBox3d | LandmarkMapBoundaries |
| |
| typedef Eigen::Vector3d | LandmarkPosition3 |
| |
| typedef LandmarkSensorModel< LandmarkMap, Sophus::SE2d > | LandmarkSensorModel2d |
| |
| typedef LandmarkSensorModel< LandmarkMap, Sophus::SE3d > | LandmarkSensorModel3d |
| |
| typedef NDTCell< 2, double > | NDTCell2d |
| |
| typedef NDTCell< 2, float > | NDTCell2f |
| |
| typedef NDTCell< 3, double > | NDTCell3d |
| |
| typedef NDTCell< 3, float > | NDTCell3f |
| |
| typedef NDTModelParam< 2 > | NDTModelParam2d |
| |
| typedef NDTModelParam< 3 > | NDTModelParam3d |
| |
| typedef CircularArray< T, N, CircularArrayFeatureFlags::kRolloverOnWrite|CircularArrayFeatureFlags::kExtrapolateOnRead|CircularArrayFeatureFlags::kLayoutReversal > | RollingWindow |
| |
| typedef beluga::BearingSensorModel2d< LandmarkMap > | Sensor2D |
| |
| typedef beluga::BearingSensorModel3d< LandmarkMap > | Sensor3D |
| |
| typedef testing::Types< std::unordered_map< Eigen::Vector2i, int, Hasher >, std::map< Eigen::Vector2i, int, Less > > | SparseGridTestCases |
| |
| typedef SparseValueGrid< MapType, 2 > | SparseValueGrid2 |
| |
| typedef SparseValueGrid< MapType, 3 > | SparseValueGrid3 |
| |
| typedef typename particle_traits< T >::state_type | state_t |
| |
| typedef Numeric< double, struct StrongDoubleTag > | strong_double |
| |
| typedef Numeric< std::size_t, struct StrongSizeTTag > | strong_size_t |
| |
| typedef Numeric< std::size_t, struct StrongSizeTTag2 > | strong_size_t_2 |
| |
| typedef typename tuple_index< T, TupleLike >::type | tuple_index_t |
| |
| typedef beluga::BeamSensorModel< StaticOccupancyGrid< 5, 5 > > | UUT |
| |
| typedef std::vector< T, std::allocator< T > > | Vector |
| |
| typedef Numeric< double, struct WeightTag > | Weight |
| |
| typedef typename particle_traits< T >::weight_type | weight_t |
| |
|
| Sophus::Matrix2< Scalar > | calculate_covariance (Range &&range, const Sophus::Vector2< Scalar > &mean) |
| |
| Sophus::Matrix2< Scalar > | calculate_covariance (Range &&range, WeightsRange &&normalized_weights, const Sophus::Vector2< Scalar > &mean) |
| |
| auto | cluster_based_estimate (States &&states, Weights &&weights, ParticleClusterizerParam parameters={}) |
| |
| auto | effective_sample_size (Range &&range) |
| |
| constexpr decltype(auto) | element (TupleLike &&tuple) noexcept |
| |
| std::pair< Sophus::SE2< Scalar >, Sophus::Matrix3< Scalar > > | estimate (Poses &&poses) |
| |
| std::pair< Sophus::SE2< Scalar >, Sophus::Matrix3< Scalar > > | estimate (Poses &&poses, Weights &&weights) |
| |
| std::pair< Scalar, Scalar > | estimate (Scalars &&scalars, Weights &&weights) |
| |
| auto | estimate_clusters (States &&states, Weights &&weights, Clusters &&clusters) |
| |
| double | expected_aggregate_probability (std::vector< double > landmark_probs) |
| |
| constexpr auto && | forward_like (U &&value) noexcept |
| |
| constexpr T && | get (CircularArray< T, N, F > &&array) noexcept |
| |
| constexpr T & | get (CircularArray< T, N, F > &array) noexcept |
| |
| constexpr const T && | get (const CircularArray< T, N, F > &&array) noexcept |
| |
| constexpr const T & | get (const CircularArray< T, N, F > &array) noexcept |
| |
| BearingModelParam | get_default_model_params () |
| |
| T | get_robot_pose_in_world () |
| |
| Sophus::SE2d | get_robot_pose_in_world< Sophus::SE2d > () |
| |
| 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) |
| |
| auto | make_sensor_data (std::vector< std::tuple< double, double, double, uint32_t >> detections) |
| |
| | MultivariateNormalDistribution (const T &, const typename multivariate_distribution_traits< T >::covariance_type &) -> MultivariateNormalDistribution< typename multivariate_distribution_traits< T >::result_type > |
| |
| | MultivariateUniformDistribution (const BaseOccupancyGrid2< Derived > &) -> MultivariateUniformDistribution< Sophus::SE2d, Derived > |
| |
| | MultivariateUniformDistribution (const Eigen::AlignedBox2d &) -> MultivariateUniformDistribution< Sophus::SE2d, Eigen::AlignedBox2d > |
| |
| | MultivariateUniformDistribution (const Eigen::AlignedBox3d &) -> MultivariateUniformDistribution< Sophus::SE3d, Eigen::AlignedBox3d > |
| |
| auto | nearest_obstacle_distance_map (Range &&obstacle_map, DistanceFunction &&distance_function, NeighborsFunction &&neighbors_function) |
| |
| constexpr bool | operator& (CircularArrayFeatureFlags mask, CircularArrayFeatureFlags flag) |
| |
| CircularArray< T, N, F > & | operator<< (CircularArray< T, N, F > &array, T value) |
| |
| constexpr CircularArrayFeatureFlags | operator| (CircularArrayFeatureFlags lflag, CircularArrayFeatureFlags rflag) |
| |
| constexpr void | swap (CircularArray< T, N, F > &a, CircularArray< T, N, G > &b) |
| |
| | 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) |
| |
| Sophus::SE3d | To3d (const Sophus::SE2d &tf) |
| |
| | TupleVector (I, S) -> TupleVector< decay_tuple_like_t< ranges::iter_value_t< I >>> |
| |
| | 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,) |
| |