Browse Source

AP_Math: examples use millis/micros/panic functions

master
Caio Marcelo de Oliveira Filho 9 years ago committed by Randy Mackay
parent
commit
8257e6ab89
  1. 4
      libraries/AP_Math/examples/location/location.cpp
  2. 4
      libraries/AP_Math/examples/polygon/polygon.cpp

4
libraries/AP_Math/examples/location/location.cpp

@ -66,10 +66,10 @@ static void test_one_offset(const struct Location &loc, @@ -66,10 +66,10 @@ static void test_one_offset(const struct Location &loc,
float dist2, bearing2;
loc2 = loc;
uint32_t t1 = hal.scheduler->micros();
uint32_t t1 = AP_HAL::micros();
location_offset(loc2, ofs_north, ofs_east);
hal.console->printf("location_offset took %u usec\n",
(unsigned)(hal.scheduler->micros() - t1));
(unsigned)(AP_HAL::micros() - t1));
dist2 = get_distance(loc, loc2);
bearing2 = get_bearing_cd(loc, loc2) * 0.01f;
float brg_error = bearing2-bearing;

4
libraries/AP_Math/examples/polygon/polygon.cpp

@ -92,7 +92,7 @@ void setup(void) @@ -92,7 +92,7 @@ void setup(void)
hal.console->println(all_passed ? "TEST PASSED" : "TEST FAILED");
hal.console->println("Speed test:");
start_time = hal.scheduler->micros();
start_time = AP_HAL::micros();
for (count=0; count<1000; count++) {
for (i=0; i<ARRAY_SIZE(test_points); i++) {
bool result;
@ -103,7 +103,7 @@ void setup(void) @@ -103,7 +103,7 @@ void setup(void)
}
}
}
hal.console->printf("%u usec/call\n", (unsigned)((hal.scheduler->micros()
hal.console->printf("%u usec/call\n", (unsigned)((AP_HAL::micros()
- start_time)/(count*ARRAY_SIZE(test_points))));
hal.console->println(all_passed ? "ALL TESTS PASSED" : "TEST FAILED");
}

Loading…
Cancel
Save