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
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_ADC/AP_ADC.h>
|
|
|
|
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
|
|
|
#include <AP_Airspeed/AP_Airspeed.h>
|
2012-07-15 22:21:20 -03:00
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
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
|
|
|
|
2014-07-25 04:08:01 -03:00
|
|
|
AP_Param::set_object_value(&airspeed, airspeed.var_info, "_PIN", 65);
|
2015-11-03 23:53:59 -04:00
|
|
|
AP_Param::set_object_value(&airspeed, airspeed.var_info, "_ENABLE", 1);
|
|
|
|
AP_Param::set_object_value(&airspeed, airspeed.var_info, "_USE", 1);
|
2014-07-25 04:08:01 -03:00
|
|
|
|
2013-06-25 10:45:30 -03:00
|
|
|
airspeed.init();
|
2014-11-13 06:12:37 -04:00
|
|
|
airspeed.calibrate(false);
|
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();
|
2015-11-03 23:53:59 -04:00
|
|
|
hal.console->printf("airspeed %.2f healthy=%u\n", airspeed.get_airspeed(), airspeed.healthy());
|
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();
|