mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
GCS_MAVLink: ignore Clang out-of-range warning
warning: comparison of constant 4 with expression of type 'mavlink_channel_t' is always false [-Wtautological-constant-out-of-range-compare] if (chan >= MAVLINK_COMM_NUM_BUFFERS) { ~~~~ ^ ~~~~~~~~~~~~~~~~~~~~~~~~
This commit is contained in:
parent
d54a22baaa
commit
d3e149e5d7
@ -37,8 +37,7 @@ GCS_MAVLINK::GCS_MAVLINK()
|
||||
void
|
||||
GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
|
||||
{
|
||||
// sanity check chan
|
||||
if (mav_chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
if (!valid_channel(mav_chan)) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -402,8 +401,7 @@ void GCS_MAVLINK::handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg)
|
||||
*/
|
||||
bool GCS_MAVLINK::have_flow_control(void)
|
||||
{
|
||||
// sanity check chan
|
||||
if (chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
if (!valid_channel(chan)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -54,7 +54,7 @@ void (*GCS_MAVLINK::msg_snoop)(const mavlink_message_t* msg) = NULL;
|
||||
*/
|
||||
void GCS_MAVLINK::lock_channel(mavlink_channel_t _chan, bool lock)
|
||||
{
|
||||
if (_chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
if (!valid_channel(chan)) {
|
||||
return;
|
||||
}
|
||||
if (lock) {
|
||||
@ -88,8 +88,7 @@ uint8_t mav_var_type(enum ap_var_type t)
|
||||
///
|
||||
uint8_t comm_receive_ch(mavlink_channel_t chan)
|
||||
{
|
||||
// sanity check chan
|
||||
if (chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
if (!valid_channel(chan)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -102,8 +101,7 @@ uint8_t comm_receive_ch(mavlink_channel_t chan)
|
||||
/// @returns Number of bytes available
|
||||
uint16_t comm_get_txspace(mavlink_channel_t chan)
|
||||
{
|
||||
// sanity check chan
|
||||
if (chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
if (!valid_channel(chan)) {
|
||||
return 0;
|
||||
}
|
||||
if ((1U<<chan) & mavlink_locked_mask) {
|
||||
@ -122,8 +120,7 @@ uint16_t comm_get_txspace(mavlink_channel_t chan)
|
||||
/// @returns Number of bytes available
|
||||
uint16_t comm_get_available(mavlink_channel_t chan)
|
||||
{
|
||||
// sanity check chan
|
||||
if (chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
if (!valid_channel(chan)) {
|
||||
return 0;
|
||||
}
|
||||
if ((1U<<chan) & mavlink_locked_mask) {
|
||||
@ -141,8 +138,7 @@ uint16_t comm_get_available(mavlink_channel_t chan)
|
||||
*/
|
||||
void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
|
||||
{
|
||||
// sanity check chan
|
||||
if (chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
if (!valid_channel(chan)) {
|
||||
return;
|
||||
}
|
||||
mavlink_comm_port[chan]->write(buf, len);
|
||||
|
@ -40,6 +40,21 @@ extern AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS];
|
||||
/// MAVLink system definition
|
||||
extern mavlink_system_t mavlink_system;
|
||||
|
||||
/// Sanity check MAVLink channel
|
||||
///
|
||||
/// @param chan Channel to send to
|
||||
static inline bool valid_channel(mavlink_channel_t chan)
|
||||
{
|
||||
#pragma clang diagnostic push
|
||||
#pragma clang diagnostic ignored "-Wtautological-constant-out-of-range-compare"
|
||||
if (chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
#pragma clang diagnostic pop
|
||||
}
|
||||
|
||||
/// Send a byte to the nominated MAVLink channel
|
||||
///
|
||||
/// @param chan Channel to send to
|
||||
@ -47,8 +62,7 @@ extern mavlink_system_t mavlink_system;
|
||||
///
|
||||
static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
|
||||
{
|
||||
// sanity check chan
|
||||
if (chan >= MAVLINK_COMM_NUM_BUFFERS) {
|
||||
if (!valid_channel(chan)) {
|
||||
return;
|
||||
}
|
||||
mavlink_comm_port[chan]->write(ch);
|
||||
|
Loading…
Reference in New Issue
Block a user