From fc5ce7b273aa6a2bf6d2eb8f83a2266fcf3c8b92 Mon Sep 17 00:00:00 2001 From: Raouf Date: Thu, 6 Sep 2018 19:18:24 +0900 Subject: [PATCH] Rover: send obstacle_distance messages to proximity lib --- APMrover2/GCS_Mavlink.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index c39d9701ba..d25b6c2044 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1227,6 +1227,9 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) rover.rangefinder.handle_msg(msg); rover.g2.proximity.handle_msg(msg); break; + case MAVLINK_MSG_ID_OBSTACLE_DISTANCE: + rover.g2.proximity.handle_msg(msg); + break; default: handle_common_message(msg);