Skip to content

Commit

Permalink
Plan:wip;fix altitude slope issue
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Nov 29, 2024
1 parent a9880f0 commit ab7eb93
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion ArduPlane/mode_autoland.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ void ModeAutoLand::update()
{
plane.calc_nav_roll();
plane.calc_nav_pitch();

plane.set_offset_altitude_location(plane.prev_WP_loc, plane.next_WP_loc);
if (plane.landing.is_throttle_suppressed()) {
// if landing is considered complete throttle is never allowed, regardless of landing type
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
Expand All @@ -93,6 +93,7 @@ void ModeAutoLand::navigate()
land_started = true;
plane.prev_WP_loc = plane.current_loc;
plane.next_WP_loc = home_loc;
plane.set_offset_altitude_location(plane.prev_WP_loc, plane.next_WP_loc);
plane.start_command(cmd);
}
return;
Expand Down

0 comments on commit ab7eb93

Please sign in to comment.