AP_Follow: fixed m/s to cm/s conversion

This commit is contained in:
Andrew Tridgell 2018-12-30 20:56:25 +11:00 committed by Randy Mackay
parent 42881ecf17
commit a097dd558b
1 changed files with 1 additions and 1 deletions

View File

@ -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.alt -= vel_ned.z * 10.0f * dt; // convert m/s to cm/s, multiply by dt. minus because NED
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
loc = last_loc;