diff --git a/.github/workflows/ci_pipeline.yml b/.github/workflows/ci_pipeline.yml index de2590b63..af05e668d 100644 --- a/.github/workflows/ci_pipeline.yml +++ b/.github/workflows/ci_pipeline.yml @@ -41,7 +41,6 @@ jobs: pre-commit run --all-files --verbose --show-diff-on-failure build-docs: - if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/main' }} runs-on: ubuntu-22.04 env: REPOSITORY_CHECKOUT_PATH: ${{ github.workspace }}/repository @@ -65,7 +64,8 @@ jobs: working-directory: ${{ env.REPOSITORY_CHECKOUT_PATH }} run: beluga/docs/generate_docs.sh - - name: Deploy documentation + - if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/main' }} + name: Deploy documentation working-directory: ${{ env.DOXYGEN_HTML_OUTPUT }} env: COMMIT_MESSAGE: "Triggered by commit ${{ github.sha }}." diff --git a/beluga/docs/Doxyfile b/beluga/docs/Doxyfile index f0abc15a9..e1989a34f 100644 --- a/beluga/docs/Doxyfile +++ b/beluga/docs/Doxyfile @@ -9,5 +9,4 @@ GENERATE_LATEX = NO HTML_OUTPUT = $(DOXYGEN_HTML_OUTPUT) HTML_EXTRA_STYLESHEET = ./doxygen_extra.css CITE_BIB_FILES = ./doxygen_cites.bib -# TODO(nahuel): Reenable this when there are no warnings. -WARN_AS_ERROR = NO +WARN_AS_ERROR = YES diff --git a/beluga/docs/doxygen_extra.css b/beluga/docs/doxygen_extra.css index 43f41563e..185818ef0 100644 --- a/beluga/docs/doxygen_extra.css +++ b/beluga/docs/doxygen_extra.css @@ -1,8 +1,9 @@ -/* Highlight inline code in paragraphs and description list elements */ -p > code, dd > code { +/* Highlight inline code in paragraphs, tables and list elements */ +p > code, dd > code, li > code, td > code { background-color: #ecedf0; border-radius: .5rem; padding: 0 .3rem; + font-size: 0.8rem; } /* Highlight multiline code fragments */ diff --git a/beluga/include/beluga/algorithm/estimation.hpp b/beluga/include/beluga/algorithm/estimation.hpp index 79bc7496c..7095cb0eb 100644 --- a/beluga/include/beluga/algorithm/estimation.hpp +++ b/beluga/include/beluga/algorithm/estimation.hpp @@ -33,12 +33,12 @@ namespace beluga { /// Calculates the covariance of a range given its mean. /** * \tparam Range A [sized range](https://en.cppreference.com/w/cpp/ranges/sized_range) type whose - * Range::value_type is Eigen::Vector2. + * `Range::value_type` is `Eigen::Vector2`. * \tparam Scalar An scalar type, e.g. double or float. * \param range Range to be used to calculate the covariance. * \param mean The previously calculated mean of range. The value must be correct for the resulting * covariance to be correct. - * \return The calculated covariance, as a Eigen::Matrix2. + * \return The calculated covariance, as a `Eigen::Matrix2`. */ template Eigen::Matrix2 covariance(const Range& range, const Eigen::Vector2& mean) { @@ -76,7 +76,7 @@ Eigen::Matrix2 covariance(const Range& range, const Eigen::Vector2 diff --git a/beluga/include/beluga/algorithm/particle_filter.hpp b/beluga/include/beluga/algorithm/particle_filter.hpp index f6e5487df..436ef8385 100644 --- a/beluga/include/beluga/algorithm/particle_filter.hpp +++ b/beluga/include/beluga/algorithm/particle_filter.hpp @@ -45,18 +45,18 @@ * - A possibly const instance `cp` of `T`. * * The following is satisfied: - * - `particle_traits::state_type` is a valid type. - * - `particle_traits::state(cp)` returns an instance of `particle_traits::state_type`. - * - Given `s` an instance of `particle_traits::state_type`, `particle_traits::state(p) = s` - * is a valid expression and assigns the state `s` to the particle `p`. - * i.e. after the assignment `s == particle_traits::state(p)` is `true`. - * - `particle_traits::weight_type` is a valid arithmetic type (that is, an integral + * - \c particle_traits::state_type is a valid type. + * - \c particle_traits::state(cp) returns an instance of \c particle_traits::state_type. + * - Given `s` an instance of \c particle_traits::state_type, \c particle_traits::state(p) = `s` + * is a valid expression and assigns the state `s` to the particle `p`. \n + * i.e. after the assignment `s` == \c particle_traits::state(p) is `true`. + * - \c particle_traits::weight_type is a valid arithmetic type (that is, an integral * type or a floating-point type). - * - `particle_traits::weight(cp)` is a valid expression and the return type is - * `particle_traits::weight_type`. - * - Given `w` an instance of `particle_traits::weight_type`, `particle_traits::weight(p) = w` - * is a valid expression and assigns the weight `w` to the particle `p`. - * i.e. after the assignment `w == particle_traits::weight(p)` is `true`. + * - \c particle_traits::weight(cp) is a valid expression and the return type is + * \c particle_traits::weight_type. + * - Given `w` an instance of \c particle_traits::weight_type, \c particle_traits::weight(p) = `w` + * is a valid expression and assigns the weight `w` to the particle `p`. \n + * i.e. after the assignment `w` == \c particle_traits::weight(p) is `true`. */ /** @@ -113,13 +113,14 @@ namespace beluga { * BootstrapParticleFilter is an implementation of the * \ref BaseParticleFilterPage "BaseParticleFilter" named requirements. * - * `particle_traits::state_type` must be the same as - * the state_type of the sensor and motion model. + * Given `T`, the type named by \c Container::value_type, + * - \c particle_traits::state_type must be the same as the `state_type` of the sensor + * and motion model. * - * `particle_traits::weight_type` must be the same as the weight - * type used in the sensor mode. + * - \c particle_traits::weight_type must be the same as the `weight_type` used in the + * sensor mode. * - * \tparam The mixed-in type. An instance m of Mixin must provide a protected method, + * \tparam Mixin The mixed-in type. An instance m of Mixin must provide a protected method, * `m.self()`. The return type of `m.self()` must satisfy: * - \ref ParticleResamplingPage "ParticleResampling" * - \ref ParticleBaselineGenerationPage "ParticleBaselineGeneration" @@ -138,8 +139,8 @@ struct BootstrapParticleFilter : public Mixin { /// Constructs a BootstrapParticleFilter. /** - * The initial particles are generated using the ParticleBaselineGeneration implementation of - * Mixin. + * The initial particles are generated using the \ref ParticleBaselineGenerationPage "ParticleBaselineGeneration" + * implementation of `Mixin`. * * \tparam ...Args Arguments types for the remaining mixin constructors. * \param ...args arguments that are not used by this part of the mixin, but by others. @@ -168,7 +169,7 @@ struct BootstrapParticleFilter : public Mixin { /// Reinitializes the filter with a given range view to the new particle states. /** * The particle filter will be initialized with the first `max_samples` states of the range, - * determined by the ParticleResampling named requirements. + * determined by the \ref ParticleResamplingPage "ParticleResampling" named requirements. * * \tparam View Range view type whose elements are of the same type as `particle_type::state_type`. * \param states A state range view to reinitialize the filter. @@ -190,8 +191,8 @@ struct BootstrapParticleFilter : public Mixin { /// Update the particles states based on the motion model and the last pose update. /** - * The update will be done based on the Mixin implementation of the MotionModel named - * requirement. + * The update will be done based on the `Mixin` implementation of the + * \ref MotionModelPage "MotionModel" named requirement. */ void sample() { const auto states = views::states(particles_); @@ -202,8 +203,8 @@ struct BootstrapParticleFilter : public Mixin { /// Update the particle weights based on the sensor model. /** - * The update will be done based on the Mixin implementation of the SensorModel named - * requirement. + * The update will be done based on the `Mixin` implementation of the \ref SensorModelPage "SensorModel" + * named requirement. */ void importance_sample() { const auto states = views::states(particles_); @@ -214,8 +215,9 @@ struct BootstrapParticleFilter : public Mixin { /// Resample particles based on ther weights and the resampling policy used. /** - * The update will be done based on the Mixin implementation of the ParticleSampledGeneration and - * ParticleResampling named requirements. + * The update will be done based on the Mixin implementation of the + * \ref ParticleSampledGenerationPage "ParticleSampledGeneration" and + * \ref ParticleResamplingPage "ParticleResampling" named requirements. */ void resample() { particles_ = initialize_container(this->self().generate_samples_from(particles_) | this->self().take_samples()); @@ -248,8 +250,8 @@ struct BootstrapParticleFilter : public Mixin { * MCL is an implementation of the \ref ParticleFilterPage "ParticleFilter" * named requirements. * - * \tparam MotionModel MotionModel must implement the MotionModel named requirement. - * \tparam SensorModel MotionModel must implement the SensorModel named requirement. + * \tparam MotionModel MotionModel must implement the \ref MotionModelPage "MotionModel" named requirement. + * \tparam SensorModel MotionModel must implement the \ref SensorModelPage "SensorModel" named requirement. * \tparam State The state of the particle type. * \tparam Container The particle container type. * It must satisfy the \ref ParticleContainerPage "ParticleContainer" named requirements. @@ -286,8 +288,8 @@ struct MCL : public ciabatta::mixin< * AMCL is an implementation of the \ref ParticleFilterPage "ParticleFilter" * named requirements. * - * \tparam MotionModel MotionModel must implement the MotionModel named requirement. - * \tparam SensorModel MotionModel must implement the SensorModel named requirement. + * \tparam MotionModel MotionModel must implement the \ref MotionModelPage "MotionModel" named requirement. + * \tparam SensorModel MotionModel must implement the \ref SensorModelPage "SensorModel" named requirement. * \tparam State The state of the particle type. * \tparam Container The particle container type. * It must satisfy the \ref ParticleContainerPage "ParticleContainer" named requirements. diff --git a/beluga/include/beluga/algorithm/sampling.hpp b/beluga/include/beluga/algorithm/sampling.hpp index 6dfa194c1..17be0bde5 100644 --- a/beluga/include/beluga/algorithm/sampling.hpp +++ b/beluga/include/beluga/algorithm/sampling.hpp @@ -91,8 +91,8 @@ namespace beluga { /// Selects between executing one function or another randomly. /** - * \tparam Function1 Callable type, with prototype () -> Ret. - * \tparam Function2 Callable type, with prototype () -> Ret. + * \tparam Function1 Callable type, with prototype `() -> Ret`. + * \tparam Function2 Callable type, with prototype `() -> Ret`. * The return type of both Function1 and Function2 must be the same. * \tparam RandomNumberGenerator Must meet the requirements of * [UniformRandomBitGenerator](https://en.cppreference.com/w/cpp/named_req/UniformRandomBitGenerator). @@ -103,7 +103,7 @@ namespace beluga { * In the rest of the cases, second is called. * A Bernoully distribution is used. * \return The result of the called function. - * The return type is decltype(first()). + * The return type is `decltype(first())`. */ template auto random_select(Function1 first, Function2 second, RandomNumberGenerator& generator, double probability) { @@ -124,10 +124,10 @@ auto random_select(Function1 first, Function2 second, RandomNumberGenerator& gen * \param samples The container of samples to be picked. * \param weights The weights of the samples to be picked. * The size of the container must be the same as the size of samples. - * For a sample samples[i], its weight is weights[i]. + * For a sample `samples[i]`, its weight is `weights[i]`. * \param generator The random number generator used. * \return The picked sample. - * Its type is the same as the Range value type. + * Its type is the same as the `Range` value type. */ template auto random_sample(const Range& samples, const Weights& weights, RandomNumberGenerator& generator) { @@ -140,11 +140,11 @@ auto random_sample(const Range& samples, const Weights& weights, RandomNumberGen /// Returns a callable object that allows setting the cluster of a particle. /** * \param resolution The size along any axis of the spatial cluster cell. - * \return A callable object with prototype (ParticleT && p) -> ParticleT. - * ParticleT must satisfy the \ref ParticlePage "Particle" named requirements. - * The expression particle_traits::cluster(p) must also - * be valid and return a `std::size_t &`. - * After the returned object is applied to a particle p, cluster(p) will be updated + * \return A callable object with prototype `(ParticleT && p) -> ParticleT`. \n + * `ParticleT` must satisfy the \ref ParticlePage "Particle" named requirements. \n + * The expression \c particle_traits::cluster(p) must also + * be valid and return a `std::size_t &`. \n + * After the returned object is applied to a particle `p`, \c cluster(p) will be updated * with the calculated spatial hash according to the specified resolution. */ inline auto set_cluster(double resolution) { @@ -159,14 +159,17 @@ inline auto set_cluster(double resolution) { /// 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. + * distance epsilon between the maximum likelihood estimate and the true distribution. \n * 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 = 0.900 -> Z = 1.28155156327703 - * - P = 0.950 -> Z = 1.64485362793663 - * - P = 0.990 -> Z = 2.32634787735669 - * - P = 0.999 -> Z = 3.09023224677087 + * | 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. * @@ -175,12 +178,12 @@ inline auto set_cluster(double resolution) { * distrubution. * \param z Upper standard normal quantile for the probability that the error in the * estimated distribution is less than epsilon. - * \return A callable object with prototype (std::size_t hash) -> bool. - * hash is the spatial hash of the particle being added. + * \return A callable object with prototype `(std::size_t hash) -> bool`. + * `hash` is the spatial hash of the particle being added. \n * The returned callable object is stateful, tracking the total number of particles and - * the particle clusters based on the spatial hash. - * The return value 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. + * the particle clusters based on the spatial hash. \n + * 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. \n * i.e. A return value of true means that you need to keep sampling to satisfy the condition. */ inline auto kld_condition(std::size_t min, double epsilon, double z = 3.) { @@ -206,8 +209,9 @@ inline auto kld_condition(std::size_t min, double epsilon, double z = 3.) { * An implementation of the \ref ParticleBaselineGenerationPage "ParticleBaselineGeneration" * named requirements. * - * \tparam Mixin The mixed-in type. An instance m of Mixin must provide a protected method, - * m.self(). The return type of m.self() must satisfy the SensorModel named requirements. + * \tparam Mixin The mixed-in type. An instance `m` of `Mixin` must provide a protected method, + * `m.self()`. The return type of `m.self()` must satisfy the \ref SensorModelPage "SensorModel" + * named requirements. * \tparam RandomNumberGenerator A random number generator, must satisfy the * [UniformRandomBitGenerator]( * https://en.cppreference.com/w/cpp/named_req/UniformRandomBitGenerator) requirements. @@ -229,7 +233,7 @@ struct BaselineGeneration : public Mixin { * model. See \ref SensorModelPage "SensorModel". * * \tparam Particle The particle type, must satisfy the \ref ParticlePage "Particle" named requirements. - * \return range with the generated particles. + * \return A range with the generated particles. */ template [[nodiscard]] auto generate_samples() { @@ -290,10 +294,10 @@ struct AdaptiveGenerationParam { * The addition of random samples allows the filter to recover. * It determines how many random particles to add by averaging the weights of the particles. * The estimate used considers a short-term and a long-term average. - * See Probabilistic Robotics \cite thrun2005probabilistic, Chapter `8.3.3`. + * See Probabilistic Robotics \cite thrun2005probabilistic, Chapter 8.3.3. * * \tparam Mixin The mixed-in type. An instance m of Mixin must provide a protected method, - * m.self(). The return type of m.self() must satisfy the SensorModel named requirements. + * `m.self()`. The return type of `m.self()` must satisfy the \ref SensorModelPage "SensorModel" named requirements. * \tparam RandomNumberGenerator A random number generator, must satisfy the * [UniformRandomBitGenerator]( * https://en.cppreference.com/w/cpp/named_req/UniformRandomBitGenerator) requirements. @@ -318,7 +322,7 @@ struct AdaptiveGeneration : public Mixin { /// Generates new particles from the given input particles. /** * A random state will be generated with a probability of - * P = max(0, 1 - fast_filter_average / slow_filter_average) + * `P = max(0, 1 - fast_filter_average / slow_filter_average)` * where the filters are configured according to param_type specified in the constructor. * If not, a previous particle will be sampled. * @@ -385,7 +389,7 @@ struct FixedResampling : public Mixin { /// Returns the minimum number of particles to be sampled. /** * This policy uses a fixed number of particles, so the return value is equal - * to this->max_samples() and also to FixedResamplingParam::max_samples parameter + * to max_samples() and also to FixedResamplingParam::max_samples parameter * specified in the constructor. * * \return Minimum number of particles to be sampled. @@ -394,7 +398,7 @@ struct FixedResampling : public Mixin { /// Returns the maximum number of particles to be sampled. /** * This policy uses a fixed number of particles, so the return value is equal - * to this->min_samples() and also to FixedResamplingParam::max_samples parameter + * to min_samples() and also to FixedResamplingParam::max_samples parameter * specified in the constructor. * * \return Maximum number of particles to be sampled. @@ -473,11 +477,11 @@ struct KldResampling : public Mixin { * It can only be composed with a range whose value type satisfies: * - The \ref ParticlePage "Particle" named requirements. * - Given `P` the range value type, `p` an instance of `P`, `cp` a possibly const instance of `P`. - * The expression `particle_traits

