Skip to content

Commit

Permalink
ArduPlane: use set_alt_m when possible
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Nov 6, 2024
1 parent 66cbbba commit 31c7e69
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions ArduPlane/mode_LoiterAltQLand.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,12 +43,12 @@ bool ModeLoiterAltQLand::handle_guided_request(Location target_loc)
// setup altitude
#if AP_TERRAIN_AVAILABLE
if (plane.terrain_enabled_in_mode(Mode::Number::QLAND)) {
target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_TERRAIN);
target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_TERRAIN);
} else {
target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME);
target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_HOME);
}
#else
target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME);
target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_HOME);
#endif

plane.set_guided_WP(target_loc);
Expand Down

0 comments on commit 31c7e69

Please sign in to comment.