mirror of https://github.com/ArduPilot/ardupilot
95 lines
2.7 KiB
C++
95 lines
2.7 KiB
C++
/*
|
|
generic Baro driver test
|
|
*/
|
|
#include <AP_Common/AP_Common.h>
|
|
#include <AP_Progmem/AP_Progmem.h>
|
|
#include <AP_Param/AP_Param.h>
|
|
#include <AP_Math/AP_Math.h>
|
|
#include <AP_HAL/AP_HAL.h>
|
|
#include <AP_Buffer/AP_Buffer.h>
|
|
#include <Filter/Filter.h>
|
|
#include <AP_Baro/AP_Baro.h>
|
|
#include <AP_Notify/AP_Notify.h>
|
|
#include <AP_GPS/AP_GPS.h>
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
#include <AP_Vehicle/AP_Vehicle.h>
|
|
#include <DataFlash/DataFlash.h>
|
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
|
#include <AP_Mission/AP_Mission.h>
|
|
#include <StorageManager/StorageManager.h>
|
|
#include <AP_Terrain/AP_Terrain.h>
|
|
#include <AP_ADC/AP_ADC.h>
|
|
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
#include <AP_Compass/AP_Compass.h>
|
|
#include <AP_Declination/AP_Declination.h>
|
|
#include <AP_Airspeed/AP_Airspeed.h>
|
|
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
|
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
|
#include <AP_HAL_Linux/AP_HAL_Linux.h>
|
|
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
|
|
#include <AP_HAL_PX4/AP_HAL_PX4.h>
|
|
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
|
#include <AP_Rally/AP_Rally.h>
|
|
#include <AP_NavEKF/AP_NavEKF.h>
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
|
|
|
static AP_Baro barometer;
|
|
|
|
static uint32_t timer;
|
|
static uint8_t counter;
|
|
|
|
void setup()
|
|
{
|
|
hal.console->println("Barometer library test");
|
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
// disable CS on MPU6000
|
|
hal.gpio->pinMode(63, HAL_GPIO_OUTPUT);
|
|
hal.gpio->write(63, 1);
|
|
#endif
|
|
|
|
barometer.init();
|
|
barometer.calibrate();
|
|
|
|
timer = hal.scheduler->micros();
|
|
}
|
|
|
|
void loop()
|
|
{
|
|
// run accumulate() at 50Hz and update() at 10Hz
|
|
if((hal.scheduler->micros() - timer) > 20*1000UL) {
|
|
timer = hal.scheduler->micros();
|
|
barometer.accumulate();
|
|
if (counter++ < 5) {
|
|
return;
|
|
}
|
|
counter = 0;
|
|
barometer.update();
|
|
uint32_t read_time = hal.scheduler->micros() - timer;
|
|
float alt = barometer.get_altitude();
|
|
if (!barometer.healthy()) {
|
|
hal.console->println("not healthy");
|
|
return;
|
|
}
|
|
hal.console->print("Pressure:");
|
|
hal.console->print(barometer.get_pressure());
|
|
hal.console->print(" Temperature:");
|
|
hal.console->print(barometer.get_temperature());
|
|
hal.console->print(" Altitude:");
|
|
hal.console->print(alt);
|
|
hal.console->printf(" climb=%.2f t=%u",
|
|
barometer.get_climb_rate(),
|
|
(unsigned)read_time);
|
|
hal.console->println();
|
|
}
|
|
}
|
|
|
|
AP_HAL_MAIN();
|