mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AntennaTracker: use GCS_MAVLINK::packet_overhead_chan()
This commit is contained in:
parent
006b9728d0
commit
d4cb7b8970
@ -510,7 +510,8 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg)
|
||||
for (uint8_t i=0; i < num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
// request position
|
||||
if (comm_get_txspace((mavlink_channel_t)i) - MAVLINK_NUM_NON_PAYLOAD_BYTES >= MAVLINK_MSG_ID_DATA_STREAM_LEN) {
|
||||
if (comm_get_txspace((mavlink_channel_t)i) >=
|
||||
GCS_MAVLINK::packet_overhead_chan((mavlink_channel_t)i) + MAVLINK_MSG_ID_DATA_STREAM_LEN) {
|
||||
mavlink_msg_request_data_stream_send(
|
||||
(mavlink_channel_t)i,
|
||||
msg->sysid,
|
||||
@ -520,7 +521,8 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg)
|
||||
1); // start streaming
|
||||
}
|
||||
// request air pressure
|
||||
if (comm_get_txspace((mavlink_channel_t)i) - MAVLINK_NUM_NON_PAYLOAD_BYTES >= MAVLINK_MSG_ID_DATA_STREAM_LEN) {
|
||||
if (comm_get_txspace((mavlink_channel_t)i) >=
|
||||
GCS_MAVLINK::packet_overhead_chan((mavlink_channel_t)i) + MAVLINK_MSG_ID_DATA_STREAM_LEN) {
|
||||
mavlink_msg_request_data_stream_send(
|
||||
(mavlink_channel_t)i,
|
||||
msg->sysid,
|
||||
|
Loading…
Reference in New Issue
Block a user