GCS_MAVLink: use panic() call for what it is good for

This commit is contained in:
Peter Barker 2018-12-07 11:09:41 +11:00 committed by Randy Mackay
parent a9c5affe8a
commit 17c82999d0

View File

@ -1242,6 +1242,10 @@ void GCS_MAVLINK::remove_message_from_bucket(int8_t bucket, ap_message id)
find_next_bucket_to_send();
}
}
if (bucket == sending_bucket_id) {
bucket_message_ids_to_send.clear(id);
}
}
bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ms)
@ -1283,9 +1287,8 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_
empty_bucket_id = i;
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (bucket.ap_message_ids.first_set() != -1) {
::fprintf(stderr, "Bucket %u has zero interval but with ids set", i);
abort();
if (bucket.ap_message_ids.count() != 0) {
AP_HAL::panic("Bucket %u has zero interval but with ids set", i);
}
#endif
continue;