mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: correct out-of-space-to-send call in HAVE_PAYLOAD_SPACE
This commit is contained in:
parent
8b0b644c11
commit
26b88823f4
|
@ -44,7 +44,7 @@ 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
|
// 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 ","
|
// can currently fit in the output of _chan. Note the use of the ","
|
||||||
// operator here to increment a counter.
|
// operator here to increment a counter.
|
||||||
#define HAVE_PAYLOAD_SPACE(_chan, id) (comm_get_txspace(_chan) >= PAYLOAD_SIZE(_chan, id) ? (gcs_out_of_space_to_send_count(_chan), true) : false)
|
#define HAVE_PAYLOAD_SPACE(_chan, id) (comm_get_txspace(_chan) >= PAYLOAD_SIZE(_chan, id) ? true : (gcs_out_of_space_to_send_count(_chan), false))
|
||||||
|
|
||||||
// CHECK_PAYLOAD_SIZE - macro which may only be used within a
|
// CHECK_PAYLOAD_SIZE - macro which may only be used within a
|
||||||
// GCS_MAVLink object's methods. It inserts code which will
|
// GCS_MAVLink object's methods. It inserts code which will
|
||||||
|
|
Loading…
Reference in New Issue