diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index dd97c9fb34243..b952adc24aa10 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3157,6 +3157,8 @@ MAV_RESULT GCS_MAVLINK::set_message_interval(uint32_t msg_id, int32_t interval_u } else if (interval_us == -1) { // minus-one is "stop sending" interval_ms = 0; + } else if (interval_us < 0) { + return MAV_RESULT_DENIED; } else if (interval_us < 1000) { // don't squash sub-ms times to zero interval_ms = 1;