ArduPilot updates for new DCM code

G_Dt is no longer needed, and scale ADC values by 8 to match old
constants
This commit is contained in:
Andrew Tridgell 2011-09-15 13:05:31 +10:00
parent 0425f4be54
commit 58fa51b680
2 changed files with 4 additions and 4 deletions

View File

@ -502,7 +502,7 @@ static void fast_loop()
hil.update(); hil.update();
#endif #endif
dcm.update_DCM(G_Dt); dcm.update_DCM();
// uses the yaw from the DCM to give more accurate turns // uses the yaw from the DCM to give more accurate turns
calc_bearing_error(); calc_bearing_error();

View File

@ -418,7 +418,7 @@ test_adc(uint8_t argc, const Menu::arg *argv)
delay(1000); delay(1000);
while(1){ while(1){
for (int i=0;i<9;i++) Serial.printf_P(PSTR("%d\t"),adc.Ch(i)); for (int i=0;i<9;i++) Serial.printf_P(PSTR("%u\t"),adc.Ch(i));
Serial.println(); Serial.println();
delay(100); delay(100);
if(Serial.available() > 0){ if(Serial.available() > 0){
@ -476,7 +476,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
// IMU // IMU
// --- // ---
dcm.update_DCM(G_Dt); dcm.update_DCM();
if(g.compass_enabled) { if(g.compass_enabled) {
medium_loopCounter++; medium_loopCounter++;
@ -563,7 +563,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
// IMU // IMU
// --- // ---
dcm.update_DCM(G_Dt); dcm.update_DCM();
medium_loopCounter++; medium_loopCounter++;
if(medium_loopCounter == 5){ if(medium_loopCounter == 5){