Skip to content

Commit 100461d

Browse files
committed
GCS_Common: reject negative intervals
1 parent 4803bc1 commit 100461d

File tree

1 file changed

+2
-0
lines changed

1 file changed

+2
-0
lines changed

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3157,6 +3157,8 @@ MAV_RESULT GCS_MAVLINK::set_message_interval(uint32_t msg_id, int32_t interval_u
31573157
} else if (interval_us == -1) {
31583158
// minus-one is "stop sending"
31593159
interval_ms = 0;
3160+
} else if (interval_us < 0) {
3161+
return MAV_RESULT_DENIED;
31603162
} else if (interval_us < 1000) {
31613163
// don't squash sub-ms times to zero
31623164
interval_ms = 1;

0 commit comments

Comments
 (0)