From f77eed8f95931be35b474385c0f4f274145eb3f4 Mon Sep 17 00:00:00 2001 From: Nitay Megides Date: Sun, 20 Mar 2016 19:12:31 +0200 Subject: [PATCH] Copter: add break after prec landing case clause (And fixed indentation) --- ArduCopter/GCS_Mavlink.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 83824ecd80..4cc95d5661 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1851,10 +1851,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; #if PRECISION_LANDING == ENABLED - case MAVLINK_MSG_ID_LANDING_TARGET: - // configure or release parachute - result = MAV_RESULT_ACCEPTED; - copter.precland.handle_msg(msg); + case MAVLINK_MSG_ID_LANDING_TARGET: + // configure or release parachute + result = MAV_RESULT_ACCEPTED; + copter.precland.handle_msg(msg); + break; #endif #if CAMERA == ENABLED