Path: blob/master/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp
9592 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 objects33#if HAL_LOGGING_ENABLED34static AP_Logger logger;35AP_Int32 logger_bitmask;36static const struct LogStructure log_structure[] = {37LOG_COMMON_STRUCTURES38};39#endif // HAL_LOGGING_ENABLED4041static AP_AHRS ahrs;4243#if AP_EXTERNAL_AHRS_ENABLED44static AP_ExternalAHRS eAHRS;45#endif // AP_EXTERNAL_AHRS_ENABLED4647static uint32_t timer;48static AP_BoardConfig board_config;4950#if CONFIG_HAL_BOARD == HAL_BOARD_SITL51#include <SITL/SITL.h>52SITL::SIM sitl;53#endif5455void setup();56void loop();5758// to be called only once on boot for initializing objects59void setup()60{61hal.console->printf("Barometer library test\n");6263board_config.init();64#if AP_SIM_ENABLED65sitl.init();66#endif // AP_SIM_ENABLED67#if HAL_LOGGING_ENABLED68logger.init(logger_bitmask, log_structure, ARRAY_SIZE(log_structure));69#endif // HAL_LOGGING_ENABLED7071hal.scheduler->delay(1000);7273// initialize the barometer74barometer.init();75barometer.calibrate();7677// set up timer to count time in microseconds78timer = AP_HAL::micros();79}8081// loop82void loop()83{84// terminate program if console fails to initialize85if (!hal.console->is_initialized()) {86return;87}8889// run update() at 10Hz90if ((AP_HAL::micros() - timer) > 100 * 1000UL) {91timer = AP_HAL::micros();92barometer.update();9394//calculate time taken for barometer readings to update95uint32_t read_time = AP_HAL::micros() - timer;96if (!barometer.healthy()) {97hal.console->printf("not healthy\n");98return;99}100101//output barometer readings to console102hal.console->printf(" Pressure: %.2f Pa\n"103" Temperature: %.2f degC\n"104" Relative Altitude: %.2f m\n"105" climb=%.2f m/s\n"106" Read + update time: %u usec\n"107"\n",108(double)barometer.get_pressure(),109(double)barometer.get_temperature(),110(double)barometer.get_altitude(),111(double)barometer.get_climb_rate(),112(unsigned)read_time);113} else {114// if stipulated time has not passed between two distinct readings, delay the program for a millisecond115hal.scheduler->delay(1);116}117}118119GCS_Dummy _gcs;120121122AP_HAL_MAIN();123124125