ardupilot/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp

114 lines
3.2 KiB
C++
Raw Normal View History

2018-05-23 07:55:54 -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/>.
*/
/*
generic Baro driver test
*/
#include <AP_Baro/AP_Baro.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
2017-02-06 15:10:54 -04:00
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS_Dummy.h>
2021-02-08 10:05:31 -04:00
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
2017-02-06 15:10:54 -04:00
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
2018-05-23 07:55:54 -03:00
// create barometer object
static AP_Baro barometer;
2021-02-08 10:05:31 -04:00
#if HAL_EXTERNAL_AHRS_ENABLED
2021-02-09 10:09:51 -04:00
static AP_ExternalAHRS eAHRS;
2021-02-08 10:05:31 -04:00
#endif // HAL_EXTERNAL_AHRS_ENABLED
static uint32_t timer;
static uint8_t counter;
static AP_BoardConfig board_config;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h>
SITL::SITL sitl;
#endif
2017-02-06 15:10:54 -04:00
void setup();
void loop();
2018-05-23 07:55:54 -03:00
// to be called only once on boot for initializing objects
void setup()
{
hal.console->printf("Barometer library test\n");
board_config.init();
hal.scheduler->delay(1000);
2018-05-23 07:55:54 -03:00
// initialize the barometer
barometer.init();
barometer.calibrate();
2018-05-23 07:55:54 -03:00
// set up timer to count time in microseconds
timer = AP_HAL::micros();
}
2018-05-23 07:55:54 -03:00
// loop
void loop()
{
2018-05-23 07:55:54 -03:00
// terminate program if console fails to initialize
if (!hal.console->is_initialized()) {
return;
}
// run accumulate() at 50Hz and update() at 10Hz
2017-02-06 15:10:54 -04:00
if ((AP_HAL::micros() - timer) > 20 * 1000UL) {
timer = AP_HAL::micros();
barometer.accumulate();
if (counter++ < 5) {
return;
}
counter = 0;
barometer.update();
2018-05-23 07:55:54 -03:00
//calculate time taken for barometer readings to update
uint32_t read_time = AP_HAL::micros() - timer;
if (!barometer.healthy()) {
hal.console->printf("not healthy\n");
return;
}
2018-05-23 07:55:54 -03:00
//output barometer readings to console
hal.console->printf(" Pressure: %.2f Pa\n"
" Temperature: %.2f degC\n"
" Relative Altitude: %.2f m\n"
" climb=%.2f m/s\n"
" Read + update time: %u usec\n"
"\n",
(double)barometer.get_pressure(),
(double)barometer.get_temperature(),
(double)barometer.get_altitude(),
(double)barometer.get_climb_rate(),
2018-05-03 22:41:35 -03:00
(unsigned)read_time);
2015-09-28 06:50:14 -03:00
} else {
2018-05-23 07:55:54 -03:00
// if stipulated time has not passed between two distinct readings, delay the program for a millisecond
2015-09-28 06:50:14 -03:00
hal.scheduler->delay(1);
}
}
const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPEND
};
GCS_Dummy _gcs;
AP_HAL_MAIN();