mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Landing: move jump_to_landing_sequence() to AP_Mission
This commit is contained in:
parent
1a70e2f353
commit
d4d186058d
@ -236,27 +236,3 @@ bool AP_Landing::restart_landing_sequence()
|
|||||||
return success;
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
find the nearest landing sequence starting point (DO_LAND_START) and
|
|
||||||
switch to that mission item. Returns false if no DO_LAND_START
|
|
||||||
available.
|
|
||||||
*/
|
|
||||||
bool AP_Landing::jump_to_landing_sequence(void)
|
|
||||||
{
|
|
||||||
uint16_t land_idx = mission.get_landing_sequence_start();
|
|
||||||
if (land_idx != 0) {
|
|
||||||
if (mission.set_current_cmd(land_idx)) {
|
|
||||||
|
|
||||||
//if the mission has ended it has to be restarted
|
|
||||||
if (mission.state() == AP_Mission::MISSION_STOPPED) {
|
|
||||||
mission.resume();
|
|
||||||
}
|
|
||||||
|
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Landing sequence start");
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_WARNING, "Unable to start landing sequence");
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
@ -76,7 +76,6 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
bool restart_landing_sequence();
|
bool restart_landing_sequence();
|
||||||
bool jump_to_landing_sequence(void);
|
|
||||||
bool verify_land(const AP_SpdHgtControl::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
bool verify_land(const AP_SpdHgtControl::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||||
const int32_t auto_state_takeoff_altitude_rel_cm, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range, bool &throttle_suppressed);
|
const int32_t auto_state_takeoff_altitude_rel_cm, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range, bool &throttle_suppressed);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user