diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 8a6124e781..082582bf5f 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -294,14 +294,6 @@ void Plane::send_simstate(mavlink_channel_t chan) #endif } -void Plane::send_hwstatus(mavlink_channel_t chan) -{ - mavlink_msg_hwstatus_send( - chan, - hal.analogin->board_voltage()*1000, - 0); -} - void Plane::send_wind(mavlink_channel_t chan) { Vector3f wind = ahrs.wind_estimate(); @@ -564,11 +556,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) send_ahrs2(plane.ahrs); break; - case MSG_HWSTATUS: - CHECK_PAYLOAD_SIZE(HWSTATUS); - plane.send_hwstatus(chan); - break; - case MSG_RANGEFINDER: CHECK_PAYLOAD_SIZE(RANGEFINDER); send_rangefinder_downward(plane.rangefinder); diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 64512c24ea..824cb20a88 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -813,7 +813,6 @@ private: void send_servo_out(mavlink_channel_t chan); void send_vfr_hud(mavlink_channel_t chan); void send_simstate(mavlink_channel_t chan); - void send_hwstatus(mavlink_channel_t chan); void send_wind(mavlink_channel_t chan); void send_pid_tuning(mavlink_channel_t chan); void send_rpm(mavlink_channel_t chan);