diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index fc677dfec0f2eb..9d10ea106d0461 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -28,6 +28,7 @@ #include #include #include +#include #include "ap_message.h" @@ -267,6 +268,11 @@ class GCS_MAVLINK // accessor for uart AP_HAL::UARTDriver *get_uart() { return _port; } +#if AP_SCHEDULER_ENABLED + // cap the MAVLink message rate. It can't be greater than 0.8 * SCHED_LOOP_RATE + uint16_t cap_message_interval(uint16_t interval_ms) const; +#endif + virtual uint8_t sysid_my_gcs() const = 0; virtual bool sysid_enforce() const { return false; } diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 05c2d8f85c81e7..3a6907b543b20b 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -225,6 +225,16 @@ void GCS_MAVLINK::send_power_status(void) hal.analogin->power_status_flags()); } +#if AP_SCHEDULER_ENABLED +// cap the MAVLink message rate. It can't be greater than 0.8 * SCHED_LOOP_RATE +uint16_t GCS_MAVLINK::cap_message_interval(uint16_t interval_ms) const { + if (interval_ms*800 < AP::scheduler().get_loop_period_us()) { + return AP::scheduler().get_loop_period_us()/800.0f; + } + return interval_ms; +} +#endif + #if HAL_WITH_MCU_MONITORING // report MCU voltage/temperature status void GCS_MAVLINK::send_mcu_status(void) @@ -1652,11 +1662,7 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ } #if AP_SCHEDULER_ENABLED - // send messages out at most 80% of main loop rate - if (interval_ms != 0 && - interval_ms*800 < AP::scheduler().get_loop_period_us()) { - interval_ms = AP::scheduler().get_loop_period_us()/800.0f; - } + interval_ms = cap_message_interval(interval_ms); #endif // check if it's a specially-handled message: @@ -3127,6 +3133,12 @@ MAV_RESULT GCS_MAVLINK::set_message_interval(uint32_t msg_id, int32_t interval_u } else { interval_ms = interval_us / 1000; } +#if AP_SCHEDULER_ENABLED + if (cap_message_interval(interval_ms) > interval_ms) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Requested message rate too fast. Increase SCHED_LOOP_RATE"); + return MAV_RESULT_DENIED; + } +#endif if (set_ap_message_interval(id, interval_ms)) { return MAV_RESULT_ACCEPTED; }