mirror of https://github.com/ArduPilot/ardupilot
AP_Landing: add AutoLand mode
This commit is contained in:
parent
9539ba6b69
commit
00fa1c4f35
|
@ -463,6 +463,18 @@ void AP_Landing::setup_landing_glide_slope(const Location &prev_WP_loc, const Lo
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
reset landing state
|
||||
*/
|
||||
void AP_Landing::reset(void)
|
||||
{
|
||||
initial_slope = 0;
|
||||
slope = 0;
|
||||
type_slope_flags.post_stats = false;
|
||||
type_slope_flags.has_aborted_due_to_slope_recalc = false;
|
||||
type_slope_stage = SlopeStage::NORMAL;
|
||||
}
|
||||
|
||||
/*
|
||||
Restart a landing by first checking for a DO_LAND_START and
|
||||
jump there. Otherwise decrement waypoint so we would re-start
|
||||
|
|
|
@ -66,6 +66,8 @@ public:
|
|||
|
||||
void convert_parameters(void);
|
||||
|
||||
void reset(void);
|
||||
|
||||
void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
|
||||
bool verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||
const int32_t auto_state_takeoff_altitude_rel_cm, bool &throttle_suppressed);
|
||||
|
|
Loading…
Reference in New Issue