Browse Source

fixed printf_P bug

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1705 f9c3cf11-9bcb-44bc-f272-b75c42450872
mission-4.1.18
jasonshort 14 years ago
parent
commit
6fa1a9576e
  1. 2
      ArduCopterMega/ArduCopterMega.pde
  2. 22
      ArduCopterMega/setup.pde

2
ArduCopterMega/ArduCopterMega.pde

@ -1016,7 +1016,9 @@ void update_alt() @@ -1016,7 +1016,9 @@ void update_alt()
sonar_alt = min(sonar_alt, 600);
current_loc.alt = sonar_alt + home.alt;
}
}else{
// no sonar altitude
current_loc.alt = baro_alt + home.alt;
}

22
ArduCopterMega/setup.pde

@ -1057,33 +1057,19 @@ void print_enabled(boolean b) @@ -1057,33 +1057,19 @@ void print_enabled(boolean b)
void
print_accel_offsets(void)
{
Serial.println("jason");
Serial.println(imu.ax(), 2);
Serial.println((float)imu.ax(),2);
Serial.println(imu.ax(), DEC);
Serial.println("jason");
Serial.printf(PSTR("Accel offsets: %4.2f, %4.2f, %4.2f\n"),
Serial.printf_P(PSTR("Accel offsets: %4.2f, %4.2f, %4.2f\n"),
(float)imu.ax(),
(float)imu.ay(),
(float)imu.az()
);
(float)imu.az());
}
void
print_gyro_offsets(void)
{
Serial.println("jasong");
Serial.println(imu.gx(), 2);
Serial.println((float)imu.gx(),2);
Serial.println(imu.gx(), DEC);
Serial.println("jasong");
Serial.printf(PSTR("Gyro offsets: %4.2f, %4.2f, %4.2f\n"),
Serial.printf_P(PSTR("Gyro offsets: %4.2f, %4.2f, %4.2f\n"),
(float)imu.gx(),
(float)imu.gy(),
(float)imu.gz()
);
(float)imu.gz());
}

Loading…
Cancel
Save