mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
GCS_MAVLINK: added check_payload_size() method
this saves flash by moving common code to cpp
This commit is contained in:
parent
f20769057b
commit
b80dca38ff
@ -356,3 +356,15 @@ void gcs_out_of_space_to_send(mavlink_channel_t chan)
|
|||||||
{
|
{
|
||||||
gcs().chan(chan)->out_of_space_to_send();
|
gcs().chan(chan)->out_of_space_to_send();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
check there is enough space for a message
|
||||||
|
*/
|
||||||
|
bool GCS_MAVLINK::check_payload_size(uint16_t max_payload_len)
|
||||||
|
{
|
||||||
|
if (txspace() < unsigned(packet_overhead()+max_payload_len)) {
|
||||||
|
gcs_out_of_space_to_send(chan);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
@ -38,6 +38,7 @@
|
|||||||
// macros used to determine if a message will fit in the space available.
|
// macros used to determine if a message will fit in the space available.
|
||||||
|
|
||||||
void gcs_out_of_space_to_send(mavlink_channel_t chan);
|
void gcs_out_of_space_to_send(mavlink_channel_t chan);
|
||||||
|
bool check_payload_size(mavlink_channel_t chan, uint16_t max_payload_len);
|
||||||
|
|
||||||
// important note: despite the names, these messages do NOT check to
|
// 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
|
// see if the payload will fit in the buffer. They check to see if
|
||||||
@ -61,7 +62,7 @@ void gcs_out_of_space_to_send(mavlink_channel_t chan);
|
|||||||
// immediately return false from the current function if there is no
|
// 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
|
// room to fit the mavlink message with id id on the current object's
|
||||||
// output
|
// output
|
||||||
#define CHECK_PAYLOAD_SIZE(id) if (txspace() < unsigned(packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN)) { gcs_out_of_space_to_send(chan); return false; }
|
#define CHECK_PAYLOAD_SIZE(id) if (!check_payload_size(MAVLINK_MSG_ID_ ## id ## _LEN)) return false
|
||||||
|
|
||||||
// CHECK_PAYLOAD_SIZE2 - macro which inserts code which will
|
// CHECK_PAYLOAD_SIZE2 - macro which inserts code which will
|
||||||
// immediately return false from the current function if there is no
|
// immediately return false from the current function if there is no
|
||||||
@ -187,6 +188,8 @@ public:
|
|||||||
return MIN(_port->txspace(), 8192U);
|
return MIN(_port->txspace(), 8192U);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool check_payload_size(uint16_t max_payload_len);
|
||||||
|
|
||||||
// this is called when we discover we'd like to send something but can't:
|
// this is called when we discover we'd like to send something but can't:
|
||||||
void out_of_space_to_send() { out_of_space_to_send_count++; }
|
void out_of_space_to_send() { out_of_space_to_send_count++; }
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user