mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 09:33:59 -03:00
AP_Baro: update example to use accumulate()
This commit is contained in:
parent
8ceabc97f1
commit
1ce1fa3864
@ -44,11 +44,22 @@ void setup()
|
|||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
float tmp_float;
|
float tmp_float;
|
||||||
|
static uint32_t last_print;
|
||||||
|
|
||||||
if((hal.scheduler->micros()- timer) > 50000L) {
|
bmp085.accumulate();
|
||||||
timer = hal.scheduler->micros();
|
|
||||||
|
// accumulate values at 50Hz
|
||||||
|
if ((hal.scheduler->micros()- timer) > 20000L) {
|
||||||
bmp085.read();
|
bmp085.read();
|
||||||
uint32_t read_time = hal.scheduler->micros() - timer;
|
timer = hal.scheduler->micros();
|
||||||
|
}
|
||||||
|
|
||||||
|
// print at 2Hz
|
||||||
|
if ((hal.scheduler->millis()- last_print) >= 500) {
|
||||||
|
uint32_t start = hal.scheduler->micros();
|
||||||
|
last_print = hal.scheduler->millis();
|
||||||
|
bmp085.read();
|
||||||
|
uint32_t read_time = hal.scheduler->micros() - start;
|
||||||
if (! bmp085.healthy) {
|
if (! bmp085.healthy) {
|
||||||
hal.console->println("not healthy");
|
hal.console->println("not healthy");
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user