mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
GCS_MAVLink: Bitmask is now a template
This commit is contained in:
parent
0dd71e7b3a
commit
c143ec47da
@ -532,7 +532,7 @@ private:
|
||||
int8_t next_deferred_message_to_send_cache = -1;
|
||||
|
||||
struct deferred_message_bucket_t {
|
||||
Bitmask ap_message_ids{MSG_LAST};
|
||||
Bitmask<MSG_LAST> ap_message_ids;
|
||||
uint16_t interval_ms;
|
||||
uint16_t last_sent_ms; // from AP_HAL::millis16()
|
||||
};
|
||||
@ -540,7 +540,7 @@ private:
|
||||
static const uint8_t no_bucket_to_send = -1;
|
||||
static const ap_message no_message_to_send = (ap_message)-1;
|
||||
uint8_t sending_bucket_id = no_bucket_to_send;
|
||||
Bitmask bucket_message_ids_to_send{MSG_LAST};
|
||||
Bitmask<MSG_LAST> bucket_message_ids_to_send;
|
||||
|
||||
ap_message next_deferred_bucket_message_to_send();
|
||||
void find_next_bucket_to_send();
|
||||
@ -548,7 +548,7 @@ private:
|
||||
|
||||
// bitmask of IDs the code has spontaneously decided it wants to
|
||||
// send out. Examples include HEARTBEAT (gcs_send_heartbeat)
|
||||
Bitmask pushed_ap_message_ids{MSG_LAST};
|
||||
Bitmask<MSG_LAST> pushed_ap_message_ids;
|
||||
|
||||
// returns true if it is OK to send a message while we are in
|
||||
// delay callback. In particular, when we are doing sensor init
|
||||
|
Loading…
Reference in New Issue
Block a user