mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
GCS_MAVLink: avoid integer underflow in mavlink txspace check
This commit is contained in:
parent
f7b01a6f3f
commit
2ebdfce4ea
@ -162,8 +162,8 @@ void GCS_MAVLINK::handle_log_send(DataFlash_Class &dataflash)
|
||||
*/
|
||||
void GCS_MAVLINK::handle_log_send_listing(DataFlash_Class &dataflash)
|
||||
{
|
||||
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
if (payload_space < MAVLINK_MSG_ID_LOG_ENTRY_LEN) {
|
||||
uint16_t txspace = comm_get_txspace(chan);
|
||||
if (txspace < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_LOG_ENTRY_LEN) {
|
||||
// no space
|
||||
return;
|
||||
}
|
||||
@ -192,8 +192,8 @@ void GCS_MAVLINK::handle_log_send_listing(DataFlash_Class &dataflash)
|
||||
*/
|
||||
bool GCS_MAVLINK::handle_log_send_data(DataFlash_Class &dataflash)
|
||||
{
|
||||
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
if (payload_space < MAVLINK_MSG_ID_LOG_DATA_LEN) {
|
||||
uint16_t txspace = comm_get_txspace(chan);
|
||||
if (txspace < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_LOG_DATA_LEN) {
|
||||
// no space
|
||||
return false;
|
||||
}
|
||||
|
@ -87,7 +87,7 @@ void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps)
|
||||
while (port->txspace() <= 0) {
|
||||
hal.scheduler->delay(5);
|
||||
}
|
||||
uint8_t n = port->txspace();
|
||||
uint16_t n = port->txspace();
|
||||
if (n > packet.count) {
|
||||
n = packet.count;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user