Skip to content

Commit

Permalink
Copter: update pv_location_to_vector to use get_origin instead of get…
Browse files Browse the repository at this point in the history
…_home
  • Loading branch information
jschall committed Feb 3, 2015
1 parent 4d5dfcf commit 46cbbe7
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduCopter/position_vector.pde
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
// pv_location_to_vector - convert lat/lon coordinates to a position vector
Vector3f pv_location_to_vector(const Location& loc)
{
const struct Location &temp_home = ahrs.get_home();
Vector3f tmp((loc.lat-temp_home.lat) * LATLON_TO_CM, (loc.lng-temp_home.lng) * LATLON_TO_CM * scaleLongDown, loc.alt);
const struct Location &origin = inertial_nav.get_origin();
Vector3f tmp((loc.lat-origin.lat) * LATLON_TO_CM, (loc.lng-origin.lng) * LATLON_TO_CM * scaleLongDown, loc.alt);
return tmp;
}

Expand Down

0 comments on commit 46cbbe7

Please sign in to comment.