ardupilot/libraries/AP_Airspeed/examples/Airspeed/Airspeed.pde

45 lines
1.0 KiB
Plaintext
Raw Normal View History

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* Airspeed.pde - airspeed example sketch
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
* as published by the Free Software Foundation; either version 2.1
* of the License, or (at your option) any later version.
*/
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Param.h>
#include <AP_Math.h>
2012-10-09 21:01:22 -03:00
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <Filter.h>
#include <AP_Buffer.h>
#include <AP_Airspeed.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
2012-10-09 21:01:22 -03:00
AP_Airspeed airspeed;
void setup()
{
2012-10-09 21:01:22 -03:00
hal.console->println("ArduPilot Airspeed library test");
airspeed.init();
2012-10-09 21:01:22 -03:00
airspeed.calibrate();
}
void loop(void)
{
static uint32_t timer;
2012-10-09 21:01:22 -03:00
if((hal.scheduler->millis() - timer) > 100) {
timer = hal.scheduler->millis();
airspeed.read();
2012-10-09 21:01:22 -03:00
hal.console->printf("airspeed %.2f\n", airspeed.get_airspeed());
}
}
2012-10-09 21:01:22 -03:00
AP_HAL_MAIN();