mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: use new Baro API
This commit is contained in:
parent
35e3c887d2
commit
bcce2e4fc5
@ -423,13 +423,13 @@ static void NOINLINE send_raw_imu1(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(
|
||||
chan,
|
||||
millis(),
|
||||
pressure/100.0,
|
||||
(pressure - barometer.get_ground_pressure())/100.0,
|
||||
barometer.get_temperature());
|
||||
pressure*0.01f, // hectopascal
|
||||
(pressure - barometer.get_ground_pressure())*0.01f, // hectopascal
|
||||
barometer.get_temperature()*100); // 0.01 degrees C
|
||||
}
|
||||
|
||||
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.z,
|
||||
compass.get_declination(),
|
||||
barometer.get_raw_pressure(),
|
||||
barometer.get_raw_temp(),
|
||||
barometer.get_pressure(),
|
||||
barometer.get_temperature()*100,
|
||||
gyro_offsets.x,
|
||||
gyro_offsets.y,
|
||||
gyro_offsets.z,
|
||||
|
@ -642,8 +642,9 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
|
||||
cliSerial->println_P(PSTR("not healthy"));
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),
|
||||
current_loc.alt / 100.0,
|
||||
barometer.get_pressure(), 0.1*barometer.get_temperature());
|
||||
current_loc.alt / 100.0,
|
||||
barometer.get_pressure(),
|
||||
barometer.get_temperature());
|
||||
}
|
||||
|
||||
if(cliSerial->available() > 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user