AP_AHRS: move AOA/SSA to AP_AHRS, don't recalc on fetch

This commit is contained in:
Peter Barker 2021-07-22 21:54:35 +10:00 committed by Peter Barker
parent c1e263695f
commit e4bceb2417
6 changed files with 17 additions and 28 deletions

View File

@ -320,6 +320,9 @@ void AP_AHRS::update(bool skip_ins_update)
_view->update(skip_ins_update);
}
// update AOA and SSA
update_AOA_SSA();
#if HAL_NMEA_OUTPUT_ENABLED
// update NMEA output
if (_nmea_out != nullptr) {

View File

@ -324,6 +324,18 @@ public:
// create a view
AP_AHRS_View *create_view(enum Rotation rotation, float pitch_trim_deg=0);
// write AOA and SSA information to dataflash logs:
void Write_AOA_SSA(void) const;
// update AOA and SSA values
virtual void update_AOA_SSA(void);
// return AOA
float getAOA(void) const { return _AOA; }
// return SSA
float getSSA(void) const { return _SSA; }
protected:
// optional view class
AP_AHRS_View *_view;

View File

@ -248,7 +248,7 @@ AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg)
* "ANGLE OF ATTACK AND SIDESLIP ESTIMATION USING AN INERTIAL REFERENCE PLATFORM" by
* JOSEPH E. ZEIS, JR., CAPTAIN, USAF
*/
void AP_AHRS_Backend::update_AOA_SSA(void)
void AP_AHRS::update_AOA_SSA(void)
{
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
const uint32_t now = AP_HAL::millis();
@ -294,20 +294,6 @@ void AP_AHRS_Backend::update_AOA_SSA(void)
#endif
}
// return current AOA
float AP_AHRS_Backend::getAOA(void)
{
update_AOA_SSA();
return _AOA;
}
// return calculated SSA
float AP_AHRS_Backend::getSSA(void)
{
update_AOA_SSA();
return _SSA;
}
// rotate a 2D vector from earth frame to body frame
Vector2f AP_AHRS_Backend::earth_to_body2D(const Vector2f &ef) const
{

View File

@ -514,12 +514,6 @@ public:
AP::ins().get_delta_velocity(ret, dt);
}
// return calculated AOA
float getAOA(void);
// return calculated SSA
float getSSA(void);
// rotate a 2D vector from earth frame to body frame
// in result, x is forward, y is right
Vector2f earth_to_body2D(const Vector2f &ef_vector) const;
@ -537,8 +531,6 @@ public:
Vector3f earth_to_body(const Vector3f &v) const {
return get_rotation_body_to_ned().mul_transpose(v);
}
virtual void update_AOA_SSA(void);
// get_hgt_ctrl_limit - get maximum height to be observed by the
// control loops in meters and a validity flag. It will return
@ -571,7 +563,6 @@ public:
// Logging to disk functions
void Write_AHRS2(void) const;
void Write_AOA_SSA(void); // should be const? but it calls update functions
void Write_Attitude(const Vector3f &targets) const;
void Write_Origin(uint8_t origin_type, const Location &loc) const;
void Write_POS(void) const;

View File

@ -112,9 +112,6 @@ AP_AHRS_DCM::update(bool skip_ins_update)
// update trig values including _cos_roll, cos_pitch
update_trig();
// update AOA and SSA
update_AOA_SSA();
backup_attitude();
// update takeoff/touchdown flags

View File

@ -32,7 +32,7 @@ void AP_AHRS_Backend::Write_AHRS2() const
}
// Write AOA and SSA
void AP_AHRS_Backend::Write_AOA_SSA(void)
void AP_AHRS::Write_AOA_SSA(void) const
{
const struct log_AOA_SSA aoa_ssa{
LOG_PACKET_HEADER_INIT(LOG_AOA_SSA_MSG),