Browse Source

AntennaTracker: use HAVE_PAYLOAD_SPACE()

master
Andrew Tridgell 9 years ago
parent
commit
16901ffb2b
  1. 6
      AntennaTracker/GCS_Mavlink.cpp

6
AntennaTracker/GCS_Mavlink.cpp

@ -510,8 +510,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg) @@ -510,8 +510,7 @@ 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) >=
GCS_MAVLINK::packet_overhead_chan((mavlink_channel_t)i) + MAVLINK_MSG_ID_DATA_STREAM_LEN) {
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, DATA_STREAM)) {
mavlink_msg_request_data_stream_send(
(mavlink_channel_t)i,
msg->sysid,
@ -521,8 +520,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg) @@ -521,8 +520,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg)
1); // start streaming
}
// request air pressure
if (comm_get_txspace((mavlink_channel_t)i) >=
GCS_MAVLINK::packet_overhead_chan((mavlink_channel_t)i) + MAVLINK_MSG_ID_DATA_STREAM_LEN) {
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, DATA_STREAM)) {
mavlink_msg_request_data_stream_send(
(mavlink_channel_t)i,
msg->sysid,

Loading…
Cancel
Save