Rover: move send_attitude up to GCS_MAVLINK

This commit is contained in:
Peter Barker 2018-05-02 16:50:43 +10:00 committed by Peter Barker
parent 514bc5c21d
commit 3799a13bc3
2 changed files with 0 additions and 20 deletions

View File

@ -75,20 +75,6 @@ MAV_STATE GCS_MAVLINK_Rover::system_status() const
return MAV_STATE_ACTIVE;
}
void Rover::send_attitude(mavlink_channel_t chan)
{
const Vector3f omega = ahrs.get_gyro();
mavlink_msg_attitude_send(
chan,
millis(),
ahrs.roll,
ahrs.pitch,
ahrs.yaw,
omega.x,
omega.y,
omega.z);
}
void Rover::send_extended_status1(mavlink_channel_t chan)
{
int16_t battery_current = -1;
@ -312,11 +298,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
}
break;
case MSG_ATTITUDE:
CHECK_PAYLOAD_SIZE(ATTITUDE);
rover.send_attitude(chan);
break;
case MSG_LOCATION:
CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);
rover.send_location(chan);

View File

@ -463,7 +463,6 @@ private:
void fence_send_mavlink_status(mavlink_channel_t chan);
// GCS_Mavlink.cpp
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);