mirror of https://github.com/ArduPilot/ardupilot
Copter: fix barometer cli test
This commit is contained in:
parent
916f241fff
commit
d1791bab76
|
@ -16,6 +16,7 @@ static void init_sonar(void)
|
|||
|
||||
static void init_barometer(void)
|
||||
{
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer"));
|
||||
barometer.calibrate();
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
|
||||
}
|
||||
|
|
|
@ -142,6 +142,10 @@ static void init_ardupilot()
|
|||
// load parameters from EEPROM
|
||||
load_parameters();
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
barometer.init();
|
||||
#endif
|
||||
|
||||
// init the GCS
|
||||
gcs0.init(hal.uartA);
|
||||
|
||||
|
@ -197,9 +201,6 @@ static void init_ardupilot()
|
|||
// begin filtering the ADC Gyros
|
||||
adc.Init(); // APM ADC library initialization
|
||||
#endif // CONFIG_ADC
|
||||
|
||||
barometer.init();
|
||||
|
||||
#endif // HIL_MODE
|
||||
|
||||
// Do GPS init
|
||||
|
@ -251,8 +252,8 @@ static void init_ardupilot()
|
|||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// initialise controller filters
|
||||
init_rate_controllers();
|
||||
// initialise controller filters
|
||||
init_rate_controllers();
|
||||
#endif // HELI_FRAME
|
||||
|
||||
// initialize commands
|
||||
|
|
|
@ -67,9 +67,9 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
|
|||
{"tune", test_tuning},
|
||||
{"relay", test_relay},
|
||||
{"wp", test_wp},
|
||||
// {"toy", test_toy},
|
||||
// {"toy", test_toy},
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
||||
{"altitude", test_baro},
|
||||
{"baro", test_baro},
|
||||
{"sonar", test_sonar},
|
||||
#endif
|
||||
{"compass", test_mag},
|
||||
|
@ -413,20 +413,21 @@ test_wp(uint8_t argc, const Menu::arg *argv)
|
|||
static int8_t
|
||||
test_baro(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
int32_t alt;
|
||||
print_hit_enter();
|
||||
init_barometer();
|
||||
|
||||
while(1) {
|
||||
delay(100);
|
||||
int32_t alt = read_barometer(); // calls barometer.read()
|
||||
alt = read_barometer();
|
||||
|
||||
float pres = barometer.get_pressure();
|
||||
int16_t temp = barometer.get_temperature();
|
||||
int32_t raw_pres = barometer.get_raw_pressure();
|
||||
int32_t raw_temp = barometer.get_raw_temp();
|
||||
cliSerial->printf_P(PSTR("alt: %ldcm, pres: %fmbar, temp: %d/100degC,"
|
||||
" raw pres: %ld, raw temp: %ld\n"),
|
||||
(long)alt, pres, (int)temp, (long)raw_pres, (long)raw_temp);
|
||||
if (!barometer.healthy) {
|
||||
cliSerial->println_P(PSTR("not healthy"));
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),
|
||||
alt / 100.0,
|
||||
barometer.get_pressure(), 0.1*barometer.get_temperature());
|
||||
}
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue