Sub: move send_attitude up to GCS_MAVLINK

This commit is contained in:
Peter Barker 2018-05-02 16:51:39 +10:00 committed by Peter Barker
parent 6f8339028e
commit 3e7cb08804
2 changed files with 0 additions and 20 deletions

View File

@ -89,20 +89,6 @@ MAV_STATE GCS_MAVLINK_Sub::system_status() const
return MAV_STATE_STANDBY;
}
NOINLINE void Sub::send_attitude(mavlink_channel_t chan)
{
const Vector3f &gyro = ins.get_gyro();
mavlink_msg_attitude_send(
chan,
millis(),
ahrs.roll,
ahrs.pitch,
ahrs.yaw,
gyro.x,
gyro.y,
gyro.z);
}
#if AC_FENCE == ENABLED
NOINLINE void Sub::send_limits_status(mavlink_channel_t chan)
{
@ -494,11 +480,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
}
break;
case MSG_ATTITUDE:
CHECK_PAYLOAD_SIZE(ATTITUDE);
sub.send_attitude(chan);
break;
case MSG_LOCATION:
CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);
sub.send_location(chan);

View File

@ -474,7 +474,6 @@ private:
void gcs_send_heartbeat(void);
void gcs_send_deferred(void);
void send_heartbeat(mavlink_channel_t chan);
void send_attitude(mavlink_channel_t chan);
void send_limits_status(mavlink_channel_t chan);
void send_extended_status1(mavlink_channel_t chan);
void send_location(mavlink_channel_t chan);