mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Fixed a 1280 only test
This commit is contained in:
parent
005ff8d47e
commit
737feabc6c
@ -873,13 +873,15 @@ test_baro(uint8_t argc, const Menu::arg *argv)
|
|||||||
while(1){
|
while(1){
|
||||||
delay(100);
|
delay(100);
|
||||||
int32_t alt = read_barometer(); // calls barometer.read()
|
int32_t alt = read_barometer(); // calls barometer.read()
|
||||||
|
|
||||||
|
#if defined( __AVR_ATmega1280__ )
|
||||||
|
Serial.printf_P(PSTR("alt: %ldcm\n"),alt);
|
||||||
|
|
||||||
|
#else
|
||||||
int32_t pres = barometer.get_pressure();
|
int32_t pres = barometer.get_pressure();
|
||||||
int16_t temp = barometer.get_temperature();
|
int16_t temp = barometer.get_temperature();
|
||||||
int32_t raw_pres = barometer.get_raw_pressure();
|
int32_t raw_pres = barometer.get_raw_pressure();
|
||||||
int32_t raw_temp = barometer.get_raw_temp();
|
int32_t raw_temp = barometer.get_raw_temp();
|
||||||
#if defined( __AVR_ATmega1280__ )
|
|
||||||
Serial.printf_P(PSTR("alt: %ldcm\n"),alt);
|
|
||||||
#else
|
|
||||||
Serial.printf_P(PSTR("alt: %ldcm, pres: %ldmbar, temp: %d/100degC,"
|
Serial.printf_P(PSTR("alt: %ldcm, pres: %ldmbar, temp: %d/100degC,"
|
||||||
" raw pres: %ld, raw temp: %ld\n"),
|
" raw pres: %ld, raw temp: %ld\n"),
|
||||||
alt, pres ,temp, raw_pres, raw_temp);
|
alt, pres ,temp, raw_pres, raw_temp);
|
||||||
|
Loading…
Reference in New Issue
Block a user