mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 01:12:31 +00:00
mc_pos_control/FlightTask: apply nit-pick review findings
This commit is contained in:
@@ -164,7 +164,7 @@ void FlightTask::_evaluateVehicleLocalPosition()
|
||||
|
||||
void FlightTask::_evaluateDistanceToGround()
|
||||
{
|
||||
// Altitude above ground is by default just the negation of the current local position in D-direction.
|
||||
// Altitude above ground is local z-position or altitude above home or distance sensor altitude depending on what's available
|
||||
_dist_to_ground = -_position(2);
|
||||
|
||||
if (PX4_ISFINITE(_dist_to_bottom)) {
|
||||
|
||||
@@ -211,7 +211,7 @@ protected:
|
||||
matrix::Vector3f _position; /**< current vehicle position */
|
||||
matrix::Vector3f _velocity; /**< current vehicle velocity */
|
||||
float _yaw = 0.f; /**< current vehicle yaw heading */
|
||||
float _dist_to_bottom = 0.0f; /**< current height above ground level */
|
||||
float _dist_to_bottom = 0.f; /**< current height above ground level */
|
||||
float _dist_to_ground = 0.f; /**< equals _dist_to_bottom if valid, height above home otherwise */
|
||||
|
||||
/**
|
||||
|
||||
@@ -352,6 +352,7 @@ PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 0.7f);
|
||||
|
||||
/**
|
||||
* Maximum horizontal velocity during landing
|
||||
* Set the value higher than the otherwise expected maximum to disable any slowdown.
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0
|
||||
@@ -692,11 +693,12 @@ PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 45.0f);
|
||||
/**
|
||||
* Altitude for 1. step of slow landing (descend)
|
||||
*
|
||||
* Below this altitude descending velocity gets limited
|
||||
* to a value between "MPC_Z_VEL_MAX" and "MPC_LAND_SPEED"
|
||||
* to enable a smooth descent experience.
|
||||
* The horizontal velocity also gets limited to a value
|
||||
* Below this altitude:
|
||||
* - descending velocity gets limited to a value
|
||||
* between "MPC_Z_VEL_MAX" and "MPC_LAND_SPEED"
|
||||
* - horizontal velocity gets limited to a value
|
||||
* between "MPC_VEL_MANUAL" and "MPC_LAND_VEL_XY"
|
||||
* for a smooth descent and landing experience.
|
||||
* Value needs to be higher than "MPC_LAND_ALT2"
|
||||
*
|
||||
* @unit m
|
||||
|
||||
Reference in New Issue
Block a user