mirror of https://github.com/ArduPilot/ardupilot
Tracker: move try_send_message queued_param_send up
This commit is contained in:
parent
1fcab08bd0
commit
33858187ef
|
@ -197,11 +197,6 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
||||||
send_sensor_offsets(tracker.ins, tracker.compass, tracker.barometer);
|
send_sensor_offsets(tracker.ins, tracker.compass, tracker.barometer);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_NEXT_PARAM:
|
|
||||||
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
|
|
||||||
queued_param_send();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_AHRS:
|
case MSG_AHRS:
|
||||||
CHECK_PAYLOAD_SIZE(AHRS);
|
CHECK_PAYLOAD_SIZE(AHRS);
|
||||||
send_ahrs(tracker.ahrs);
|
send_ahrs(tracker.ahrs);
|
||||||
|
|
Loading…
Reference in New Issue