mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
GCS_MAVLink: added send_queued_parameters()
This commit is contained in:
parent
58861eb51c
commit
5c4ca3bf0b
@ -180,6 +180,9 @@ public:
|
||||
// send a PARAM_VALUE message to all active MAVLink connections.
|
||||
static void send_parameter_value_all(const char *param_name, ap_var_type param_type, float param_value);
|
||||
|
||||
// send queued parameters if needed
|
||||
void send_queued_parameters(void);
|
||||
|
||||
/*
|
||||
send a MAVLink message to all components with this vehicle's system id
|
||||
This is a no-op if no routes to components have been learned
|
||||
|
@ -340,3 +340,20 @@ void GCS_MAVLINK::send_parameter_value_all(const char *param_name, ap_var_type p
|
||||
dataflash->Log_Write_Parameter(param_name, param_value);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
send queued parameters if needed
|
||||
*/
|
||||
void GCS_MAVLINK::send_queued_parameters(void)
|
||||
{
|
||||
if (_queued_parameter == nullptr &&
|
||||
param_replies.empty()) {
|
||||
return;
|
||||
}
|
||||
if (streamRates[STREAM_PARAMS].get() <= 0) {
|
||||
streamRates[STREAM_PARAMS].set(10);
|
||||
}
|
||||
if (stream_trigger(STREAM_PARAMS)) {
|
||||
send_message(MSG_NEXT_PARAM);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user