Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp
Views: 1800
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16* Airspeed.cpp - airspeed example sketch17*18*/1920#include <AP_AHRS/AP_AHRS.h>21#include <AP_Airspeed/AP_Airspeed.h>22#include <AP_HAL/AP_HAL.h>23#include <AP_BoardConfig/AP_BoardConfig.h>24#include <GCS_MAVLink/GCS_Dummy.h>2526void setup();27void loop();2829const AP_HAL::HAL& hal = AP_HAL::get_HAL();3031float temperature;3233// create an AHRS object for get_airspeed_max34AP_AHRS ahrs;3536// create airspeed object37AP_Airspeed airspeed;3839static AP_BoardConfig board_config;4041namespace {42// try to set the object value but provide diagnostic if it failed43void set_object_value(const void *object_pointer,44const struct AP_Param::GroupInfo *group_info,45const char *name, float value)46{47if (!AP_Param::set_object_value(object_pointer, group_info, name, value)) {48hal.console->printf("WARNING: AP_Param::set object value \"%s::%s\" Failed.\n",49group_info->name, name);50}51}52}5354// to be called only once on boot for initializing objects55void setup()56{57hal.console->printf("ArduPilot Airspeed library test\n");5859// set airspeed pin to 65, enable and use to true60set_object_value(&airspeed, airspeed.var_info, "PIN", 65);61set_object_value(&airspeed, airspeed.var_info, "ENABLE", 1);62set_object_value(&airspeed, airspeed.var_info, "USE", 1);6364board_config.init();6566// initialize airspeed67// Note airspeed.set_log_bit(LOG_BIT) would need to be called in order to enable logging68airspeed.init();6970airspeed.calibrate(false);71}7273// loop74void loop(void)75{76static uint32_t timer;7778// run read() and get_temperature() in 10Hz79if ((AP_HAL::millis() - timer) > 100) {8081// current system time in milliseconds82timer = AP_HAL::millis();83airspeed.update();84airspeed.get_temperature(temperature);8586// print temperature and airspeed to console87hal.console->printf("airspeed %5.2f temperature %6.2f healthy = %u\n",88(double)airspeed.get_airspeed(), (double)temperature, airspeed.healthy());89}90hal.scheduler->delay(1);91}9293const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {94AP_GROUPEND95};96GCS_Dummy _gcs;9798AP_HAL_MAIN();99100101