Copter: use new baro API

This commit is contained in:
Andrew Tridgell 2013-09-21 21:30:54 +10:00
parent fc119d9b80
commit 35e3c887d2
2 changed files with 8 additions and 7 deletions

View File

@ -445,9 +445,9 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
mavlink_msg_scaled_pressure_send( mavlink_msg_scaled_pressure_send(
chan, chan,
millis(), millis(),
(float)barometer.get_pressure()/100.0f, barometer.get_pressure()*0.01f, // hectopascal
(float)(barometer.get_pressure() - barometer.get_ground_pressure())/100.0f, (barometer.get_pressure() - barometer.get_ground_pressure())*0.01f, // hectopascal
(int)(barometer.get_temperature()*10)); (int16_t)(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)
@ -461,8 +461,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

@ -95,8 +95,9 @@ test_baro(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"),
alt / 100.0, 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) {
return (0); return (0);