mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Changes to match Copter updates.
This commit is contained in:
parent
473016b41d
commit
3869ce55e8
@ -13,6 +13,7 @@ void Sub::gcs_send_heartbeat(void)
|
|||||||
void Sub::gcs_send_deferred(void)
|
void Sub::gcs_send_deferred(void)
|
||||||
{
|
{
|
||||||
gcs_send_message(MSG_RETRY_DEFERRED);
|
gcs_send_message(MSG_RETRY_DEFERRED);
|
||||||
|
GCS_MAVLINK::service_statustext();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -486,16 +487,6 @@ void Sub::send_pid_tuning(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void NOINLINE Sub::send_statustext(mavlink_channel_t chan)
|
|
||||||
{
|
|
||||||
mavlink_statustext_t *s = &gcs[chan-MAVLINK_COMM_0].pending_status;
|
|
||||||
mavlink_msg_statustext_send(
|
|
||||||
chan,
|
|
||||||
s->severity,
|
|
||||||
s->text);
|
|
||||||
}
|
|
||||||
|
|
||||||
// are we still delaying telemetry to try to avoid Xbee bricking?
|
// are we still delaying telemetry to try to avoid Xbee bricking?
|
||||||
bool Sub::telemetry_delayed(mavlink_channel_t chan)
|
bool Sub::telemetry_delayed(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
@ -658,9 +649,8 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_STATUSTEXT:
|
case MSG_STATUSTEXT:
|
||||||
CHECK_PAYLOAD_SIZE(STATUSTEXT);
|
// depreciated, use GCS_MAVLINK::send_statustext*
|
||||||
sub.send_statustext(chan);
|
return false;
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_LIMITS_STATUS:
|
case MSG_LIMITS_STATUS:
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
@ -2083,11 +2073,7 @@ void Sub::gcs_check_input(void)
|
|||||||
|
|
||||||
void Sub::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
void Sub::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
GCS_MAVLINK::send_statustext(severity, 0xFF, str);
|
||||||
if (gcs[i].initialised) {
|
|
||||||
gcs[i].send_text(severity, str);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -2097,17 +2083,10 @@ void Sub::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
|||||||
*/
|
*/
|
||||||
void Sub::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
|
void Sub::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list arg_list;
|
char str[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] {};
|
||||||
gcs[0].pending_status.severity = (uint8_t)severity;
|
va_list arg_list;
|
||||||
va_start(arg_list, fmt);
|
va_start(arg_list, fmt);
|
||||||
hal.util->vsnprintf((char *)gcs[0].pending_status.text,
|
|
||||||
sizeof(gcs[0].pending_status.text), fmt, arg_list);
|
|
||||||
va_end(arg_list);
|
va_end(arg_list);
|
||||||
gcs[0].send_message(MSG_STATUSTEXT);
|
hal.util->vsnprintf((char *)str, sizeof(str), fmt, arg_list);
|
||||||
for (uint8_t i=1; i<num_gcs; i++) {
|
GCS_MAVLINK::send_statustext(severity, 0xFF, str);
|
||||||
if (gcs[i].initialised) {
|
|
||||||
gcs[i].pending_status = gcs[0].pending_status;
|
|
||||||
gcs[i].send_message(MSG_STATUSTEXT);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
@ -600,7 +600,6 @@ private:
|
|||||||
void send_rpm(mavlink_channel_t chan);
|
void send_rpm(mavlink_channel_t chan);
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
void send_pid_tuning(mavlink_channel_t chan);
|
void send_pid_tuning(mavlink_channel_t chan);
|
||||||
void send_statustext(mavlink_channel_t chan);
|
|
||||||
bool telemetry_delayed(mavlink_channel_t chan);
|
bool telemetry_delayed(mavlink_channel_t chan);
|
||||||
void gcs_send_message(enum ap_message id);
|
void gcs_send_message(enum ap_message id);
|
||||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||||
|
@ -162,6 +162,8 @@ void Sub::init_ardupilot()
|
|||||||
log_init();
|
log_init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
GCS_MAVLINK::set_dataflash(&DataFlash);
|
||||||
|
|
||||||
// update motor interlock state
|
// update motor interlock state
|
||||||
update_using_interlock();
|
update_using_interlock();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user