From 431e3443bd108e4975eae833a569d41a3e782a53 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 18 Jul 2017 21:48:04 +1000 Subject: [PATCH] Copter: move try_send_message send_hwstatus up --- ArduCopter/Copter.h | 1 - ArduCopter/GCS_Mavlink.cpp | 13 ------------- 2 files changed, 14 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 058894a38f..2ada00a75e 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -706,7 +706,6 @@ private: void send_location(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan); void send_simstate(mavlink_channel_t chan); - void send_hwstatus(mavlink_channel_t chan); void send_vfr_hud(mavlink_channel_t chan); void send_rpm(mavlink_channel_t chan); void rpm_update(); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 72d3c5baf7..94f007c182 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -182,14 +182,6 @@ void NOINLINE Copter::send_simstate(mavlink_channel_t chan) #endif } -void NOINLINE Copter::send_hwstatus(mavlink_channel_t chan) -{ - mavlink_msg_hwstatus_send( - chan, - hal.analogin->board_voltage()*1000, - 0); -} - void NOINLINE Copter::send_vfr_hud(mavlink_channel_t chan) { mavlink_msg_vfr_hud_send( @@ -445,11 +437,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) send_ahrs2(copter.ahrs); break; - case MSG_HWSTATUS: - CHECK_PAYLOAD_SIZE(HWSTATUS); - copter.send_hwstatus(chan); - break; - case MSG_MOUNT_STATUS: #if MOUNT == ENABLED CHECK_PAYLOAD_SIZE(MOUNT_STATUS);