mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AntennaTracker: use common send_queued_parameters()
This commit is contained in:
parent
f778954b84
commit
005797c327
@ -368,14 +368,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|||||||
void
|
void
|
||||||
GCS_MAVLINK_Tracker::data_stream_send(void)
|
GCS_MAVLINK_Tracker::data_stream_send(void)
|
||||||
{
|
{
|
||||||
if (_queued_parameter != nullptr) {
|
send_queued_parameters();
|
||||||
if (streamRates[STREAM_PARAMS].get() <= 0) {
|
|
||||||
streamRates[STREAM_PARAMS].set(10);
|
|
||||||
}
|
|
||||||
if (stream_trigger(STREAM_PARAMS)) {
|
|
||||||
send_message(MSG_NEXT_PARAM);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (tracker.in_mavlink_delay) {
|
if (tracker.in_mavlink_delay) {
|
||||||
// don't send any other stream types while in the delay callback
|
// don't send any other stream types while in the delay callback
|
||||||
|
Loading…
Reference in New Issue
Block a user