mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
FW land detector: reduce default for LNDFW_VEL_Z_MAX to 1m/s
And remove 0.7 factor for airspeed-less flying for the vertical speed threshold. Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
@@ -96,16 +96,14 @@ bool FixedwingLandDetector::_get_landed_state()
|
||||
const float acc_hor = matrix::Vector2f(_acceleration).norm();
|
||||
_xy_accel_filtered = _xy_accel_filtered * 0.8f + acc_hor * 0.18f;
|
||||
|
||||
// make thresholds tighter if airspeed is invalid
|
||||
// make groundspeed threshold tighter if airspeed is invalid
|
||||
const float vel_xy_max_threshold = airspeed_invalid ? 0.7f * _param_lndfw_vel_xy_max.get() :
|
||||
_param_lndfw_vel_xy_max.get();
|
||||
const float vel_z_max_threshold = airspeed_invalid ? 0.7f * _param_lndfw_vel_z_max.get() :
|
||||
_param_lndfw_vel_z_max.get();
|
||||
|
||||
// Crude land detector for fixedwing.
|
||||
landDetected = _airspeed_filtered < _param_lndfw_airspd.get()
|
||||
&& _velocity_xy_filtered < vel_xy_max_threshold
|
||||
&& _velocity_z_filtered < vel_z_max_threshold
|
||||
&& _velocity_z_filtered < _param_lndfw_vel_z_max.get()
|
||||
&& _xy_accel_filtered < _param_lndfw_xyaccel_max.get();
|
||||
|
||||
} else {
|
||||
|
||||
@@ -51,8 +51,6 @@ PARAM_DEFINE_FLOAT(LNDFW_VEL_XY_MAX, 5.0f);
|
||||
* Fixed-wing land detector: Max vertiacal velocity threshold
|
||||
*
|
||||
* Maximum vertical velocity allowed in the landed state.
|
||||
* A factor of 0.7 is applied in case of airspeed-less flying
|
||||
* (either because no sensor is present or sensor data got invalid in flight).
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.1
|
||||
@@ -61,7 +59,7 @@ PARAM_DEFINE_FLOAT(LNDFW_VEL_XY_MAX, 5.0f);
|
||||
*
|
||||
* @group Land Detector
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(LNDFW_VEL_Z_MAX, 2.0f);
|
||||
PARAM_DEFINE_FLOAT(LNDFW_VEL_Z_MAX, 1.0f);
|
||||
|
||||
/**
|
||||
* Fixed-wing land detector: Max horizontal acceleration
|
||||
|
||||
Reference in New Issue
Block a user