diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 2ca8f3d5ef..eb2bc068a8 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -417,6 +417,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) case MSG_RANGEFINDER: CHECK_PAYLOAD_SIZE(RANGEFINDER); rover.send_rangefinder(chan); + send_distance_sensor(rover.sonar); break; case MSG_MOUNT_STATUS: