|
|
@ -2,17 +2,20 @@ |
|
|
|
generic Baro driver test |
|
|
|
generic Baro driver test |
|
|
|
*/ |
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
|
|
|
|
#include <AP_Baro/AP_Baro.h> |
|
|
|
#include <AP_Baro/AP_Baro.h> |
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h> |
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h> |
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
|
|
|
|
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); |
|
|
|
const AP_HAL::HAL &hal = AP_HAL::get_HAL(); |
|
|
|
|
|
|
|
|
|
|
|
static AP_Baro barometer; |
|
|
|
static AP_Baro barometer; |
|
|
|
|
|
|
|
|
|
|
|
static uint32_t timer; |
|
|
|
static uint32_t timer; |
|
|
|
static uint8_t counter; |
|
|
|
static uint8_t counter; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void setup(); |
|
|
|
|
|
|
|
void loop(); |
|
|
|
|
|
|
|
|
|
|
|
void setup() |
|
|
|
void setup() |
|
|
|
{ |
|
|
|
{ |
|
|
|
hal.console->printf("Barometer library test\n"); |
|
|
|
hal.console->printf("Barometer library test\n"); |
|
|
@ -30,7 +33,7 @@ void setup() |
|
|
|
void loop() |
|
|
|
void loop() |
|
|
|
{ |
|
|
|
{ |
|
|
|
// run accumulate() at 50Hz and update() at 10Hz
|
|
|
|
// run accumulate() at 50Hz and update() at 10Hz
|
|
|
|
if((AP_HAL::micros() - timer) > 20*1000UL) { |
|
|
|
if ((AP_HAL::micros() - timer) > 20 * 1000UL) { |
|
|
|
timer = AP_HAL::micros(); |
|
|
|
timer = AP_HAL::micros(); |
|
|
|
barometer.accumulate(); |
|
|
|
barometer.accumulate(); |
|
|
|
if (counter++ < 5) { |
|
|
|
if (counter++ < 5) { |
|
|
|