mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: use set_alt_m when possible
Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
This commit is contained in:
parent
bf3da4396b
commit
215405023d
|
@ -43,12 +43,12 @@ bool ModeLoiterAltQLand::handle_guided_request(Location target_loc)
|
||||||
// setup altitude
|
// setup altitude
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE
|
||||||
if (plane.terrain_enabled_in_mode(Mode::Number::QLAND)) {
|
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 {
|
} 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
|
#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
|
#endif
|
||||||
|
|
||||||
plane.set_guided_WP(target_loc);
|
plane.set_guided_WP(target_loc);
|
||||||
|
|
Loading…
Reference in New Issue