mirror of https://github.com/ArduPilot/ardupilot
Tracker: move send_attitude up to GCS_MAVLINK
This commit is contained in:
parent
3799a13bc3
commit
2b68ab4d87
|
@ -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);
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue