mirror of https://github.com/ArduPilot/ardupilot
Plane: option to immediately climb in AUTO mode (not doing glide slope)
add comment in Parameters.cpp Update ArduPlane/altitude.cpp Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com> clarification in FLIGHT_OPTIONS description change the comment param comment change Update ArduPlane/Parameters.cpp Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
This commit is contained in:
parent
9acd23d196
commit
fe2e75b2a0
|
@ -1096,6 +1096,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @Bitmask: 11: Disable suppression of fixed wing rate gains in ground mode
|
||||
// @Bitmask: 12: Enable FBWB style loiter altitude control
|
||||
// @Bitmask: 13: Indicate takeoff waiting for neutral rudder with flight control surfaces
|
||||
// @Bitmask: 14: In AUTO - climb to next waypoint altitude immediately instead of linear climb
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
|
||||
|
||||
|
|
|
@ -81,6 +81,13 @@ void Plane::setup_glide_slope(void)
|
|||
break;
|
||||
|
||||
case Mode::Number::AUTO:
|
||||
|
||||
//climb without doing glide slope if option is enabled
|
||||
if (!above_location_current(next_WP_loc) && plane.flight_option_enabled(FlightOptions::IMMEDIATE_CLIMB_IN_AUTO)) {
|
||||
reset_offset_altitude();
|
||||
break;
|
||||
}
|
||||
|
||||
// we only do glide slide handling in AUTO when above 20m or
|
||||
// when descending. The 20 meter threshold is arbitrary, and
|
||||
// is basically to prevent situations where we try to slowly
|
||||
|
|
|
@ -168,6 +168,7 @@ enum FlightOptions {
|
|||
DISABLE_GROUND_PID_SUPPRESSION = (1<<11),
|
||||
ENABLE_LOITER_ALT_CONTROL = (1<<12),
|
||||
INDICATE_WAITING_FOR_RUDDER_NEUTRAL = (1<<13),
|
||||
IMMEDIATE_CLIMB_IN_AUTO = (1<<14),
|
||||
};
|
||||
|
||||
enum CrowFlapOptions {
|
||||
|
|
Loading…
Reference in New Issue