mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
MAVLink: comm_get_txspace should return 0 on error
it is used in expressions that add constants
This commit is contained in:
parent
24ab456f8e
commit
e59a031611
@ -94,20 +94,24 @@ static inline uint16_t comm_get_available(mavlink_channel_t chan)
|
|||||||
/// Check for available transmit space on the nominated MAVLink channel
|
/// Check for available transmit space on the nominated MAVLink channel
|
||||||
///
|
///
|
||||||
/// @param chan Channel to check
|
/// @param chan Channel to check
|
||||||
/// @returns Number of bytes available, -1 for error
|
/// @returns Number of bytes available
|
||||||
static inline int comm_get_txspace(mavlink_channel_t chan)
|
static inline uint16_t comm_get_txspace(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
|
int16_t ret = 0;
|
||||||
switch(chan) {
|
switch(chan) {
|
||||||
case MAVLINK_COMM_0:
|
case MAVLINK_COMM_0:
|
||||||
return mavlink_comm_0_port->txspace();
|
ret = mavlink_comm_0_port->txspace();
|
||||||
break;
|
break;
|
||||||
case MAVLINK_COMM_1:
|
case MAVLINK_COMM_1:
|
||||||
return mavlink_comm_1_port->txspace();
|
ret = mavlink_comm_1_port->txspace();
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
return -1;
|
if (ret < 0) {
|
||||||
|
ret = 0;
|
||||||
|
}
|
||||||
|
return (uint16_t)ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
Loading…
Reference in New Issue
Block a user