From 8423ab6364e3cb1b74e5344aaf0cad1d0b8d9262 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Tue, 11 Jan 2011 21:22:54 +0000 Subject: [PATCH] added better default value for longitude scaling git-svn-id: https://arducopter.googlecode.com/svn/trunk@1490 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/ArduCopterMega.pde | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/ArduCopterMega/ArduCopterMega.pde b/ArduCopterMega/ArduCopterMega.pde index 027a4804c3..24068d5bb6 100644 --- a/ArduCopterMega/ArduCopterMega.pde +++ b/ArduCopterMega/ArduCopterMega.pde @@ -168,8 +168,8 @@ PID pid_sonar_throttle (EE_GAIN_10); // ------------- byte ground_start_count = 5; // have we achieved first lock and set Home? const float t7 = 10000000.0; // used to scale GPS values for EEPROM storage -float scaleLongUp; // used to reverse longtitude scaling -float scaleLongDown; // used to reverse longtitude scaling +float scaleLongUp = 1; // used to reverse longtitude scaling +float scaleLongDown = 1; // used to reverse longtitude scaling boolean GPS_light = false; // status of the GPS light // Location & Navigation @@ -526,7 +526,7 @@ void medium_loop() //------------------- case 2: medium_loopCounter++; - + // Read Baro pressure // ------------------ read_barometer(); @@ -613,6 +613,10 @@ void medium_loop() flight_lights(); #endif + #if ENABLE_xx + do_something_usefull(); + #endif + if (millis() - perf_mon_timer > 20000) { if (mainLoop_count != 0) {