AP_AHRS: move frontend parameters up / DCM parameters down

This commit is contained in:
Peter Barker 2021-08-20 12:20:59 +10:00 committed by Andrew Tridgell
parent 62f6a5b033
commit 8169910866
3 changed files with 20 additions and 16 deletions

View File

@ -116,6 +116,10 @@ public:
// return a wind estimation vector, in m/s // return a wind estimation vector, in m/s
Vector3f wind_estimate() const override; Vector3f wind_estimate() const override;
// return the parameter AHRS_WIND_MAX in metres per second
uint8_t get_max_wind() const {
return _wind_max;
}
/* /*
* airspeed support * airspeed support
@ -335,6 +339,11 @@ public:
return uint8_t(active_EKF_type()); return uint8_t(active_EKF_type());
} }
// get the selected ekf type, for allocation decisions
int8_t get_ekf_type(void) const {
return _ekf_type;
}
// these are only out here so vehicles can reference them for parameters // these are only out here so vehicles can reference them for parameters
#if HAL_NAVEKF2_AVAILABLE #if HAL_NAVEKF2_AVAILABLE
NavEKF2 EKF2; NavEKF2 EKF2;
@ -466,6 +475,16 @@ private:
*/ */
VehicleClass _vehicle_class{VehicleClass::UNKNOWN}; VehicleClass _vehicle_class{VehicleClass::UNKNOWN};
/*
* Parameters
*/
AP_Int8 _wind_max;
AP_Int8 _board_orientation;
AP_Int8 _ekf_type;
AP_Float _custom_roll;
AP_Float _custom_pitch;
AP_Float _custom_yaw;
enum class EKFType { enum class EKFType {
NONE = 0 NONE = 0
#if HAL_NAVEKF3_AVAILABLE #if HAL_NAVEKF3_AVAILABLE

View File

@ -206,11 +206,6 @@ public:
return _airspeed != nullptr && _airspeed->use(airspeed_index) && _airspeed->healthy(airspeed_index); return _airspeed != nullptr && _airspeed->use(airspeed_index) && _airspeed->healthy(airspeed_index);
} }
// return the parameter AHRS_WIND_MAX in metres per second
uint8_t get_max_wind() const {
return _wind_max;
}
// return a ground vector estimate in meters/second, in North/East order // return a ground vector estimate in meters/second, in North/East order
virtual Vector2f groundspeed_vector(void); virtual Vector2f groundspeed_vector(void);
@ -374,11 +369,6 @@ public:
return false; return false;
} }
// get the selected ekf type, for allocation decisions
int8_t get_ekf_type(void) const {
return _ekf_type;
}
// Retrieves the corrected NED delta velocity in use by the inertial navigation // Retrieves the corrected NED delta velocity in use by the inertial navigation
virtual void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const { virtual void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const {
ret.zero(); ret.zero();
@ -455,13 +445,7 @@ protected:
}; };
AP_Enum<GPSUse> _gps_use; AP_Enum<GPSUse> _gps_use;
AP_Int8 _wind_max;
AP_Int8 _board_orientation;
AP_Int8 _gps_minsats; AP_Int8 _gps_minsats;
AP_Int8 _ekf_type;
AP_Float _custom_roll;
AP_Float _custom_pitch;
AP_Float _custom_yaw;
Matrix3f _custom_rotation; Matrix3f _custom_rotation;

View File

@ -1091,6 +1091,7 @@ bool AP_AHRS_DCM::airspeed_estimate(uint8_t airspeed_index, float &airspeed_ret)
return false; return false;
} }
const float _wind_max = AP::ahrs().get_max_wind();
if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) { if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
// constrain the airspeed by the ground speed // constrain the airspeed by the ground speed
// and AHRS_WIND_MAX // and AHRS_WIND_MAX