mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
GPS is disabled in this version to debug some bad behavior. If it doesn't stabilize well. Let me know.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1823 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
68e48de0f6
commit
11d71e77c8
@ -448,9 +448,9 @@ void loop()
|
|||||||
G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator
|
G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator
|
||||||
mainLoop_count++;
|
mainLoop_count++;
|
||||||
|
|
||||||
if(delta_ms_fast_loop > 11){
|
//if(delta_ms_fast_loop > 11){
|
||||||
Serial.println(delta_ms_fast_loop,DEC);
|
// Serial.println(delta_ms_fast_loop,DEC);
|
||||||
}
|
//}
|
||||||
// Execute the fast loop
|
// Execute the fast loop
|
||||||
// ---------------------
|
// ---------------------
|
||||||
fast_loop();
|
fast_loop();
|
||||||
@ -524,7 +524,7 @@ void medium_loop()
|
|||||||
case 0:
|
case 0:
|
||||||
medium_loopCounter++;
|
medium_loopCounter++;
|
||||||
|
|
||||||
update_GPS();
|
//update_GPS();
|
||||||
//readCommands();
|
//readCommands();
|
||||||
|
|
||||||
if(g.compass_enabled){
|
if(g.compass_enabled){
|
||||||
|
@ -193,7 +193,7 @@ void init_ardupilot()
|
|||||||
// read in the flight switches
|
// read in the flight switches
|
||||||
//update_servo_switches();
|
//update_servo_switches();
|
||||||
|
|
||||||
//imu.init_gyro(IMU::WARM_START); // offsets are loaded from EEPROM
|
//imu.init_gyro(IMU::WARM_START);
|
||||||
|
|
||||||
startup_ground();
|
startup_ground();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user