mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: add more comments to example
This commit is contained in:
parent
47f3720040
commit
1830e72a0e
|
@ -1,3 +1,18 @@
|
|||
/*
|
||||
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
|
||||
*/
|
||||
|
@ -10,6 +25,7 @@
|
|||
|
||||
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||
|
||||
// create barometer object
|
||||
static AP_Baro barometer;
|
||||
|
||||
static uint32_t timer;
|
||||
|
@ -19,6 +35,7 @@ static AP_BoardConfig board_config;
|
|||
void setup();
|
||||
void loop();
|
||||
|
||||
// to be called only once on boot for initializing objects
|
||||
void setup()
|
||||
{
|
||||
hal.console->printf("Barometer library test\n");
|
||||
|
@ -27,14 +44,18 @@ void setup()
|
|||
|
||||
hal.scheduler->delay(1000);
|
||||
|
||||
// initialize the barometer
|
||||
barometer.init();
|
||||
barometer.calibrate();
|
||||
|
||||
// set up timer to count time in microseconds
|
||||
timer = AP_HAL::micros();
|
||||
}
|
||||
|
||||
// loop
|
||||
void loop()
|
||||
{
|
||||
// terminate program if console fails to initialize
|
||||
if (!hal.console->is_initialized()) {
|
||||
return;
|
||||
}
|
||||
|
@ -48,11 +69,15 @@ void loop()
|
|||
}
|
||||
counter = 0;
|
||||
barometer.update();
|
||||
|
||||
//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;
|
||||
}
|
||||
|
||||
//output barometer readings to console
|
||||
hal.console->printf(" Pressure: %.2f Pa\n"
|
||||
" Temperature: %.2f degC\n"
|
||||
" Relative Altitude: %.2f m\n"
|
||||
|
@ -65,6 +90,7 @@ void loop()
|
|||
(double)barometer.get_climb_rate(),
|
||||
(unsigned)read_time);
|
||||
} else {
|
||||
// if stipulated time has not passed between two distinct readings, delay the program for a millisecond
|
||||
hal.scheduler->delay(1);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue