From 63ca982f21ba802aff513e67943b652e491bc132 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Sep 2012 10:14:20 +1000 Subject: [PATCH] APM: tidy up an if() statement --- ArduPlane/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 78dcee6b63..e920c2c28e 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1218,7 +1218,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // command needs scaling x = tell_command.lat/1.0e7; // local (x), global (latitude) y = tell_command.lng/1.0e7; // local (y), global (longitude) - if (tell_command.options & MASK_OPTIONS_RELATIVE_ALT && tell_command.id != MAV_CMD_NAV_TAKEOFF) { + if ((tell_command.options & MASK_OPTIONS_RELATIVE_ALT) && tell_command.id != MAV_CMD_NAV_TAKEOFF) { z = (tell_command.alt - home.alt) / 1.0e2; // because tell_command.alt already includes a += home.alt } else { z = tell_command.alt/1.0e2; // local (z), global/relative (altitude)