|
|
@ -378,6 +378,10 @@ uint8_t GCS_MAVLINK_Sub::sysid_my_gcs() const |
|
|
|
return sub.g.sysid_my_gcs; |
|
|
|
return sub.g.sysid_my_gcs; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
bool GCS_MAVLINK_Sub::vehicle_initialised() const { |
|
|
|
|
|
|
|
return sub.ap.initialised; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// try to send a message, return false if it won't fit in the serial tx buffer
|
|
|
|
// try to send a message, return false if it won't fit in the serial tx buffer
|
|
|
|
bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) |
|
|
|
bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) |
|
|
|
{ |
|
|
|
{ |
|
|
@ -399,17 +403,14 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) |
|
|
|
send_info(); |
|
|
|
send_info(); |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MSG_EXTENDED_STATUS1: |
|
|
|
case MSG_SYS_STATUS: |
|
|
|
// send extended status only once vehicle has been initialised
|
|
|
|
// send extended status only once vehicle has been initialised
|
|
|
|
// to avoid unnecessary errors being reported to user
|
|
|
|
// to avoid unnecessary errors being reported to user
|
|
|
|
if (sub.ap.initialised) { |
|
|
|
if (!vehicle_initialised()) { |
|
|
|
if (PAYLOAD_SIZE(chan, SYS_STATUS) + |
|
|
|
return true; |
|
|
|
PAYLOAD_SIZE(chan, POWER_STATUS) > comm_get_txspace(chan)) { |
|
|
|
|
|
|
|
return false; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
sub.send_sys_status(chan); |
|
|
|
|
|
|
|
send_power_status(); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
CHECK_PAYLOAD_SIZE(SYS_STATUS); |
|
|
|
|
|
|
|
sub.send_sys_status(chan); |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MSG_NAV_CONTROLLER_OUTPUT: |
|
|
|
case MSG_NAV_CONTROLLER_OUTPUT: |
|
|
@ -536,7 +537,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_CURRENT_WAYPOINT, |
|
|
|
MSG_CURRENT_WAYPOINT, |
|
|
|
MSG_GPS_RAW, |
|
|
|
MSG_GPS_RAW, |
|
|
@ -1146,7 +1148,7 @@ void Sub::mavlink_delay_cb() |
|
|
|
if (tnow - last_1hz > 1000) { |
|
|
|
if (tnow - last_1hz > 1000) { |
|
|
|
last_1hz = tnow; |
|
|
|
last_1hz = tnow; |
|
|
|
gcs_send_heartbeat(); |
|
|
|
gcs_send_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; |
|
|
|