AP_Follow: use set_alt_m when possible

Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
This commit is contained in:
Ryan Friedman 2024-11-06 01:20:23 -07:00 committed by Peter Barker
parent c709959f4a
commit bf3da4396b
1 changed files with 1 additions and 1 deletions

View File

@ -389,7 +389,7 @@ bool AP_Follow::handle_follow_target_message(const mavlink_message_t &msg)
Location new_loc = _target_location; Location new_loc = _target_location;
new_loc.lat = packet.lat; new_loc.lat = packet.lat;
new_loc.lng = packet.lon; new_loc.lng = packet.lon;
new_loc.set_alt_cm(packet.alt*100, Location::AltFrame::ABSOLUTE); new_loc.set_alt_m(packet.alt, Location::AltFrame::ABSOLUTE);
// FOLLOW_TARGET is always AMSL, change the provided alt to // FOLLOW_TARGET is always AMSL, change the provided alt to
// above home if we are configured for relative alt // above home if we are configured for relative alt