From 9b3ced93eee2290617867d674df1b6ba79b2fc04 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sat, 18 Aug 2012 20:41:38 +0900 Subject: [PATCH] AP_Compass: fix for mismatching set_initial_location parameters (forgot to change long to int32_t in .cpp file) --- libraries/AP_Compass/Compass.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index 422e665001..6529183f7c 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -55,7 +55,7 @@ Compass::get_offsets() } void -Compass::set_initial_location(long latitude, long longitude) +Compass::set_initial_location(int32_t latitude, int32_t longitude) { // if automatic declination is configured, then compute // the declination based on the initial GPS fix