diff --git a/CMakeLists.txt b/CMakeLists.txt index 603d0ca6f9..b92be80a98 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -115,9 +115,21 @@ if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR) -Wno-missing-field-initializers # ignore for GCC 4.8 support ) + + # enable color output + if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 4.9) + # force color for gcc > 4.9 + add_compile_options(-fdiagnostics-color=always) + endif() + + elseif ("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") + # force color for clang (needed for clang + ccache) + add_compile_options(-fcolor-diagnostics) endif() + if(BUILD_TESTING) + enable_testing() include(CTest) diff --git a/EKF/CMakeLists.txt b/EKF/CMakeLists.txt index 9e72161ac4..3b099a95fe 100644 --- a/EKF/CMakeLists.txt +++ b/EKF/CMakeLists.txt @@ -31,6 +31,20 @@ # ############################################################################ +if((${CONFIG_ARCH_DPFPU} MATCHES "y") AND ECL_USE_DOUBLE_FPU) # DISABLED for now + message(STATUS "PX4 ECL: using double precision floating point (ecl_float_t = double)") + add_definitions(-DECL_FLOAT_TYPE=double) + + add_compile_options( + -Wno-double-promotion + -Wno-narrowing + -Wno-absolute-value + ) +else() + # ONLY in ecl_float_t = float32 mode + add_compile_options(-fsingle-precision-constant) +endif() + add_library(ecl_EKF airspeed_fusion.cpp control.cpp diff --git a/EKF/EKFGSF_yaw.cpp b/EKF/EKFGSF_yaw.cpp index 6f41e86d90..80032e9afb 100644 --- a/EKF/EKFGSF_yaw.cpp +++ b/EKF/EKFGSF_yaw.cpp @@ -1,6 +1,8 @@ #include "EKFGSF_yaw.h" #include +namespace estimator { + EKFGSF_yaw::EKFGSF_yaw() { // this flag must be false when we start @@ -548,3 +550,5 @@ void EKFGSF_yaw::setVelocity(const Vector2f &velocity, float accuracy) _vel_accuracy = accuracy; _vel_data_updated = true; } + +} // namespace estimator diff --git a/EKF/EKFGSF_yaw.h b/EKF/EKFGSF_yaw.h index 9b07ae6f6d..7d669d8a05 100644 --- a/EKF/EKFGSF_yaw.h +++ b/EKF/EKFGSF_yaw.h @@ -1,5 +1,7 @@ #pragma once +#include + #include #include #include @@ -7,15 +9,6 @@ #include "common.h" #include "utils.hpp" -using matrix::AxisAnglef; -using matrix::Dcmf; -using matrix::Eulerf; -using matrix::Matrix3f; -using matrix::Quatf; -using matrix::Vector2f; -using matrix::Vector3f; -using matrix::wrap_pi; - static constexpr uint8_t N_MODELS_EKFGSF = 5; // Required math constants @@ -23,7 +16,7 @@ static constexpr float _m_2pi_inv = 0.159154943f; static constexpr float _m_pi = 3.14159265f; static constexpr float _m_pi2 = 1.57079632f; -using namespace estimator; +namespace estimator { class EKFGSF_yaw { @@ -134,3 +127,5 @@ class EKFGSF_yaw // return the probability of the state estimate for the specified EKF assuming a gaussian error distribution float gaussianDensity(const uint8_t model_index) const; }; + +} // namespace estimator diff --git a/EKF/airspeed_fusion.cpp b/EKF/airspeed_fusion.cpp index be5385a3e2..f4e380cd2f 100644 --- a/EKF/airspeed_fusion.cpp +++ b/EKF/airspeed_fusion.cpp @@ -41,10 +41,15 @@ * @author Paul Riseborough * */ -#include "../ecl.h" + +#include + #include "ekf.h" #include +namespace estimator +{ + void Ekf::fuseAirspeed() { const float &vn = _state.vel(0); // Velocity in north direction @@ -184,3 +189,5 @@ void Ekf::resetWindStates() _state.wind_vel.setZero(); } } + +} // namespace estimator diff --git a/EKF/common.h b/EKF/common.h index d0a0d5bc4e..f0d59861c1 100644 --- a/EKF/common.h +++ b/EKF/common.h @@ -31,6 +31,8 @@ * ****************************************************************************/ +#pragma once + /** * @file common.h * Definition of base class for attitude estimators @@ -41,18 +43,20 @@ */ #pragma once +#include #include namespace estimator { -using matrix::AxisAnglef; -using matrix::Dcmf; -using matrix::Eulerf; -using matrix::Matrix3f; -using matrix::Quatf; -using matrix::Vector2f; -using matrix::Vector3f; +using AxisAnglef = matrix::AxisAngle; +using Dcmf = matrix::Dcm; +using Eulerf = matrix::Euler; +using Matrix3f = matrix::SquareMatrix; +using Quatf = matrix::Quaternion; +using Vector2f = matrix::Vector2; +using Vector3f = matrix::Vector3; + using matrix::wrap_pi; enum velocity_frame_t {LOCAL_FRAME_FRD, BODY_FRAME_FRD}; diff --git a/EKF/control.cpp b/EKF/control.cpp index 265cccf556..0e2204c0cb 100644 --- a/EKF/control.cpp +++ b/EKF/control.cpp @@ -39,10 +39,14 @@ * */ -#include "../ecl.h" +#include + #include "ekf.h" #include +namespace estimator +{ + void Ekf::controlFusionModes() { // Store the status to enable change detection @@ -1317,3 +1321,5 @@ void Ekf::controlAuxVelFusion() } } + +} // namespace estimator diff --git a/EKF/covariance.cpp b/EKF/covariance.cpp index d874283c0c..4001433c78 100644 --- a/EKF/covariance.cpp +++ b/EKF/covariance.cpp @@ -48,6 +48,9 @@ #include #include +namespace estimator +{ + // Sets initial values for the covariance matrix // Do not call before quaternion states have been initialised void Ekf::initialiseCovariance() @@ -57,7 +60,7 @@ void Ekf::initialiseCovariance() _delta_angle_bias_var_accum.setZero(); _delta_vel_bias_var_accum.setZero(); - const float dt = FILTER_UPDATE_PERIOD_S; + const ecl_float_t dt = FILTER_UPDATE_PERIOD_S; resetQuatCov(); @@ -106,41 +109,41 @@ void Ekf::initialiseCovariance() void Ekf::predictCovariance() { // assign intermediate state variables - const float &q0 = _state.quat_nominal(0); - const float &q1 = _state.quat_nominal(1); - const float &q2 = _state.quat_nominal(2); - const float &q3 = _state.quat_nominal(3); + const auto &q0 = _state.quat_nominal(0); + const auto &q1 = _state.quat_nominal(1); + const auto &q2 = _state.quat_nominal(2); + const auto &q3 = _state.quat_nominal(3); - const float &dax = _imu_sample_delayed.delta_ang(0); - const float &day = _imu_sample_delayed.delta_ang(1); - const float &daz = _imu_sample_delayed.delta_ang(2); + const auto &dax = _imu_sample_delayed.delta_ang(0); + const auto &day = _imu_sample_delayed.delta_ang(1); + const auto &daz = _imu_sample_delayed.delta_ang(2); - const float &dvx = _imu_sample_delayed.delta_vel(0); - const float &dvy = _imu_sample_delayed.delta_vel(1); - const float &dvz = _imu_sample_delayed.delta_vel(2); + const auto &dvx = _imu_sample_delayed.delta_vel(0); + const auto &dvy = _imu_sample_delayed.delta_vel(1); + const auto &dvz = _imu_sample_delayed.delta_vel(2); - const float &dax_b = _state.delta_ang_bias(0); - const float &day_b = _state.delta_ang_bias(1); - const float &daz_b = _state.delta_ang_bias(2); + const auto &dax_b = _state.delta_ang_bias(0); + const auto &day_b = _state.delta_ang_bias(1); + const auto &daz_b = _state.delta_ang_bias(2); - const float &dvx_b = _state.delta_vel_bias(0); - const float &dvy_b = _state.delta_vel_bias(1); - const float &dvz_b = _state.delta_vel_bias(2); + const auto &dvx_b = _state.delta_vel_bias(0); + const auto &dvy_b = _state.delta_vel_bias(1); + const auto &dvz_b = _state.delta_vel_bias(2); // Use average update interval to reduce accumulated covariance prediction errors due to small single frame dt values - const float dt = FILTER_UPDATE_PERIOD_S; - const float dt_inv = 1.0f / dt; + const auto dt = FILTER_UPDATE_PERIOD_S; + const auto dt_inv = 1.0 / dt; // convert rate of change of rate gyro bias (rad/s**2) as specified by the parameter to an expected change in delta angle (rad) since the last update - const float d_ang_bias_sig = dt * dt * math::constrain(_params.gyro_bias_p_noise, 0.0f, 1.0f); + const ecl_float_t d_ang_bias_sig = dt * dt * math::constrain(_params.gyro_bias_p_noise, 0.0f, 1.0f); // convert rate of change of accelerometer bias (m/s**3) as specified by the parameter to an expected change in delta velocity (m/s) since the last update - const float d_vel_bias_sig = dt * dt * math::constrain(_params.accel_bias_p_noise, 0.0f, 1.0f); + const ecl_float_t d_vel_bias_sig = dt * dt * math::constrain(_params.accel_bias_p_noise, 0.0f, 1.0f); // inhibit learning of imu accel bias if the manoeuvre levels are too high to protect against the effect of sensor nonlinearities or bad accel data is detected // xy accel bias learning is also disabled on ground as those states are poorly observable when perpendicular to the gravity vector - const float alpha = math::constrain((dt / _params.acc_bias_learn_tc), 0.0f, 1.0f); - const float beta = 1.0f - alpha; + const ecl_float_t alpha = math::constrain((dt / _params.acc_bias_learn_tc), 0.0f, 1.0f); + const ecl_float_t beta = 1.0f - alpha; _ang_rate_magnitude_filt = fmaxf(dt_inv * _imu_sample_delayed.delta_ang.norm(), beta * _ang_rate_magnitude_filt); _accel_magnitude_filt = fmaxf(dt_inv * _imu_sample_delayed.delta_vel.norm(), beta * _accel_magnitude_filt); _accel_vec_filt = alpha * dt_inv * _imu_sample_delayed.delta_vel + beta * _accel_vec_filt; @@ -228,12 +231,12 @@ void Ekf::predictCovariance() // assign IMU noise variances // inputs to the system are 3 delta angles and 3 delta velocities - float gyro_noise = math::constrain(_params.gyro_noise, 0.0f, 1.0f); - const float daxVar = sq(dt * gyro_noise); - const float dayVar = daxVar; - const float dazVar = daxVar; + ecl_float_t gyro_noise = math::constrain(_params.gyro_noise, 0.0f, 1.0f); + const ecl_float_t daxVar = sq(dt * gyro_noise); + const ecl_float_t dayVar = daxVar; + const ecl_float_t dazVar = daxVar; - float accel_noise = math::constrain(_params.accel_noise, 0.0f, 1.0f); + ecl_float_t accel_noise = math::constrain(_params.accel_noise, 0.0f, 1.0f); if (_fault_status.flags.bad_acc_vertical) { // Increase accelerometer process noise if bad accel data is detected. Measurement errors due to @@ -241,7 +244,7 @@ void Ekf::predictCovariance() accel_noise = BADACC_BIAS_PNOISE; } - float dvxVar, dvyVar, dvzVar; + ecl_float_t dvxVar, dvyVar, dvzVar; dvxVar = dvyVar = dvzVar = sq(dt * accel_noise); // Accelerometer Clipping @@ -1120,3 +1123,5 @@ void Ekf::resetWindCovariance() P.uncorrelateCovarianceSetVariance<2>(22, _params.initial_wind_uncertainty); } } + +} // namespace estimator diff --git a/EKF/drag_fusion.cpp b/EKF/drag_fusion.cpp index a2d84d46f1..001199b3c9 100644 --- a/EKF/drag_fusion.cpp +++ b/EKF/drag_fusion.cpp @@ -44,6 +44,9 @@ #include #include +namespace estimator +{ + void Ekf::fuseDrag() { SparseVector24f<0,1,2,3,4,5,6,22,23> Hfusion; // Observation Jacobians @@ -268,3 +271,6 @@ void Ekf::fuseDrag() } } } + +} // namespace estimator + diff --git a/EKF/ekf.cpp b/EKF/ekf.cpp index 7a51552217..766e504af6 100644 --- a/EKF/ekf.cpp +++ b/EKF/ekf.cpp @@ -44,6 +44,9 @@ #include #include +namespace estimator +{ + bool Ekf::init(uint64_t timestamp) { bool ret = initialise_interface(timestamp); @@ -292,11 +295,11 @@ void Ekf::predictState() constrainStates(); // calculate an average filter update time - float input = 0.5f * (_imu_sample_delayed.delta_vel_dt + _imu_sample_delayed.delta_ang_dt); + ecl_float_t input = 0.5 * (_imu_sample_delayed.delta_vel_dt + _imu_sample_delayed.delta_ang_dt); // filter and limit input between -50% and +100% of nominal value - input = math::constrain(input, 0.5f * FILTER_UPDATE_PERIOD_S, 2.0f * FILTER_UPDATE_PERIOD_S); - _dt_ekf_avg = 0.99f * _dt_ekf_avg + 0.01f * input; + input = math::constrain(input, 0.5 * FILTER_UPDATE_PERIOD_S, 2.0 * FILTER_UPDATE_PERIOD_S); + _dt_ekf_avg = 0.99 * _dt_ekf_avg + 0.01 * input; // some calculations elsewhere in code require a raw angular rate vector so calculate here to avoid duplication // protect angainst possible small timesteps resulting from timing slip on previous frame that can drive spikes into the rate @@ -406,14 +409,14 @@ void Ekf::calculateOutputStates(const imuSample &imu) const Quatf q_error((_state.quat_nominal.inversed() * output_delayed.quat_nominal).normalized()); // convert the quaternion delta to a delta angle - const float scalar = (q_error(0) >= 0.0f) ? -2.f : 2.f; + const ecl_float_t scalar = (q_error(0) >= 0.0f) ? -2.f : 2.f; const Vector3f delta_ang_error{scalar * q_error(1), scalar * q_error(2), scalar * q_error(3)}; // calculate a gain that provides tight tracking of the estimator attitude states and // adjust for changes in time delay to maintain consistent damping ratio of ~0.7 - const float time_delay = fmaxf((imu.time_us - _imu_sample_delayed.time_us) * 1e-6f, _dt_imu_avg); - const float att_gain = 0.5f * _dt_imu_avg / time_delay; + const ecl_float_t time_delay = fmaxf((imu.time_us - _imu_sample_delayed.time_us) * 1e-6, _dt_imu_avg); + const ecl_float_t att_gain = 0.5 * _dt_imu_avg / time_delay; // calculate a corrrection to the delta angle // that will cause the INS to track the EKF quaternions @@ -428,16 +431,16 @@ void Ekf::calculateOutputStates(const imuSample &imu) */ // Complementary filter gains - const float vel_gain = _dt_ekf_avg / math::constrain(_params.vel_Tau, _dt_ekf_avg, 10.0f); - const float pos_gain = _dt_ekf_avg / math::constrain(_params.pos_Tau, _dt_ekf_avg, 10.0f); + const ecl_float_t vel_gain = _dt_ekf_avg / math::constrain(_params.vel_Tau, (float)_dt_ekf_avg, 10.0f); + const ecl_float_t pos_gain = _dt_ekf_avg / math::constrain(_params.pos_Tau, (float)_dt_ekf_avg, 10.0f); // calculate down velocity and position tracking errors - const float vert_vel_err = (_state.vel(2) - output_vert_delayed.vert_vel); - const float vert_vel_integ_err = (_state.pos(2) - output_vert_delayed.vert_vel_integ); + const ecl_float_t vert_vel_err = (_state.vel(2) - output_vert_delayed.vert_vel); + const ecl_float_t vert_vel_integ_err = (_state.pos(2) - output_vert_delayed.vert_vel_integ); // calculate a velocity correction that will be applied to the output state history // using a PD feedback tuned to a 5% overshoot - const float vert_vel_correction = vert_vel_integ_err * pos_gain + vert_vel_err * vel_gain * 1.1f; + const ecl_float_t vert_vel_correction = vert_vel_integ_err * pos_gain + vert_vel_err * vel_gain * 1.1f; applyCorrectionToVerticalOutputBuffer(vert_vel_correction); @@ -525,7 +528,8 @@ void Ekf::applyCorrectionToOutputBuffer(const Vector3f& vel_correction, const Ve /* * Predict the previous quaternion output state forward using the latest IMU delta angle data. */ -Quatf Ekf::calculate_quaternion() const +matrix::Quaternion +Ekf::calculate_quaternion() const { // Correct delta angle data for bias errors using bias state estimates from the EKF and also apply // corrections required to track the EKF quaternion states @@ -533,5 +537,9 @@ Quatf Ekf::calculate_quaternion() const // increment the quaternions using the corrected delta angle vector // the quaternions must always be normalised after modification - return Quatf{_output_new.quat_nominal * AxisAnglef{delta_angle}}.unit(); + const Quatf q{_output_new.quat_nominal * AxisAnglef{delta_angle}}; + const Quatf q_norm = q.unit(); + return matrix::Quaternion {q_norm(0), q_norm(1), q_norm(2), q_norm(3)}; } + +} // namespace estimator diff --git a/EKF/ekf.h b/EKF/ekf.h index d84dfa66f6..46777f8ef6 100644 --- a/EKF/ekf.h +++ b/EKF/ekf.h @@ -46,6 +46,9 @@ #include "EKFGSF_yaw.h" +namespace estimator +{ + class Ekf final : public EstimatorInterface { public: @@ -132,19 +135,19 @@ class Ekf final : public EstimatorInterface void get_true_airspeed(float *tas) const; // get the full covariance matrix - const matrix::SquareMatrix &covariances() const { return P; } + const matrix::SquareMatrix &covariances() const { return P; } // get the diagonal elements of the covariance matrix - matrix::Vector covariances_diagonal() const { return P.diag(); } + matrix::Vector covariances_diagonal() const { return P.diag(); } // get the orientation (quaterion) covariances - matrix::SquareMatrix orientation_covariances() const { return P.slice<4, 4>(0, 0); } + matrix::SquareMatrix orientation_covariances() const { return P.slice<4, 4>(0, 0); } // get the linear velocity covariances - matrix::SquareMatrix velocity_covariances() const { return P.slice<3, 3>(4, 4); } + matrix::SquareMatrix velocity_covariances() const { return P.slice<3, 3>(4, 4); } // get the position covariances - matrix::SquareMatrix position_covariances() const { return P.slice<3, 3>(7, 7); } + matrix::SquareMatrix position_covariances() const { return P.slice<3, 3>(7, 7); } // ask estimator for sensor data collection decision and do any preprocessing if required, returns true if not defined bool collect_gps(const gps_message &gps) override; @@ -248,7 +251,11 @@ class Ekf final : public EstimatorInterface // return the amount the quaternion has changed in the last reset and the number of reset events void get_quat_reset(float delta_quat[4], uint8_t *counter) const { - _state_reset_status.quat_change.copyTo(delta_quat); + delta_quat[0] = _state_reset_status.quat_change(0); + delta_quat[1] = _state_reset_status.quat_change(1); + delta_quat[2] = _state_reset_status.quat_change(2); + delta_quat[3] = _state_reset_status.quat_change(3); + *counter = _state_reset_status.quat_counter; } @@ -267,7 +274,7 @@ class Ekf final : public EstimatorInterface matrix::Quatf getVisionAlignmentQuaternion() const { return Quatf(_R_ev_to_ekf); }; // use the latest IMU data at the current time horizon. - Quatf calculate_quaternion() const; + matrix::Quaternion calculate_quaternion() const; // set minimum continuous period without GPS fail required to mark a healthy GPS status void set_min_required_gps_health_time(uint32_t time_us) { _min_gps_health_time_us = time_us; } @@ -308,7 +315,7 @@ class Ekf final : public EstimatorInterface Quatf quat_change; ///< quaternion delta due to last reset - multiply pre-reset quaternion by this to get post-reset quaternion } _state_reset_status{}; ///< reset event monitoring structure containing velocity, position, height and yaw reset information - float _dt_ekf_avg{FILTER_UPDATE_PERIOD_S}; ///< average update rate of the ekf + ecl_float_t _dt_ekf_avg{FILTER_UPDATE_PERIOD_S}; ///< average update rate of the ekf Vector3f _ang_rate_delayed_raw; ///< uncorrected angular rate vector at fusion time horizon (rad/sec) @@ -944,3 +951,5 @@ class Ekf final : public EstimatorInterface void resetGpsDriftCheckFilters(); }; + +} // namespace estimator diff --git a/EKF/ekf_helper.cpp b/EKF/ekf_helper.cpp index 26510cf1f0..2756a2d6e6 100644 --- a/EKF/ekf_helper.cpp +++ b/EKF/ekf_helper.cpp @@ -39,12 +39,16 @@ * */ +#include + #include "ekf.h" -#include #include #include +namespace estimator +{ + void Ekf::resetVelocity() { @@ -1587,3 +1591,5 @@ void Ekf::resetGpsDriftCheckFilters() _gps_velNE_filt.setZero(); _gps_pos_deriv_filt.setZero(); } + +} // namespace estimator diff --git a/EKF/estimator_interface.cpp b/EKF/estimator_interface.cpp index ea945c98e3..f99bf5b2ae 100644 --- a/EKF/estimator_interface.cpp +++ b/EKF/estimator_interface.cpp @@ -45,6 +45,9 @@ #include #include +namespace estimator +{ + // Accumulate imu data and store to buffer at desired rate void EstimatorInterface::setIMUData(const imuSample &imu_sample) { @@ -616,3 +619,6 @@ void EstimatorInterface::print_status() ECL_INFO("output vert buffer: %d (%d Bytes)", _output_vert_buffer.get_length(), _output_vert_buffer.get_total_size()); ECL_INFO("drag buffer: %d (%d Bytes)", _drag_buffer.get_length(), _drag_buffer.get_total_size()); } + +} // namespace estimator + diff --git a/EKF/estimator_interface.h b/EKF/estimator_interface.h index d7b9b352bc..3ce3cf6ae7 100644 --- a/EKF/estimator_interface.h +++ b/EKF/estimator_interface.h @@ -53,7 +53,8 @@ #include #include -using namespace estimator; +namespace estimator +{ class EstimatorInterface { @@ -416,3 +417,6 @@ class EstimatorInterface bool _auxvel_buffer_fail{false}; }; + +} // namespace estimator + diff --git a/EKF/gps_checks.cpp b/EKF/gps_checks.cpp index b0ab0b0be1..74ca5ae34f 100644 --- a/EKF/gps_checks.cpp +++ b/EKF/gps_checks.cpp @@ -45,6 +45,9 @@ #include #include +namespace estimator +{ + // GPS pre-flight check bit locations #define MASK_GPS_NSATS (1<<0) #define MASK_GPS_PDOP (1<<1) @@ -274,3 +277,6 @@ bool Ekf::gps_is_good(const gps_message &gps) // continuous period without fail of x seconds required to return a healthy status return isTimedOut(_last_gps_fail_us, (uint64_t)_min_gps_health_time_us); } + +} // namespace estimator + diff --git a/EKF/gps_yaw_fusion.cpp b/EKF/gps_yaw_fusion.cpp index 237bd52652..d4880d87c2 100644 --- a/EKF/gps_yaw_fusion.cpp +++ b/EKF/gps_yaw_fusion.cpp @@ -46,6 +46,9 @@ #include #include +namespace estimator +{ + void Ekf::fuseGpsYaw() { // assign intermediate state variables @@ -215,3 +218,6 @@ bool Ekf::resetYawToGps() return true; } + +} // namespace estimator + diff --git a/EKF/mag_fusion.cpp b/EKF/mag_fusion.cpp index add82b9dd5..f151ca762f 100644 --- a/EKF/mag_fusion.cpp +++ b/EKF/mag_fusion.cpp @@ -45,6 +45,9 @@ #include #include +namespace estimator +{ + void Ekf::fuseMag() { // assign intermediate variables @@ -954,3 +957,6 @@ float Ekf::calculate_synthetic_mag_z_measurement(const Vector3f& mag_meas, const return (mag_z_body_pred < 0) ? -mag_z_abs : mag_z_abs; } + +} // namespace estimator + diff --git a/EKF/optflow_fusion.cpp b/EKF/optflow_fusion.cpp index b09f0950c2..857f5a44fa 100644 --- a/EKF/optflow_fusion.cpp +++ b/EKF/optflow_fusion.cpp @@ -47,6 +47,9 @@ #include #include "utils.hpp" +namespace estimator +{ + void Ekf::fuseOptFlow() { float gndclearance = fmaxf(_params.rng_gnd_clearance, 0.1f); @@ -396,3 +399,6 @@ float Ekf::calcOptFlowMeasVar() return R_LOS; } + +} // namespace estimator + diff --git a/EKF/sideslip_fusion.cpp b/EKF/sideslip_fusion.cpp index 2b966a1b72..e3d6612327 100644 --- a/EKF/sideslip_fusion.cpp +++ b/EKF/sideslip_fusion.cpp @@ -45,6 +45,9 @@ #include #include +namespace estimator +{ + void Ekf::fuseSideslip() { // get latest estimated orientation @@ -212,3 +215,6 @@ void Ekf::fuseSideslip() } } } + +} // namespace estimator + diff --git a/EKF/terrain_estimator.cpp b/EKF/terrain_estimator.cpp index 77cc681810..80cf819977 100644 --- a/EKF/terrain_estimator.cpp +++ b/EKF/terrain_estimator.cpp @@ -43,6 +43,9 @@ #include #include +namespace estimator +{ + bool Ekf::initHagl() { bool initialized = false; @@ -294,3 +297,6 @@ void Ekf::updateTerrainValidity() _hagl_sensor_status.flags.flow = shouldUseOpticalFlowForHagl() && recent_flow_for_terrain_fusion; } + +} // namespace estimator + diff --git a/EKF/vel_pos_fusion.cpp b/EKF/vel_pos_fusion.cpp index 911a065d07..77d1a68cdf 100644 --- a/EKF/vel_pos_fusion.cpp +++ b/EKF/vel_pos_fusion.cpp @@ -45,6 +45,9 @@ #include #include "ekf.h" +namespace estimator +{ + bool Ekf::fuseHorizontalVelocity(const Vector3f &innov, const Vector2f &innov_gate, const Vector3f &obs_var, Vector3f &innov_var, Vector2f &test_ratio) { @@ -218,3 +221,6 @@ void Ekf::setVelPosFaultStatus(const int index, const bool status) _fault_status.flags.bad_pos_D = status; } } + +} // namespace estimator + diff --git a/ecl.h b/ecl.h index 653cca788b..8178099760 100644 --- a/ecl.h +++ b/ecl.h @@ -38,6 +38,12 @@ */ #pragma once +#if defined(ECL_FLOAT_TYPE) +using ecl_float_t = ECL_FLOAT_TYPE; +#else +using ecl_float_t = float; +#endif + #if defined(__PX4_POSIX) || defined(__PX4_NUTTX) #include