ekf2: update include guards

This commit is contained in:
Daniel Agar 2023-09-19 11:48:13 +02:00
parent 51dbd8ee4c
commit 8a9a303354
4 changed files with 16 additions and 4 deletions

View File

@ -47,7 +47,8 @@
* @author Mathieu Bresciani <mathieu@auterion.com>
*/
#pragma once
#ifndef EKF_BIAS_ESTIMATOR_HPP
#define EKF_BIAS_ESTIMATOR_HPP
#include <matrix/math.hpp>
#include <mathlib/mathlib.h>
@ -133,3 +134,5 @@ private:
static constexpr float _innov_sequence_monitnoring_time_constant{10.f}; ///< in seconds
static constexpr float _process_var_boost_gain{1.0e3f};
};
#endif // !EKF_BIAS_ESTIMATOR_HPP

View File

@ -35,7 +35,8 @@
* @file height_bias_estimator.hpp
*/
#pragma once
#ifndef EKF_HEIGHT_BIAS_ESTIMATOR_HPP
#define EKF_HEIGHT_BIAS_ESTIMATOR_HPP
#include "bias_estimator.hpp"
@ -72,3 +73,5 @@ private:
bool _is_sensor_fusion_active{false}; // TODO: replace by const ref and remove setter when migrating _control_status.flags from union to bool
};
#endif // !EKF_HEIGHT_BIAS_ESTIMATOR_HPP

View File

@ -35,7 +35,8 @@
* @file position_bias_estimator.hpp
*/
#pragma once
#ifndef EKF_POSITION_BIAS_ESTIMATOR_HPP
#define EKF_POSITION_BIAS_ESTIMATOR_HPP
#include "bias_estimator.hpp"
@ -111,3 +112,5 @@ private:
bool _is_sensor_fusion_active{false}; // TODO: replace by const ref and remove setter when migrating _control_status.flags from union to bool
};
#endif // !EKF_POSITION_BIAS_ESTIMATOR_HPP

View File

@ -37,7 +37,8 @@
* using the estimated velocity as a reference in order to detect sensor faults
*/
#pragma once
#ifndef EKF_RANGE_FINDER_CONSISTENCY_CHECK_HPP
#define EKF_RANGE_FINDER_CONSISTENCY_CHECK_HPP
#include <mathlib/math/filter/AlphaFilter.hpp>
@ -77,3 +78,5 @@ private:
static constexpr float _min_vz_for_valid_consistency = .5f;
static constexpr uint64_t _consistency_hyst_time_us = 1e6;
};
#endif // !EKF_RANGE_FINDER_CONSISTENCY_CHECK_HPP