mirror of https://github.com/ArduPilot/ardupilot
AP_Follow: use Location.change_alt_frame for what it is good for
This commit is contained in:
parent
cf3cceff68
commit
a4ec91c4f1
|
@ -214,9 +214,9 @@ bool AP_Follow::get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_w
|
|||
return false;
|
||||
}
|
||||
|
||||
// change to altitude above home if relative altitude is being used
|
||||
// change to altitude above home
|
||||
if (target_loc.relative_alt == 1) {
|
||||
current_loc.alt -= AP::ahrs().get_home().alt;
|
||||
current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME);
|
||||
}
|
||||
|
||||
// calculate difference
|
||||
|
|
Loading…
Reference in New Issue