2012-07-15 22:21:20 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2012-07-15 22:21:20 -03:00
|
|
|
/*
|
2012-08-17 03:08:43 -03:00
|
|
|
* Airspeed.pde - airspeed example sketch
|
|
|
|
*
|
|
|
|
*/
|
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>
|
2013-09-28 05:40:29 -03:00
|
|
|
#include <AP_HAL_Linux.h>
|
|
|
|
#include <AP_HAL_Empty.h>
|
2013-07-15 01:10:27 -03:00
|
|
|
#include <AP_ADC.h>
|
|
|
|
#include <AP_ADC_AnalogSource.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>
|
2013-09-12 22:45:57 -03:00
|
|
|
#include <AP_Vehicle.h>
|
2013-08-29 02:04:08 -03:00
|
|
|
#include <AP_Notify.h>
|
|
|
|
#include <DataFlash.h>
|
|
|
|
#include <GCS_MAVLink.h>
|
|
|
|
#include <AP_GPS.h>
|
|
|
|
#include <AP_InertialSensor.h>
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2013-07-15 01:10:27 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
|
|
AP_ADC_ADS7844 apm1_adc;
|
|
|
|
#endif
|
|
|
|
|
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
|
|
|
|
2013-09-12 22:45:57 -03:00
|
|
|
static AP_Vehicle::FixedWing aparm;
|
2013-08-29 02:04:08 -03:00
|
|
|
|
|
|
|
AP_Airspeed airspeed(aparm);
|
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
|
|
|
|
2013-06-25 10:45:30 -03:00
|
|
|
airspeed.init();
|
2012-10-09 21:01:22 -03:00
|
|
|
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
|
|
|
}
|
2013-09-28 05:40:29 -03:00
|
|
|
hal.scheduler->delay(1);
|
2012-07-15 22:21:20 -03:00
|
|
|
}
|
2012-10-09 21:01:22 -03:00
|
|
|
|
|
|
|
AP_HAL_MAIN();
|