mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Plane: move landing.reset to landing.do_land()
This commit is contained in:
parent
61bc0a6206
commit
650e694eb1
@ -867,10 +867,10 @@ void Plane::set_flight_stage(AP_Vehicle::FixedWing::FlightStage fs)
|
||||
|
||||
landing.set_in_progress(fs == AP_Vehicle::FixedWing::FLIGHT_LAND);
|
||||
|
||||
if (fs == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
|
||||
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Landing aborted, climbing to %dm",
|
||||
auto_state.takeoff_altitude_rel_cm/100);
|
||||
}
|
||||
if (fs == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
|
||||
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Landing aborted, climbing to %dm",
|
||||
auto_state.takeoff_altitude_rel_cm/100);
|
||||
}
|
||||
|
||||
flight_stage = fs;
|
||||
|
||||
@ -978,10 +978,6 @@ void Plane::update_flight_stage(void)
|
||||
set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_NORMAL);
|
||||
}
|
||||
|
||||
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
landing.reset();
|
||||
}
|
||||
|
||||
// tell AHRS the airspeed to true airspeed ratio
|
||||
airspeed.set_EAS2TAS(barometer.get_EAS2TAS());
|
||||
}
|
||||
|
@ -13,8 +13,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
DataFlash.Log_Write_Mission_Cmd(mission, cmd);
|
||||
}
|
||||
|
||||
landing.reset();
|
||||
|
||||
// special handling for nav vs non-nav commands
|
||||
if (AP_Mission::is_nav_cmd(cmd)) {
|
||||
// set land_complete to false to stop us zeroing the throttle
|
||||
@ -138,7 +136,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_LAND_START:
|
||||
// handled in landing.reset()
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_FENCE_ENABLE:
|
||||
|
@ -343,9 +343,6 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason)
|
||||
|
||||
// reset landing check
|
||||
auto_state.checked_for_autoland = false;
|
||||
|
||||
// reset landing
|
||||
landing.reset();
|
||||
|
||||
// zero locked course
|
||||
steer_state.locked_course_err = 0;
|
||||
|
@ -141,7 +141,11 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
void AP_Landing::do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude) {
|
||||
void AP_Landing::do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude)
|
||||
{
|
||||
complete = false;
|
||||
commanded_go_around = false;
|
||||
|
||||
switch (type) {
|
||||
case TYPE_STANDARD_GLIDE_SLOPE:
|
||||
type_slope_do_land(cmd, relative_altitude);
|
||||
@ -268,20 +272,6 @@ void AP_Landing::setup_landing_glide_slope(const Location &prev_WP_loc, const Lo
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* initialize state for new nav command
|
||||
*/
|
||||
void AP_Landing::reset(void)
|
||||
{
|
||||
complete = false;
|
||||
commanded_go_around = false;
|
||||
initial_slope = 0;
|
||||
slope = 0;
|
||||
|
||||
// once landed, post some landing statistics to the GCS
|
||||
post_stats = false;
|
||||
}
|
||||
|
||||
/*
|
||||
Restart a landing by first checking for a DO_LAND_START and
|
||||
jump there. Otherwise decrement waypoint so we would re-start
|
||||
|
@ -81,7 +81,6 @@ public:
|
||||
void set_in_progress(const bool _in_progress) { in_progress = _in_progress; }
|
||||
|
||||
// helper functions
|
||||
void reset(void);
|
||||
bool restart_landing_sequence(void);
|
||||
float wind_alignment(const float heading_deg);
|
||||
float head_wind(void);
|
||||
|
@ -23,8 +23,14 @@
|
||||
|
||||
void AP_Landing::type_slope_do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude)
|
||||
{
|
||||
type_slope_stage = SLOPE_APPROACH;
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing approach start at %.1fm", (double)relative_altitude);
|
||||
initial_slope = 0;
|
||||
slope = 0;
|
||||
|
||||
// once landed, post some landing statistics to the GCS
|
||||
post_stats = false;
|
||||
|
||||
type_slope_stage = SLOPE_APPROACH;
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing approach start at %.1fm", (double)relative_altitude);
|
||||
}
|
||||
|
||||
void AP_Landing::type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
|
||||
|
Loading…
Reference in New Issue
Block a user