GCS_MAVLink: added comm_send_buffer()
this reduces the overhead of sending messages
This commit is contained in:
parent
7f20f720e8
commit
feeebae03f
@ -51,3 +51,20 @@ uint8_t mav_var_type(enum ap_var_type t)
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
send a buffer out a MAVLink channel
|
||||
*/
|
||||
void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
|
||||
{
|
||||
switch(chan) {
|
||||
case MAVLINK_COMM_0:
|
||||
mavlink_comm_0_port->write(buf, len);
|
||||
break;
|
||||
case MAVLINK_COMM_1:
|
||||
mavlink_comm_1_port->write(buf, len);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -51,6 +51,8 @@ static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
|
||||
}
|
||||
}
|
||||
|
||||
void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len);
|
||||
|
||||
/// Read a byte from the nominated MAVLink channel
|
||||
///
|
||||
/// @param chan Channel to receive on
|
||||
|
Loading…
Reference in New Issue
Block a user