Path: blob/master/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp
6356 views
/*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/*16generic Baro driver test17*/1819#include <AP_Baro/AP_Baro.h>20#include <AP_BoardConfig/AP_BoardConfig.h>21#include <AP_HAL/AP_HAL.h>22#include <GCS_MAVLink/GCS_Dummy.h>23#include <AP_ExternalAHRS/AP_ExternalAHRS.h>24#include <AP_Logger/AP_Logger.h>25#include <AP_AHRS/AP_AHRS.h>2627const AP_HAL::HAL &hal = AP_HAL::get_HAL();2829// create barometer object30static AP_Baro barometer;3132// creating other objects33static AP_Int32 log_bitmask;34static AP_Logger logger;35static AP_AHRS ahrs;3637#if AP_EXTERNAL_AHRS_ENABLED38static AP_ExternalAHRS eAHRS;39#endif // AP_EXTERNAL_AHRS_ENABLED4041static uint32_t timer;42static AP_BoardConfig board_config;4344#if CONFIG_HAL_BOARD == HAL_BOARD_SITL45#include <SITL/SITL.h>46SITL::SIM sitl;47#endif4849void setup();50void loop();5152// to be called only once on boot for initializing objects53void setup()54{55hal.console->printf("Barometer library test\n");5657board_config.init();5859hal.scheduler->delay(1000);6061// initialize the barometer62barometer.init();63barometer.calibrate();6465// set up timer to count time in microseconds66timer = AP_HAL::micros();67}6869// loop70void loop()71{72// terminate program if console fails to initialize73if (!hal.console->is_initialized()) {74return;75}7677// run update() at 10Hz78if ((AP_HAL::micros() - timer) > 100 * 1000UL) {79timer = AP_HAL::micros();80barometer.update();8182//calculate time taken for barometer readings to update83uint32_t read_time = AP_HAL::micros() - timer;84if (!barometer.healthy()) {85hal.console->printf("not healthy\n");86return;87}8889//output barometer readings to console90hal.console->printf(" Pressure: %.2f Pa\n"91" Temperature: %.2f degC\n"92" Relative Altitude: %.2f m\n"93" climb=%.2f m/s\n"94" Read + update time: %u usec\n"95"\n",96(double)barometer.get_pressure(),97(double)barometer.get_temperature(),98(double)barometer.get_altitude(),99(double)barometer.get_climb_rate(),100(unsigned)read_time);101} else {102// if stipulated time has not passed between two distinct readings, delay the program for a millisecond103hal.scheduler->delay(1);104}105}106107GCS_Dummy _gcs;108109110AP_HAL_MAIN();111112113