diff --git a/.clang-tidy b/.clang-tidy index a12daaba4..e408511ca 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -2,4 +2,6 @@ Checks: '*, -fuchsia-overloaded-operator, -misc-non-private-member-variables-in-classes, -llvmlibc-*, - -modernize-use-trailing-return-type' + -modernize-use-trailing-return-type, + -altera-struct-pack-align, + -fuchsia-trailing-return' diff --git a/include/fcarouge/internal/kalman.hpp b/include/fcarouge/internal/kalman.hpp index 7872a827b..37ef48920 100644 --- a/include/fcarouge/internal/kalman.hpp +++ b/include/fcarouge/internal/kalman.hpp @@ -53,7 +53,7 @@ namespace fcarouge::internal template typename Transpose = transpose, template typename Symmetrize = symmetrize, - template typename Divide = divide, + typename Divide = std::divides, template typename Identity = identity, typename... PredictionArguments> struct kalman { @@ -74,34 +74,28 @@ struct kalman { //! @brief Type of the estimated covariance matrix P. //! //! @details Also known as Σ. - using estimate_uncertainty = - std::invoke_result_t, State, State>; + using estimate_uncertainty = std::invoke_result_t; //! @brief Type of the process noise covariance matrix Q. - using process_uncertainty = - std::invoke_result_t, State, State>; + using process_uncertainty = std::invoke_result_t; //! @brief Type of the observation, measurement noise covariance matrix R. - using output_uncertainty = - std::invoke_result_t, Output, Output>; + using output_uncertainty = std::invoke_result_t; //! @brief Type of the state transition matrix F. //! //! @details Also known as Φ or A. - using state_transition = - std::invoke_result_t, State, State>; + using state_transition = std::invoke_result_t; //! @brief Type of the observation transition matrix H. //! //! @details Also known as C. - using output_model = - std::invoke_result_t, Output, State>; + using output_model = std::invoke_result_t; //! @brief Type of the control transition matrix G. //! //! @details Also known as B. - using input_control = - std::invoke_result_t, State, Input>; + using input_control = std::invoke_result_t; //! @} diff --git a/include/fcarouge/internal/kalman_eigen_operator.hpp b/include/fcarouge/internal/kalman_eigen_operator.hpp index 8f704b5d7..44598b004 100644 --- a/include/fcarouge/internal/kalman_eigen_operator.hpp +++ b/include/fcarouge/internal/kalman_eigen_operator.hpp @@ -46,6 +46,8 @@ For more information, please refer to */ #include +#include + namespace fcarouge::eigen::internal { //! @brief Function object for performing Eigen matrix transposition. @@ -93,20 +95,22 @@ template struct symmetrize { //! //! @details Implemented with the Eigen linear algebra library matrices with //! sizes fixed at compile-time. -//! -//! @tparam Numerator The type template parameter of the dividend. -//! @tparam Denominator The type template parameter of the divisor. -template struct divide { +struct divide { //! @brief Returns the quotient of `numerator` and `denominator`. //! //! @param numerator The dividend of the division. //! @param denominator The divisor of the division. //! //! @exception May throw implementation-defined exceptions. - [[nodiscard]] inline constexpr Eigen::Matrix - operator()(const Numerator &numerator, const Denominator &denominator) const + //! + //! @todo Why compilation fails if we specifcy the return type in the body of + //! the function? + [[nodiscard]] inline constexpr auto operator()(const auto &numerator, + const auto &denominator) const + -> typename Eigen::Matrix< + typename std::decay_t::Scalar, + std::decay_t::RowsAtCompileTime, + std::decay_t::RowsAtCompileTime> { return denominator.transpose() .fullPivHouseholderQr() diff --git a/include/fcarouge/internal/kalman_equation.hpp b/include/fcarouge/internal/kalman_equation.hpp index 943ff55ce..e3c6c5953 100644 --- a/include/fcarouge/internal/kalman_equation.hpp +++ b/include/fcarouge/internal/kalman_equation.hpp @@ -42,6 +42,7 @@ For more information, please refer to */ //! @file //! @brief Kalman filter main project header. +#include #include namespace fcarouge::internal @@ -50,7 +51,7 @@ namespace fcarouge::internal extrapolate_state(const auto &x, const auto &ff, const auto &f, const auto &g, const auto &u) { - using state = std::remove_reference_t>; + using state = std::decay_t; return state{ ff(x, f) + g * u }; } @@ -58,7 +59,7 @@ extrapolate_state(const auto &x, const auto &ff, const auto &f, const auto &g, [[nodiscard]] inline constexpr auto extrapolate_state(const auto &x, const auto &ff, const auto &f) { - using state = std::remove_reference_t>; + using state = std::decay_t; return state{ ff(x, f) }; } @@ -67,10 +68,8 @@ template