GCS_MAVLink: move try_send_message queued_param_send up
This commit is contained in:
parent
dbac7447d6
commit
ad2c3d27ec
@ -2103,6 +2103,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
|
||||
switch(id) {
|
||||
|
||||
case MSG_NEXT_PARAM:
|
||||
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
|
||||
queued_param_send();
|
||||
ret = true;
|
||||
break;
|
||||
|
||||
case MSG_HWSTATUS:
|
||||
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
||||
send_hwstatus();
|
||||
|
Loading…
Reference in New Issue
Block a user