2012-07-15 22:21:20 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
/*
|
2012-08-17 03:08:43 -03:00
|
|
|
* 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.
|
|
|
|
*/
|
2012-07-15 22:21:20 -03:00
|
|
|
|
|
|
|
#include <AP_Common.h>
|
2012-10-27 00:55:17 -03:00
|
|
|
#include <AP_Progmem.h>
|
2012-08-20 20:22:44 -03:00
|
|
|
#include <AP_Param.h>
|
2012-07-15 22:21:20 -03:00
|
|
|
#include <AP_Math.h>
|
2012-10-09 21:01:22 -03:00
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include <AP_HAL_AVR.h>
|
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
#include <Filter.h>
|
2012-11-07 11:08:18 -04:00
|
|
|
#include <AP_Buffer.h>
|
2012-07-15 22:21:20 -03:00
|
|
|
#include <AP_Airspeed.h>
|
|
|
|
|
2012-12-18 21:26:58 -04:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2012-10-09 21:01:22 -03:00
|
|
|
AP_Airspeed airspeed;
|
2012-07-15 22:21:20 -03:00
|
|
|
|
|
|
|
void setup()
|
|
|
|
{
|
2012-10-09 21:01:22 -03:00
|
|
|
hal.console->println("ArduPilot Airspeed library test");
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2012-10-09 21:01:22 -03:00
|
|
|
airspeed.init(hal.analogin->channel(0));
|
|
|
|
airspeed.calibrate();
|
2012-07-15 22:21:20 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void loop(void)
|
|
|
|
{
|
2012-08-17 03:08:43 -03:00
|
|
|
static uint32_t timer;
|
2012-10-09 21:01:22 -03:00
|
|
|
if((hal.scheduler->millis() - timer) > 100) {
|
|
|
|
timer = hal.scheduler->millis();
|
2012-08-17 03:08:43 -03:00
|
|
|
airspeed.read();
|
2012-10-09 21:01:22 -03:00
|
|
|
hal.console->printf("airspeed %.2f\n", airspeed.get_airspeed());
|
2012-08-17 03:08:43 -03:00
|
|
|
}
|
2012-07-15 22:21:20 -03:00
|
|
|
}
|
2012-10-09 21:01:22 -03:00
|
|
|
|
|
|
|
AP_HAL_MAIN();
|