You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
38 lines
1.2 KiB
38 lines
1.2 KiB
#include "GCS_Tracker.h" |
|
#include "Tracker.h" |
|
|
|
void GCS_Tracker::request_datastream_position(const uint8_t sysid, const uint8_t compid) |
|
{ |
|
for (uint8_t i=0; i < num_gcs(); i++) { |
|
if (gcs().chan(i).initialised) { |
|
// request position |
|
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, DATA_STREAM)) { |
|
mavlink_msg_request_data_stream_send( |
|
(mavlink_channel_t)i, |
|
sysid, |
|
compid, |
|
MAV_DATA_STREAM_POSITION, |
|
tracker.g.mavlink_update_rate, |
|
1); // start streaming |
|
} |
|
} |
|
} |
|
} |
|
|
|
void GCS_Tracker::request_datastream_airpressure(const uint8_t sysid, const uint8_t compid) |
|
{ |
|
for (uint8_t i=0; i < num_gcs(); i++) { |
|
if (gcs().chan(i).initialised) { |
|
// request air pressure |
|
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, DATA_STREAM)) { |
|
mavlink_msg_request_data_stream_send( |
|
(mavlink_channel_t)i, |
|
sysid, |
|
compid, |
|
MAV_DATA_STREAM_RAW_SENSORS, |
|
tracker.g.mavlink_update_rate, |
|
1); // start streaming |
|
} |
|
} |
|
} |
|
}
|
|
|