Plane: use new Baro API

This commit is contained in:
Andrew Tridgell 2013-09-21 21:31:03 +10:00
parent 35e3c887d2
commit bcce2e4fc5
2 changed files with 9 additions and 8 deletions

View File

@ -423,13 +423,13 @@ static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
static void NOINLINE send_raw_imu2(mavlink_channel_t chan) static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
{ {
int32_t pressure = barometer.get_pressure(); float pressure = barometer.get_pressure();
mavlink_msg_scaled_pressure_send( mavlink_msg_scaled_pressure_send(
chan, chan,
millis(), millis(),
pressure/100.0, pressure*0.01f, // hectopascal
(pressure - barometer.get_ground_pressure())/100.0, (pressure - barometer.get_ground_pressure())*0.01f, // hectopascal
barometer.get_temperature()); barometer.get_temperature()*100); // 0.01 degrees C
} }
static void NOINLINE send_raw_imu3(mavlink_channel_t chan) static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
@ -451,8 +451,8 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
mag_offsets.y, mag_offsets.y,
mag_offsets.z, mag_offsets.z,
compass.get_declination(), compass.get_declination(),
barometer.get_raw_pressure(), barometer.get_pressure(),
barometer.get_raw_temp(), barometer.get_temperature()*100,
gyro_offsets.x, gyro_offsets.x,
gyro_offsets.y, gyro_offsets.y,
gyro_offsets.z, gyro_offsets.z,

View File

@ -642,8 +642,9 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
cliSerial->println_P(PSTR("not healthy")); cliSerial->println_P(PSTR("not healthy"));
} else { } else {
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"), cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),
current_loc.alt / 100.0, current_loc.alt / 100.0,
barometer.get_pressure(), 0.1*barometer.get_temperature()); barometer.get_pressure(),
barometer.get_temperature());
} }
if(cliSerial->available() > 0) { if(cliSerial->available() > 0) {