diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 99b8c7551e..906532e988 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -529,6 +529,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg) // Note: this doesn't check success for all sends meaning it's not guaranteed the vehicle's positions will be sent at 1hz 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) { mavlink_msg_request_data_stream_send( (mavlink_channel_t)i, @@ -538,6 +539,16 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg) 1, // 1hz 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) { + mavlink_msg_request_data_stream_send( + (mavlink_channel_t)i, + msg->sysid, + msg->compid, + MAV_DATA_STREAM_RAW_SENSORS, + 1, // 1hz + 1); // start streaming + } } }