@@ -81,16 +81,15 @@ template <typename State, typename Output, typename Input, typename UpdateTypes,
81
81
" discarded." )]] inline constexpr auto
82
82
kalman<State, Output, Input, UpdateTypes, PredictionTypes>::u() const
83
83
-> const input &requires (not std::is_same_v<Input, void >) {
84
- return filter.u ;
85
- }
84
+ return filter.u ;
85
+ }
86
86
87
87
template <typename State, typename Output, typename Input, typename UpdateTypes,
88
88
typename PredictionTypes>
89
89
[[nodiscard(" The returned estimated covariance matrix P is unexpectedly "
90
- " discarded." )]] inline constexpr auto kalman<State, Output, Input,
91
- UpdateTypes,
92
- PredictionTypes>::p()
93
- const -> const estimate_uncertainty & {
90
+ " discarded." )]] inline constexpr auto
91
+ kalman<State, Output, Input, UpdateTypes, PredictionTypes>::p() const
92
+ -> const estimate_uncertainty & {
94
93
return filter.p ;
95
94
}
96
95
@@ -245,26 +244,24 @@ template <typename State, typename Output, typename Input, typename UpdateTypes,
245
244
" discarded." )]] inline constexpr auto
246
245
kalman<State, Output, Input, UpdateTypes, PredictionTypes>::g() const
247
246
-> const input_control &requires (not std::is_same_v<Input, void >) {
248
- return filter.g ;
249
- }
247
+ return filter.g ;
248
+ }
250
249
251
250
template <typename State, typename Output, typename Input, typename UpdateTypes,
252
251
typename PredictionTypes>
253
252
[[nodiscard(" The returned control transition matrix G is unexpectedly "
254
- " discarded." )]] inline constexpr auto kalman<State, Output, Input,
255
- UpdateTypes,
256
- PredictionTypes>::g()
253
+ " discarded." )]] inline constexpr auto
254
+ kalman<State, Output, Input, UpdateTypes, PredictionTypes>::g()
257
255
-> input_control &requires (not std::is_same_v<Input, void >) {
258
- return filter.g ;
259
- }
256
+ return filter.g ;
257
+ }
260
258
261
259
template <typename State, typename Output, typename Input, typename UpdateTypes,
262
260
typename PredictionTypes>
263
- inline constexpr void kalman<State, Output, Input, UpdateTypes,
264
- PredictionTypes>::g(const auto &value,
265
- const auto &...values)
266
- requires (not std::is_same_v<Input, void >)
267
- {
261
+ inline constexpr void
262
+ kalman<State, Output, Input, UpdateTypes, PredictionTypes>::g(
263
+ const auto &value,
264
+ const auto &...values) requires(not std::is_same_v<Input, void >) {
268
265
if constexpr (std::is_convertible_v<decltype (value), input_control>) {
269
266
filter.g = std::move (input_control{value, values...});
270
267
} else {
0 commit comments