mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: remove dead assignment
This value is never used
This commit is contained in:
parent
2b08af69bc
commit
a09ac895e9
|
@ -1249,7 +1249,6 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_
|
|||
deferred_message_bucket[empty_bucket_id].interval_ms = interval_ms;
|
||||
deferred_message_bucket[empty_bucket_id].last_sent_ms = AP_HAL::millis16();
|
||||
closest_bucket = empty_bucket_id;
|
||||
closest_bucket_interval_delta = 0;
|
||||
}
|
||||
|
||||
deferred_message_bucket[closest_bucket].ap_message_ids.set(id);
|
||||
|
|
Loading…
Reference in New Issue