diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 02e8e0359e..024a1ca6c4 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -109,16 +109,18 @@ MAV_STATE GCS_MAVLINK_Plane::system_status() const } -void Plane::send_attitude(mavlink_channel_t chan) +void GCS_MAVLINK_Plane::send_attitude() const { + const AP_AHRS &ahrs = AP::ahrs(); + float r = ahrs.roll; - float p = ahrs.pitch - radians(g.pitch_trim_cd*0.01f); + float p = ahrs.pitch - radians(plane.g.pitch_trim_cd*0.01f); float y = ahrs.yaw; - if (quadplane.tailsitter_active()) { - r = quadplane.ahrs_view->roll; - p = quadplane.ahrs_view->pitch; - y = quadplane.ahrs_view->yaw; + if (plane.quadplane.tailsitter_active()) { + r = plane.quadplane.ahrs_view->roll; + p = plane.quadplane.ahrs_view->pitch; + y = plane.quadplane.ahrs_view->yaw; } const Vector3f &omega = ahrs.get_gyro(); @@ -423,11 +425,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) send_power_status(); break; - case MSG_ATTITUDE: - CHECK_PAYLOAD_SIZE(ATTITUDE); - plane.send_attitude(chan); - break; - case MSG_LOCATION: CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT); plane.send_location(chan); diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 2461aa145b..505476a24b 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -34,6 +34,8 @@ protected: virtual bool in_hil_mode() const override; + void send_attitude() const override; + private: void handleMessage(mavlink_message_t * msg) override; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 3b273761bd..7811e1743c 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -768,7 +768,6 @@ private: void adjust_nav_pitch_throttle(void); void update_load_factor(void); - void send_attitude(mavlink_channel_t chan); void send_fence_status(mavlink_channel_t chan); void update_sensor_status_flags(void); void send_extended_status1(mavlink_channel_t chan);