mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Rover: use common send_queued_parameters()
This commit is contained in:
parent
005797c327
commit
37585f213a
@ -588,14 +588,7 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
||||
handle_log_send(rover.DataFlash);
|
||||
}
|
||||
|
||||
if (_queued_parameter != nullptr) {
|
||||
if (streamRates[STREAM_PARAMS].get() <= 0) {
|
||||
streamRates[STREAM_PARAMS].set(10);
|
||||
}
|
||||
if (stream_trigger(STREAM_PARAMS)) {
|
||||
send_message(MSG_NEXT_PARAM);
|
||||
}
|
||||
}
|
||||
send_queued_parameters();
|
||||
|
||||
if (rover.gcs_out_of_time) {
|
||||
return;
|
||||
|
Loading…
Reference in New Issue
Block a user