mirror of https://github.com/ArduPilot/ardupilot
Tracker: split SYS_STATUS and POWER_STATUS onto separate ap_messages
This commit is contained in:
parent
90d13548a1
commit
06d2f97861
|
@ -135,7 +135,7 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
||||||
tracker.send_nav_controller_output(chan);
|
tracker.send_nav_controller_output(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_EXTENDED_STATUS1:
|
case MSG_SYS_STATUS:
|
||||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
||||||
tracker.send_sys_status(chan);
|
tracker.send_sys_status(chan);
|
||||||
break;
|
break;
|
||||||
|
@ -244,7 +244,8 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
||||||
MSG_SENSOR_OFFSETS
|
MSG_SENSOR_OFFSETS
|
||||||
};
|
};
|
||||||
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||||
MSG_EXTENDED_STATUS1, // SYS_STATUS, POWER_STATUS
|
MSG_SYS_STATUS,
|
||||||
|
MSG_POWER_STATUS,
|
||||||
MSG_MEMINFO,
|
MSG_MEMINFO,
|
||||||
MSG_NAV_CONTROLLER_OUTPUT,
|
MSG_NAV_CONTROLLER_OUTPUT,
|
||||||
MSG_GPS_RAW,
|
MSG_GPS_RAW,
|
||||||
|
@ -577,7 +578,7 @@ void Tracker::mavlink_delay_cb()
|
||||||
if (tnow - last_1hz > 1000) {
|
if (tnow - last_1hz > 1000) {
|
||||||
last_1hz = tnow;
|
last_1hz = tnow;
|
||||||
gcs().send_message(MSG_HEARTBEAT);
|
gcs().send_message(MSG_HEARTBEAT);
|
||||||
gcs().send_message(MSG_EXTENDED_STATUS1);
|
gcs().send_message(MSG_SYS_STATUS);
|
||||||
}
|
}
|
||||||
if (tnow - last_50hz > 20) {
|
if (tnow - last_50hz > 20) {
|
||||||
last_50hz = tnow;
|
last_50hz = tnow;
|
||||||
|
|
Loading…
Reference in New Issue