mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: add set_alt_measurement_noise
These calls the EKF2 and EKF3's set_baro_alt_noise
This commit is contained in:
parent
9b404669c8
commit
8caf7d5811
@ -562,6 +562,9 @@ public:
|
||||
// return current vibration vector for primary IMU
|
||||
Vector3f get_vibration(void) const;
|
||||
|
||||
// set and save the alt noise parameter value
|
||||
virtual void set_alt_measurement_noise(float noise) {};
|
||||
|
||||
// allow threads to lock against AHRS update
|
||||
HAL_Semaphore &get_semaphore(void) {
|
||||
return _rsem;
|
||||
|
@ -2290,4 +2290,15 @@ bool AP_AHRS_NavEKF::is_ext_nav_used_for_yaw(void) const
|
||||
return false;
|
||||
}
|
||||
|
||||
// set and save the alt noise parameter value
|
||||
void AP_AHRS_NavEKF::set_alt_measurement_noise(float noise)
|
||||
{
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
EKF2.set_baro_alt_noise(noise);
|
||||
#endif
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
EKF3.set_baro_alt_noise(noise);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
@ -298,6 +298,9 @@ public:
|
||||
// check whether external navigation is providing yaw. Allows compass pre-arm checks to be bypassed
|
||||
bool is_ext_nav_used_for_yaw(void) const override;
|
||||
|
||||
// set and save the ALT_M_NSE parameter value
|
||||
void set_alt_measurement_noise(float noise) override;
|
||||
|
||||
// these are only out here so vehicles can reference them for parameters
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
NavEKF2 EKF2;
|
||||
|
Loading…
Reference in New Issue
Block a user