mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde
This commit is contained in:
parent
fce9044fb4
commit
12497c51b5
|
@ -2,7 +2,7 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
#include <I2C.h>
|
#include <I2C.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include <Filter.h>
|
#include <Filter.h>
|
||||||
|
@ -14,50 +14,50 @@ FastSerialPort0(Serial);
|
||||||
|
|
||||||
AP_Baro_MS5611 baro;
|
AP_Baro_MS5611 baro;
|
||||||
Arduino_Mega_ISR_Registry isr_registry;
|
Arduino_Mega_ISR_Registry isr_registry;
|
||||||
AP_TimerProcess scheduler;
|
AP_TimerProcess scheduler;
|
||||||
|
|
||||||
unsigned long timer;
|
unsigned long timer;
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
Serial.begin(115200, 128, 128);
|
Serial.begin(115200, 128, 128);
|
||||||
Serial.println("ArduPilot Mega MeasSense Barometer library test");
|
Serial.println("ArduPilot Mega MeasSense Barometer library test");
|
||||||
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
isr_registry.init();
|
isr_registry.init();
|
||||||
scheduler.init(&isr_registry);
|
scheduler.init(&isr_registry);
|
||||||
|
|
||||||
pinMode(63, OUTPUT);
|
pinMode(63, OUTPUT);
|
||||||
digitalWrite(63, HIGH);
|
digitalWrite(63, HIGH);
|
||||||
SPI.begin();
|
SPI.begin();
|
||||||
SPI.setClockDivider(SPI_CLOCK_DIV32); // 500khz for debugging, increase later
|
SPI.setClockDivider(SPI_CLOCK_DIV32); // 500khz for debugging, increase later
|
||||||
|
|
||||||
baro.init(&scheduler);
|
baro.init(&scheduler);
|
||||||
baro.calibrate(delay);
|
baro.calibrate(delay);
|
||||||
timer = millis();
|
timer = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
if((micros() - timer) > 100000UL){
|
if((micros() - timer) > 100000UL) {
|
||||||
timer = micros();
|
timer = micros();
|
||||||
baro.read();
|
baro.read();
|
||||||
uint32_t read_time = micros() - timer;
|
uint32_t read_time = micros() - timer;
|
||||||
if (!baro.healthy) {
|
if (!baro.healthy) {
|
||||||
Serial.println("not healthy");
|
Serial.println("not healthy");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
Serial.print("Pressure:");
|
Serial.print("Pressure:");
|
||||||
Serial.print(baro.get_pressure());
|
Serial.print(baro.get_pressure());
|
||||||
Serial.print(" Temperature:");
|
Serial.print(" Temperature:");
|
||||||
Serial.print(baro.get_temperature());
|
Serial.print(baro.get_temperature());
|
||||||
Serial.print(" Altitude:");
|
Serial.print(" Altitude:");
|
||||||
Serial.print(baro.get_altitude());
|
Serial.print(baro.get_altitude());
|
||||||
Serial.printf(" climb=%.2f t=%u samples=%u",
|
Serial.printf(" climb=%.2f t=%u samples=%u",
|
||||||
baro.get_climb_rate(),
|
baro.get_climb_rate(),
|
||||||
(unsigned)read_time,
|
(unsigned)read_time,
|
||||||
(unsigned)baro.get_pressure_samples());
|
(unsigned)baro.get_pressure_samples());
|
||||||
Serial.println();
|
Serial.println();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue