mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: correct gcs_out_of_space_to_send methodname
the "_count" is incorrect given the method which this calles on the link object
This commit is contained in:
parent
d1f4e95b26
commit
38119e17c7
@ -348,7 +348,7 @@ bool GCS::out_of_time() const
|
||||
return true;
|
||||
}
|
||||
|
||||
void gcs_out_of_space_to_send_count(mavlink_channel_t chan)
|
||||
void gcs_out_of_space_to_send(mavlink_channel_t chan)
|
||||
{
|
||||
gcs().chan(chan)->out_of_space_to_send();
|
||||
}
|
||||
|
@ -39,7 +39,7 @@
|
||||
|
||||
// macros used to determine if a message will fit in the space available.
|
||||
|
||||
void gcs_out_of_space_to_send_count(mavlink_channel_t chan);
|
||||
void gcs_out_of_space_to_send(mavlink_channel_t chan);
|
||||
|
||||
// important note: despite the names, these messages do NOT check to
|
||||
// see if the payload will fit in the buffer. They check to see if
|
||||
@ -56,14 +56,14 @@ void gcs_out_of_space_to_send_count(mavlink_channel_t chan);
|
||||
// anywhere in the code to determine if the mavlink message with ID id
|
||||
// can currently fit in the output of _chan. Note the use of the ","
|
||||
// operator here to increment a counter.
|
||||
#define HAVE_PAYLOAD_SPACE(_chan, id) (comm_get_txspace(_chan) >= PAYLOAD_SIZE(_chan, id) ? true : (gcs_out_of_space_to_send_count(_chan), false))
|
||||
#define HAVE_PAYLOAD_SPACE(_chan, id) (comm_get_txspace(_chan) >= PAYLOAD_SIZE(_chan, id) ? true : (gcs_out_of_space_to_send(_chan), false))
|
||||
|
||||
// CHECK_PAYLOAD_SIZE - macro which may only be used within a
|
||||
// GCS_MAVLink object's methods. It inserts code which will
|
||||
// immediately return false from the current function if there is no
|
||||
// room to fit the mavlink message with id id on the current object's
|
||||
// output
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (txspace() < unsigned(packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN)) { gcs_out_of_space_to_send_count(chan); return false; }
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (txspace() < unsigned(packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN)) { gcs_out_of_space_to_send(chan); return false; }
|
||||
|
||||
// CHECK_PAYLOAD_SIZE2 - macro which inserts code which will
|
||||
// immediately return false from the current function if there is no
|
||||
|
@ -127,7 +127,7 @@ void comm_send_lock(mavlink_channel_t chan_m, uint16_t size)
|
||||
chan_locks[chan].take_blocking();
|
||||
if (mavlink_comm_port[chan]->txspace() < size) {
|
||||
chan_discard[chan] = true;
|
||||
gcs_out_of_space_to_send_count(chan_m);
|
||||
gcs_out_of_space_to_send(chan_m);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user