diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 15e57890f8..34a869d93b 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -74,21 +74,6 @@ MAV_STATE GCS_MAVLINK_Tracker::system_status() const return MAV_STATE_ACTIVE; } -void Tracker::send_attitude(mavlink_channel_t chan) -{ - Vector3f omega = ahrs.get_gyro(); - mavlink_msg_attitude_send( - chan, - AP_HAL::millis(), - ahrs.roll, - ahrs.pitch, - ahrs.yaw, - omega.x, - omega.y, - omega.z); -} - - void Tracker::send_extended_status1(mavlink_channel_t chan) { int16_t battery_current = -1; @@ -176,11 +161,6 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id) { switch (id) { - case MSG_ATTITUDE: - CHECK_PAYLOAD_SIZE(ATTITUDE); - tracker.send_attitude(chan); - break; - case MSG_LOCATION: CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT); tracker.send_location(chan); diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 14e6f52f92..ebe76161cf 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -199,7 +199,6 @@ private: void one_second_loop(); void ten_hz_logging_loop(); - void send_attitude(mavlink_channel_t chan); void send_extended_status1(mavlink_channel_t chan); void send_location(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan);