mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_AHRS_NavEKF: add setTakeoffExpected, setTouchdownExpected
This commit is contained in:
parent
c90d7dd86e
commit
a2999ece54
@ -1098,6 +1098,38 @@ bool AP_AHRS_NavEKF::get_variances(float &velVar, float &posVar, float &hgtVar,
|
||||
}
|
||||
}
|
||||
|
||||
void AP_AHRS_NavEKF::setTakeoffExpected(bool val)
|
||||
{
|
||||
switch (ekf_type()) {
|
||||
case EKF_TYPE1:
|
||||
EKF1.setTakeoffExpected(val);
|
||||
break;
|
||||
case EKF_TYPE2:
|
||||
EKF2.setTakeoffExpected(val);
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case EKF_TYPE_SITL:
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void AP_AHRS_NavEKF::setTouchdownExpected(bool val)
|
||||
{
|
||||
switch (ekf_type()) {
|
||||
case EKF_TYPE1:
|
||||
EKF1.setTouchdownExpected(val);
|
||||
break;
|
||||
case EKF_TYPE2:
|
||||
EKF2.setTouchdownExpected(val);
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case EKF_TYPE_SITL:
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
||||
|
@ -197,6 +197,9 @@ public:
|
||||
// boolean false is returned if variances are not available
|
||||
bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const;
|
||||
|
||||
void setTakeoffExpected(bool val);
|
||||
void setTouchdownExpected(bool val);
|
||||
|
||||
private:
|
||||
enum EKF_TYPE {EKF_TYPE_NONE=0,
|
||||
EKF_TYPE1=1,
|
||||
|
Loading…
Reference in New Issue
Block a user