mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_Soaring: Initialize filter to the current filtered measurement
This commit is contained in:
parent
e3109e4b29
commit
3ead096329
@ -253,7 +253,7 @@ void SoaringController::init_thermalling()
|
||||
}
|
||||
|
||||
// New state vector filter will be reset. Thermal location is placed in front of a/c
|
||||
const float init_xr[4] = {INITIAL_THERMAL_STRENGTH,
|
||||
const float init_xr[4] = {_vario.get_trigger_value(),
|
||||
INITIAL_THERMAL_RADIUS,
|
||||
position.x + thermal_distance_ahead * cosf(_ahrs.yaw),
|
||||
position.y + thermal_distance_ahead * sinf(_ahrs.yaw)};
|
||||
|
@ -22,7 +22,6 @@
|
||||
|
||||
#if HAL_SOARING_ENABLED
|
||||
|
||||
#define INITIAL_THERMAL_STRENGTH 2.0
|
||||
#define INITIAL_THERMAL_RADIUS 80.0
|
||||
#define INITIAL_STRENGTH_COVARIANCE 0.0049
|
||||
#define INITIAL_RADIUS_COVARIANCE 400.0
|
||||
|
Loading…
Reference in New Issue
Block a user