From f5a844d4aa6c732c7aed3c5ffbc54062ef89c9c2 Mon Sep 17 00:00:00 2001 From: Andreas Antener Date: Fri, 20 Nov 2015 21:01:35 +0100 Subject: [PATCH] added field for pressure altitude to global position --- msg/vehicle_global_position.msg | 1 + src/modules/mavlink/mavlink_messages.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/msg/vehicle_global_position.msg b/msg/vehicle_global_position.msg index 6a38e2c9d7..cee381e871 100644 --- a/msg/vehicle_global_position.msg +++ b/msg/vehicle_global_position.msg @@ -18,3 +18,4 @@ float32 epv # Standard deviation of position vertically float32 terrain_alt # Terrain altitude in m, WGS84 bool terrain_alt_valid # Terrain altitude estimate is valid bool dead_reckoning # True if this position is estimated through dead-reckoning +float32 pressure_alt # Pressure altitude diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index a4926aaed6..b6653a83e0 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -2602,7 +2602,7 @@ protected: if (updated) { mavlink_altitude_t msg; - msg.altitude_monotonic = global_pos.alt; + msg.altitude_monotonic = global_pos.pressure_alt; msg.altitude_amsl = global_pos.alt; msg.altitude_local = -local_pos.z; msg.altitude_relative = home.alt;