From 9c2865f6a8171b99031ea4075e3b98d1d5fa861d Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 2 Feb 2015 18:12:16 -0800 Subject: [PATCH] Copter: update pv_location_to_vector to use get_origin instead of get_home --- ArduCopter/position_vector.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/position_vector.pde b/ArduCopter/position_vector.pde index 03faefc056..078e6fe16f 100644 --- a/ArduCopter/position_vector.pde +++ b/ArduCopter/position_vector.pde @@ -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; }