Browse Source

InertialSensor: removed sample rate in example

not needed any more
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
f504e2ec67
  1. 7
      libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde

7
libraries/AP_InertialSensor/examples/MPU6000/MPU6000.pde

@ -17,12 +17,9 @@ @@ -17,12 +17,9 @@
#include <AP_InertialSensor.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
#define SAMPLE_UNIT 1
#define A_LED_PIN 27
#define C_LED_PIN 25
#else
// we need 5x as many samples on the oilpan
#define SAMPLE_UNIT 5
#define A_LED_PIN 37
#define C_LED_PIN 35
#endif
@ -182,7 +179,7 @@ void run_test() @@ -182,7 +179,7 @@ void run_test()
while( !hal.console->available() ) {
// wait until we have 8 samples
while( ins.num_samples_available() < 8 * SAMPLE_UNIT ) {
while (ins.num_samples_available() == 0) {
hal.scheduler->delay(1);
}
@ -192,7 +189,7 @@ void run_test() @@ -192,7 +189,7 @@ void run_test()
gyro = ins.get_gyro();
temperature = ins.temperature();
length = sqrt(accel.x*accel.x + accel.y*accel.y + accel.z*accel.z);
length = accel.length();
// display results
hal.console->printf_P(PSTR("Accel X:%4.2f \t Y:%4.2f \t Z:%4.2f \t len:%4.2f \t Gyro X:%4.2f \t Y:%4.2f \t Z:%4.2f \t Temp:%4.2f\n"),

Loading…
Cancel
Save