mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: add LAND_ALT_LOW parameter
This commit is contained in:
parent
3165d72647
commit
cfc69214e6
@ -947,6 +947,15 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("PILOT_SPEED_DN", 24, ParametersG2, pilot_speed_dn, 0),
|
||||
|
||||
// @Param: LAND_ALT_LOW
|
||||
// @DisplayName: Land alt low
|
||||
// @Description: Altitude during Landing at which vehicle slows to LAND_SPEED
|
||||
// @Units: cm
|
||||
// @Range: 100 10000
|
||||
// @Increment: 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -556,6 +556,9 @@ public:
|
||||
|
||||
// Additional pilot velocity items
|
||||
AP_Int16 pilot_speed_dn;
|
||||
|
||||
// Land alt final stage
|
||||
AP_Int16 land_alt_low;
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
@ -312,9 +312,6 @@
|
||||
#ifndef LAND_SPEED
|
||||
# define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/s
|
||||
#endif
|
||||
#ifndef LAND_START_ALT
|
||||
# define LAND_START_ALT 1000 // altitude in cm where land controller switches to slow rate of descent
|
||||
#endif
|
||||
#ifndef LAND_REPOSITION_DEFAULT
|
||||
# define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing
|
||||
#endif
|
||||
|
@ -183,8 +183,8 @@ void Copter::land_run_vertical_control(bool pause_descent)
|
||||
// Don't speed up for landing.
|
||||
max_land_descent_velocity = MIN(max_land_descent_velocity, -abs(g.land_speed));
|
||||
|
||||
// Compute a vertical velocity demand such that the vehicle approaches LAND_START_ALT. Without the below constraint, this would cause the vehicle to hover at LAND_START_ALT.
|
||||
cmb_rate = AC_AttitudeControl::sqrt_controller(LAND_START_ALT-alt_above_ground, pos_control->get_pos_z_p().kP(), pos_control->get_accel_z(), G_Dt);
|
||||
// Compute a vertical velocity demand such that the vehicle approaches g2.land_alt_low. Without the below constraint, this would cause the vehicle to hover at g2.land_alt_low.
|
||||
cmb_rate = AC_AttitudeControl::sqrt_controller(MAX(g2.land_alt_low,100)-alt_above_ground, pos_control->get_pos_z_p().kP(), pos_control->get_accel_z(), G_Dt);
|
||||
|
||||
// Constrain the demanded vertical velocity so that it is between the configured maximum descent speed and the configured minimum descent speed.
|
||||
cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(g.land_speed));
|
||||
|
Loading…
Reference in New Issue
Block a user