AP_AHRS: new APIs for takeoff/touchdown expected

timeout handling now in AP_AHRS, and state stored in AHRS and
requested by AP_DAL
This commit is contained in:
Peter Barker 2021-05-27 12:08:59 +10:00 committed by Randy Mackay
parent 2439587c5a
commit 9eeec61cec
5 changed files with 50 additions and 57 deletions

View File

@ -508,6 +508,32 @@ Vector3f AP_AHRS::get_vibration(void) const
return AP::ins().get_vibration_levels();
}
void AP_AHRS::set_takeoff_expected(bool b)
{
_flags.takeoff_expected = b;
takeoff_expected_start_ms = AP_HAL::millis();
}
void AP_AHRS::set_touchdown_expected(bool b)
{
_flags.touchdown_expected = b;
touchdown_expected_start_ms = AP_HAL::millis();
}
/*
update takeoff/touchdown flags
*/
void AP_AHRS::update_flags(void)
{
const uint32_t timeout_ms = 1000;
if (_flags.takeoff_expected && AP_HAL::millis() - takeoff_expected_start_ms > timeout_ms) {
_flags.takeoff_expected = false;
}
if (_flags.touchdown_expected && AP_HAL::millis() - touchdown_expected_start_ms > timeout_ms) {
_flags.touchdown_expected = false;
}
}
// singleton instance
AP_AHRS *AP_AHRS::_singleton;

View File

@ -95,6 +95,18 @@ public:
return _flags.fly_forward;
}
void set_takeoff_expected(bool b);
bool get_takeoff_expected(void) const {
return _flags.takeoff_expected;
}
void set_touchdown_expected(bool b);
bool get_touchdown_expected(void) const {
return _flags.touchdown_expected;
}
AHRS_VehicleClass get_vehicle_class(void) const {
return _vehicle_class;
}
@ -640,6 +652,8 @@ protected:
uint8_t fly_forward : 1; // 1 if we can assume the aircraft will be flying forward on its X axis
uint8_t correct_centrifugal : 1; // 1 if we should correct for centrifugal forces (allows arducopter to turn this off when motors are disarmed)
uint8_t wind_estimation : 1; // 1 if we should do wind estimation
uint8_t takeoff_expected : 1; // 1 if the vehicle is in a state that takeoff might be expected. Ground effect may be in play.
uint8_t touchdown_expected : 1; // 1 if the vehicle is in a state that touchdown might be expected. Ground effect may be in play.
} _flags;
// calculate sin/cos of roll/pitch/yaw from rotation
@ -654,6 +668,9 @@ protected:
// update roll_sensor, pitch_sensor and yaw_sensor
void update_cd_values(void);
// update takeoff/touchdown flags
void update_flags();
// pointer to compass object, if available
Compass * _compass;
@ -707,6 +724,9 @@ private:
static AP_AHRS *_singleton;
AP_NMEA_Output* _nmea_out;
uint32_t takeoff_expected_start_ms;
uint32_t touchdown_expected_start_ms;
};
#include "AP_AHRS_DCM.h"

View File

@ -116,6 +116,9 @@ AP_AHRS_DCM::update(bool skip_ins_update)
update_AOA_SSA();
backup_attitude();
// update takeoff/touchdown flags
update_flags();
}
/*

View File

@ -2581,58 +2581,6 @@ bool AP_AHRS_NavEKF::get_vel_innovations_and_variances_for_source(uint8_t source
return false;
}
void AP_AHRS_NavEKF::setTakeoffExpected(bool val)
{
switch (takeoffExpectedState) {
case TriState::UNKNOWN:
break;
case TriState::True:
if (val) {
return;
}
break;
case TriState::False:
if (!val) {
return;
}
break;
}
takeoffExpectedState = (TriState)val;
#if HAL_NAVEKF2_AVAILABLE
EKF2.setTakeoffExpected(val);
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.setTakeoffExpected(val);
#endif
}
void AP_AHRS_NavEKF::setTouchdownExpected(bool val)
{
switch (touchdownExpectedState) {
case TriState::UNKNOWN:
break;
case TriState::True:
if (val) {
return;
}
break;
case TriState::False:
if (!val) {
return;
}
break;
}
touchdownExpectedState = (TriState)val;
#if HAL_NAVEKF2_AVAILABLE
EKF2.setTouchdownExpected(val);
#endif
#if HAL_NAVEKF3_AVAILABLE
EKF3.setTouchdownExpected(val);
#endif
}
bool AP_AHRS_NavEKF::getGpsGlitchStatus() const
{
nav_filter_status ekf_status {};

View File

@ -278,9 +278,6 @@ public:
// returns the estimated magnetic field offsets in body frame
bool get_mag_field_correction(Vector3f &ret) const override;
void setTakeoffExpected(bool val);
void setTouchdownExpected(bool val);
bool getGpsGlitchStatus() const;
// return the index of the airspeed we should use for airspeed measurements
@ -388,8 +385,7 @@ private:
True = 1,
UNKNOWN = 3,
};
TriState touchdownExpectedState = TriState::UNKNOWN;
TriState takeoffExpectedState = TriState::UNKNOWN;
TriState terrainHgtStableState = TriState::UNKNOWN;
EKFType last_active_ekf_type;