::cluster(cp)` returns a `std::size_t` that represents the spatial - * hash of the particle `cp`. - * Given a `std::size_t` hash, the expression `particle_traits

::cluster(p) = hash` is valid and - * assigns the cluster hash to the particle `p`. - * i.e. after the assignment `hash == particle_traits

::cluster(p)` is `true`. + * - The expression \c particle_traits

::cluster(cp) returns a `std::size_t` that represents the spatial + * hash of the particle `cp`. + * - Given a `std::size_t hash`, the expression \c particle_traits

::cluster(p) = `hash` is valid and + * assigns the cluster hash to the particle `p`. \n + * i.e. after the assignment `hash` == \c particle_traits

::cluster(p) is true. */ [[nodiscard]] auto take_samples() const { return ranges::views::transform(set_cluster(parameters_.spatial_resolution)) | diff --git a/beluga/include/beluga/motion/differential_drive_model.hpp b/beluga/include/beluga/motion/differential_drive_model.hpp index 2ca574f09..9b6c9b4f2 100644 --- a/beluga/include/beluga/motion/differential_drive_model.hpp +++ b/beluga/include/beluga/motion/differential_drive_model.hpp @@ -31,17 +31,32 @@ namespace beluga { /// Parameters to construct a DifferentialDriveModel instance. /** - * See Probabilistic Robotics \cite thrun2005probabilistic Chapter `5.4.2`, particularly table `5.6`. + * See Probabilistic Robotics \cite thrun2005probabilistic Chapter 5.4.2, particularly table 5.6. */ struct DifferentialDriveModelParam { - /// alpha1, how much rotational noise is generated by the relative rotation between the last two odometry updates. + /// Rotational noise from rotation + /** + * How much rotational noise is generated by the relative rotation between the last two odometry updates. + * Also known as `alpha1`. + */ double rotation_noise_from_rotation; - /// alpha2, how much rotational noise is generated by the relative translation between the last two odometry updates. + /// Rotational noise from translation + /** + * How much rotational noise is generated by the relative translation between the last two odometry updates. + * Also known as `alpha2`. + */ double rotation_noise_from_translation; - /// alpha3, how much translational noise is generated by the relative translation between the last two odometry - /// updates. + /// Translational noise from translation + /** + * How much translational noise is generated by the relative translation between the last two odometry updates. + * Also known as `alpha3`. + */ double translation_noise_from_translation; - /// alpha4, how much translational noise is generated by the relative rotation between the last two odometry updates. + /// Translational noise from rotation + /** + * How much translational noise is generated by the relative rotation between the last two odometry updates. + * Also known as `alpha4`. + */ double translation_noise_from_rotation; /// Distance threshold to detect in-place rotation. double distance_threshold = 0.01; diff --git a/beluga/include/beluga/random/multivariate_normal_distribution.hpp b/beluga/include/beluga/random/multivariate_normal_distribution.hpp index 9fab33368..0129ef13b 100644 --- a/beluga/include/beluga/random/multivariate_normal_distribution.hpp +++ b/beluga/include/beluga/random/multivariate_normal_distribution.hpp @@ -29,7 +29,7 @@ namespace beluga { /// Multivariate normal distribution. /** - * MultivariateNormalDistribution is an implementation of the + * `MultivariateNormalDistribution` is an implementation of the * \ref RandomStateDistributionRequirements "RandomStateDistribution" named requirements that * represents a multi-dimensional normal distribution of real-valued random variables. * @@ -57,7 +57,7 @@ class MultivariateNormalDistribution { /// Constructs a parameter set instance. /** - * \tparam InputType The input type derived from EigenBase. + * \tparam InputType The input type derived from `EigenBase`. * \param covariance Real symmetric matrix that represents the covariance of the random variable. * * \throw std::runtime_error If the provided covariance is invalid. @@ -67,7 +67,7 @@ class MultivariateNormalDistribution { /// Constructs a parameter set instance. /** - * \tparam InputType The input type derived from EigenBase. + * \tparam InputType The input type derived from `EigenBase`. * \param mean A vector that represents the mean value of the random variable. * \param covariance Real symmetric matrix that represents the covariance of the random variable. * @@ -80,7 +80,7 @@ class MultivariateNormalDistribution { /// Compares this object with other parameter set object. /** * \param other Parameter set object to compare against. - * \return true if the objects are equal, false otherwise. + * \return True if the objects are equal, false otherwise. */ [[nodiscard]] bool operator==(const Param& other) const { return mean_ == other.mean_ && transform_ == other.transform_; @@ -89,7 +89,7 @@ class MultivariateNormalDistribution { /// Compares this object with other parameter set object. /** * \param other Parameter set object to compare against. - * \return true if the objects are not equal, false otherwise. + * \return True if the objects are not equal, false otherwise. */ [[nodiscard]] bool operator!=(const Param& other) const { return !(*this == other); } @@ -137,7 +137,7 @@ class MultivariateNormalDistribution { /// Constructs a MultivariateNormalDistribution with zero mean and the given covariance. /** - * \tparam InputType The input type derived from EigenBase. + * \tparam InputType The input type derived from `EigenBase`. * \param covariance Real symmetric matrix that represents the covariance of the random variable. * * \throw std::runtime_error If the provided covariance is invalid. @@ -147,7 +147,7 @@ class MultivariateNormalDistribution { /// Constructs a MultivariateNormalDistribution with the given mean and covariance. /** - * \tparam InputType The input type derived from EigenBase. + * \tparam InputType The input type derived from `EigenBase`. * \param mean A vector that represents the mean value of the random variable. * \param covariance Real symmetric matrix that represents the covariance of the random variable. * @@ -203,7 +203,7 @@ class MultivariateNormalDistribution { * In other words, if they are invoked with equal generators, they generate the same sequence. * * \param other Distribution object to compare against. - * \return true if the objects are equal, false otherwise. + * \return True if the objects are equal, false otherwise. */ [[nodiscard]] bool operator==(const MultivariateNormalDistribution& other) const { return params_ == other.params_ && distribution_ == other.distribution_; @@ -215,7 +215,7 @@ class MultivariateNormalDistribution { * In other words, if they are invoked with equal generators, they generate the same sequence. * * \param other Distribution object to compare against. - * \return true if the objects are not equal, false otherwise. + * \return True if the objects are not equal, false otherwise. */ [[nodiscard]] bool operator!=(const MultivariateNormalDistribution& other) const { return !(*this == other); } diff --git a/beluga/include/beluga/sensor/likelihood_field_model.hpp b/beluga/include/beluga/sensor/likelihood_field_model.hpp index 02cd930eb..0fef16bae 100644 --- a/beluga/include/beluga/sensor/likelihood_field_model.hpp +++ b/beluga/include/beluga/sensor/likelihood_field_model.hpp @@ -37,11 +37,14 @@ namespace beluga { /// Parameters used to construct a LikelihoodFieldModel instance. /** - * See Probabilistic Robotics \cite thrun2005probabilistic Chapter `6.4`, particularly Table `6.3`. + * See Probabilistic Robotics \cite thrun2005probabilistic Chapter 6.4, particularly Table 6.3. */ struct LikelihoodFieldModelParam { - /// When creating a distance map, if the distance to an obstacle is higher than the value specified here, - /// then this value will be used. + /// Maximum distance to obstacle. + /** + * When creating a distance map, if the distance to an obstacle is higher than the value specified here, + * then this value will be used. + */ double max_obstacle_distance; /// Maximum range of a laser ray. double max_laser_distance; @@ -49,8 +52,10 @@ struct LikelihoodFieldModelParam { double z_hit; /// Weight used to combine the probability of random noise in perception. double z_random; - /// Standard deviation of a gaussian centered arounds obstacles, used to calculate the - /// probability of the obstacle being hit. + /// Standard deviation of a gaussian centered arounds obstacles. + /** + * Used to calculate the probability of the obstacle being hit. + */ double sigma_hit; }; diff --git a/beluga/include/beluga/tuple_vector.hpp b/beluga/include/beluga/tuple_vector.hpp index 548cc7691..95ca56863 100644 --- a/beluga/include/beluga/tuple_vector.hpp +++ b/beluga/include/beluga/tuple_vector.hpp @@ -35,8 +35,8 @@ class TupleContainer; /// An implementation of a tuple of containers, with an interface that looks like a container of tuples. /** - * i.e. though this is implemented internally as a Tuple...>, the interface looks like - * a InternalContainer...>. + * i.e. though this is implemented internally as a `Tuple...>`, the interface looks like + * an `InternalContainer...>`. * It provides the convenience of the second, but when iterating over only one of the elements of the tuple in the * container it has better performance (because of cache locality). * To that end, use for example `views::all(tuple_container) | views::elements<0>` to iterate over the first element of diff --git a/beluga/include/beluga/type_traits/particle_traits.hpp b/beluga/include/beluga/type_traits/particle_traits.hpp index 4ffe50148..23398fdf4 100644 --- a/beluga/include/beluga/type_traits/particle_traits.hpp +++ b/beluga/include/beluga/type_traits/particle_traits.hpp @@ -42,7 +42,7 @@ struct decay_tuple_types> { using type = Tuple...>; }; -/// Same as `decay_tuple_types::type`. +/// Same as decay_tuple_types::type. template using decay_tuple_types_t = typename decay_tuple_types::type; @@ -53,7 +53,7 @@ struct decay_tuple { using type = decay_tuple_types_t>; }; -/// Same as `decay_tuple::type`. +/// Same as decay_tuple::type. template using decay_tuple_t = typename decay_tuple::type; @@ -243,7 +243,7 @@ constexpr auto clusters(Container&& container) { /** * \tparam Particle The particle type to be used. * \tparam T The particle state type. - * T must be convertible to `particle_traits::state_type`. + * T must be convertible to \c particle_traits::state_type. * \param value The state to make the particle from. * \return The new particle, created from the given state. */ diff --git a/beluga/include/beluga/views.hpp b/beluga/include/beluga/views.hpp index 1c4b4ec60..b14ce4dc3 100644 --- a/beluga/include/beluga/views.hpp +++ b/beluga/include/beluga/views.hpp @@ -27,7 +27,7 @@ namespace beluga::views { /// Returns [range adaptor object](https://en.cppreference.com/w/cpp/named_req/RangeAdaptorObject) that -/// will apply std::get to each value in the range lazily. +/// will apply `std::get` to each value in the range lazily. /** * \tparam N Element to get from the array or tuple. * \param particle Tuple or array instance, with at least `N + 1` elements.