mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
MulticopterLandDetector: rename vertical velocity threshold variable
This commit is contained in:
parent
06bf60672b
commit
d9764f2ef4
@ -152,13 +152,13 @@ bool MulticopterLandDetector::_get_ground_contact_state()
|
||||
// vertical speed is often deteriorated when on the ground or due to propeller
|
||||
// up/down throttling.
|
||||
|
||||
float max_vertical_velocity = _param_lndmc_z_vel_max.get();
|
||||
float vertical_velocity_threshold = _param_lndmc_z_vel_max.get();
|
||||
|
||||
if (_maybe_landed_hysteresis.get_state()) {
|
||||
max_vertical_velocity *= 2.5f;
|
||||
vertical_velocity_threshold *= 2.5f;
|
||||
}
|
||||
|
||||
_vertical_movement = (fabsf(_vehicle_local_position.vz) > max_vertical_velocity);
|
||||
_vertical_movement = (fabsf(_vehicle_local_position.vz) > vertical_velocity_threshold);
|
||||
|
||||
} else {
|
||||
_vertical_movement = true;
|
||||
|
||||
@ -48,11 +48,12 @@
|
||||
PARAM_DEFINE_FLOAT(LNDMC_TRIG_TIME, 1.0f);
|
||||
|
||||
/**
|
||||
* Multicopter max climb rate
|
||||
* Multicopter vertical velocity threshold
|
||||
*
|
||||
* Maximum vertical velocity allowed in the landed state.
|
||||
* Should be set lower than MPC_LAND_SPEED (and MPC_LAND_CRWL
|
||||
* if distance sensor is present).
|
||||
* Vertical velocity threshold to detect landing.
|
||||
* Should be set lower than the expected minimal speed for landing
|
||||
* so MPC_LAND_SPEED for autonomous landing and MPC_LAND_CRWL
|
||||
* if distance sensor is present and slowing down close to ground.
|
||||
*
|
||||
* @unit m/s
|
||||
* @decimal 1
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user