diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index eeead3df57..1d68f1a01b 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -29,6 +29,7 @@ #include #include #include +#include class OpticalFlow; #define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees @@ -571,7 +572,16 @@ public: // Write position and quaternion data from an external navigation system virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) { } + // allow threads to lock against AHRS update + HAL_Semaphore &get_semaphore(void) { + return _rsem; + } + protected: + + // multi-thread access support + HAL_Semaphore_Recursive _rsem; + AHRS_VehicleClass _vehicle_class; // settable parameters diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index ed0849da04..b1ae1fed28 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -49,6 +49,9 @@ AP_AHRS_DCM::reset_gyro_drift(void) void AP_AHRS_DCM::update(bool skip_ins_update) { + // support locked access functions to AHRS data + WITH_SEMAPHORE(_rsem); + float delta_t; if (_last_startup_ms == 0) { @@ -141,6 +144,9 @@ AP_AHRS_DCM::matrix_update(float _G_Dt) void AP_AHRS_DCM::reset(bool recover_eulers) { + // support locked access functions to AHRS data + WITH_SEMAPHORE(_rsem); + // reset the integration terms _omega_I.zero(); _omega_P.zero(); diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 4fd5ac22cc..efbced5b89 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -70,6 +70,9 @@ const Vector3f &AP_AHRS_NavEKF::get_gyro_drift(void) const // should be called if gyro offsets are recalculated void AP_AHRS_NavEKF::reset_gyro_drift(void) { + // support locked access functions to AHRS data + WITH_SEMAPHORE(_rsem); + // update DCM AP_AHRS_DCM::reset_gyro_drift(); @@ -80,6 +83,9 @@ void AP_AHRS_NavEKF::reset_gyro_drift(void) void AP_AHRS_NavEKF::update(bool skip_ins_update) { + // support locked access functions to AHRS data + WITH_SEMAPHORE(_rsem); + // drop back to normal priority if we were boosted by the INS // calling delay_microseconds_boost() hal.scheduler->boost_end(); @@ -89,7 +95,6 @@ void AP_AHRS_NavEKF::update(bool skip_ins_update) _ekf_type.set(2); } - update_DCM(skip_ins_update); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -366,6 +371,9 @@ const Vector3f &AP_AHRS_NavEKF::get_accel_ef_blended(void) const void AP_AHRS_NavEKF::reset(bool recover_eulers) { + // support locked access functions to AHRS data + WITH_SEMAPHORE(_rsem); + AP_AHRS_DCM::reset(recover_eulers); _dcm_attitude(roll, pitch, yaw); if (_ekf2_started) { @@ -379,6 +387,9 @@ void AP_AHRS_NavEKF::reset(bool recover_eulers) // reset the current attitude, used on new IMU calibration void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw) { + // support locked access functions to AHRS data + WITH_SEMAPHORE(_rsem); + AP_AHRS_DCM::reset_attitude(_roll, _pitch, _yaw); _dcm_attitude(roll, pitch, yaw); if (_ekf2_started) { @@ -1395,6 +1406,9 @@ uint32_t AP_AHRS_NavEKF::getLastPosDownReset(float &posDelta) const // If using a range finder for height no reset is performed and it returns false bool AP_AHRS_NavEKF::resetHeightDatum(void) { + // support locked access functions to AHRS data + WITH_SEMAPHORE(_rsem); + switch (ekf_type()) { case 2: