mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: remove do_land's use of RTL_ALT_MAX
This commit is contained in:
parent
2601ac9959
commit
4b6f03cc11
@ -301,7 +301,7 @@ static void do_land(const AP_Mission::Mission_Command& cmd)
|
||||
|
||||
// calculate and set desired location above landing target
|
||||
Vector3f pos = pv_location_to_vector(cmd.content.location);
|
||||
pos.z = min(current_loc.alt, RTL_ALT_MAX);
|
||||
pos.z = current_loc.alt;
|
||||
auto_wp_start(pos);
|
||||
}else{
|
||||
// set landing state
|
||||
|
Loading…
Reference in New Issue
Block a user