mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_Landing: Deepstall: Allow requiring a minimum altitude to abort a landing
This commit is contained in:
parent
202b40562f
commit
e092a83ca2
@ -128,6 +128,14 @@ const AP_Param::GroupInfo AP_Landing_Deepstall::var_info[] = {
|
|||||||
// @Path: ../PID/PID.cpp
|
// @Path: ../PID/PID.cpp
|
||||||
AP_SUBGROUPINFO(ds_PID, "", 14, AP_Landing_Deepstall, PID),
|
AP_SUBGROUPINFO(ds_PID, "", 14, AP_Landing_Deepstall, PID),
|
||||||
|
|
||||||
|
// @Param: ABORTALT
|
||||||
|
// @DisplayName: Deepstall minimum abort altitude
|
||||||
|
// @Description: The minimum altitude which the aircraft must be above to abort a deepstall landing
|
||||||
|
// @Range: 0 50
|
||||||
|
// @Units meters
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("ABORTALT", 15, AP_Landing_Deepstall, min_abort_alt, 0.0f),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -336,8 +344,15 @@ bool AP_Landing_Deepstall::override_servos(void)
|
|||||||
|
|
||||||
bool AP_Landing_Deepstall::request_go_around(void)
|
bool AP_Landing_Deepstall::request_go_around(void)
|
||||||
{
|
{
|
||||||
|
float current_altitude_d;
|
||||||
|
landing.ahrs.get_relative_position_D_home(current_altitude_d);
|
||||||
|
|
||||||
|
if (is_zero(min_abort_alt) || -current_altitude_d > min_abort_alt) {
|
||||||
landing.flags.commanded_go_around = true;
|
landing.flags.commanded_go_around = true;
|
||||||
return true;
|
return true;
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Landing_Deepstall::is_throttle_suppressed(void) const
|
bool AP_Landing_Deepstall::is_throttle_suppressed(void) const
|
||||||
|
@ -67,6 +67,7 @@ private:
|
|||||||
AP_Float L1_i;
|
AP_Float L1_i;
|
||||||
AP_Float yaw_rate_limit;
|
AP_Float yaw_rate_limit;
|
||||||
AP_Float time_constant;
|
AP_Float time_constant;
|
||||||
|
AP_Float min_abort_alt;
|
||||||
int32_t loiter_sum_cd; // used for tracking the progress on loitering
|
int32_t loiter_sum_cd; // used for tracking the progress on loitering
|
||||||
deepstall_stage stage;
|
deepstall_stage stage;
|
||||||
Location landing_point;
|
Location landing_point;
|
||||||
|
Loading…
Reference in New Issue
Block a user