mirror of https://github.com/ArduPilot/ardupilot
AP_Follow: replace location_offset() and get_distance() function calls with Location object member function calls
This allows removing duplicated code
This commit is contained in:
parent
dba80c95d5
commit
e7281aeddc
|
@ -152,7 +152,7 @@ bool AP_Follow::get_target_location_and_velocity(Location &loc, Vector3f &vel_ne
|
|||
|
||||
// project the vehicle position
|
||||
Location last_loc = _target_location;
|
||||
location_offset(last_loc, vel_ned.x * dt, vel_ned.y * dt);
|
||||
last_loc.offset(vel_ned.x * dt, vel_ned.y * dt);
|
||||
last_loc.alt -= vel_ned.z * 100.0f * dt; // convert m/s to cm/s, multiply by dt. minus because NED
|
||||
|
||||
// return latest position estimate
|
||||
|
|
Loading…
Reference in New Issue