From e2e17b882264b4fa484a9bf603dfbe6d3482b2c7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 4 Dec 2018 15:32:36 +1100 Subject: [PATCH] Sub: rename send_extended_status1 to send_sys_status --- ArduSub/GCS_Mavlink.cpp | 4 ++-- ArduSub/Sub.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 38a8da7395..210ad73243 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -84,7 +84,7 @@ MAV_STATE GCS_MAVLINK_Sub::system_status() const return MAV_STATE_STANDBY; } -NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan) +NOINLINE void Sub::send_sys_status(mavlink_channel_t chan) { uint32_t control_sensors_present; uint32_t control_sensors_enabled; @@ -404,7 +404,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) // to avoid unnecessary errors being reported to user if (sub.ap.initialised) { CHECK_PAYLOAD_SIZE(SYS_STATUS); - sub.send_extended_status1(chan); + sub.send_sys_status(chan); CHECK_PAYLOAD_SIZE(POWER_STATUS); send_power_status(); } diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 1138d35c93..5882f665a1 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -475,7 +475,7 @@ private: void rotate_body_frame_to_NE(float &x, float &y); void gcs_send_heartbeat(void); void send_heartbeat(mavlink_channel_t chan); - void send_extended_status1(mavlink_channel_t chan); + void send_sys_status(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan); #if RPM_ENABLED == ENABLED void send_rpm(mavlink_channel_t chan);