diff --git a/ArduCopterMega/ArduCopterMega.pde b/ArduCopterMega/ArduCopterMega.pde index c3f10000a3..958a5fc5a8 100644 --- a/ArduCopterMega/ArduCopterMega.pde +++ b/ArduCopterMega/ArduCopterMega.pde @@ -448,9 +448,9 @@ void loop() G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator mainLoop_count++; - if(delta_ms_fast_loop > 11){ - Serial.println(delta_ms_fast_loop,DEC); - } + //if(delta_ms_fast_loop > 11){ + // Serial.println(delta_ms_fast_loop,DEC); + //} // Execute the fast loop // --------------------- fast_loop(); @@ -524,7 +524,7 @@ void medium_loop() case 0: medium_loopCounter++; - update_GPS(); + //update_GPS(); //readCommands(); if(g.compass_enabled){ diff --git a/ArduCopterMega/system.pde b/ArduCopterMega/system.pde index 683e15fc38..f698fd3f79 100644 --- a/ArduCopterMega/system.pde +++ b/ArduCopterMega/system.pde @@ -193,7 +193,7 @@ void init_ardupilot() // read in the flight switches //update_servo_switches(); - //imu.init_gyro(IMU::WARM_START); // offsets are loaded from EEPROM + //imu.init_gyro(IMU::WARM_START); startup_ground();