diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 4d972a4e26..543013d2aa 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -304,9 +304,9 @@ void GCS_MAVLINK_Plane::send_simstate() const #endif } -void Plane::send_wind(mavlink_channel_t chan) +void GCS_MAVLINK_Plane::send_wind() const { - Vector3f wind = ahrs.wind_estimate(); + const Vector3f wind = AP::ahrs().wind_estimate(); mavlink_msg_wind_send( chan, degrees(atan2f(-wind.y, -wind.x)), // use negative, to give @@ -430,7 +430,7 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) case MSG_WIND: CHECK_PAYLOAD_SIZE(WIND); - plane.send_wind(chan); + send_wind(); break; case MSG_ADSB_VEHICLE: diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 33da5fc8fa..8c37030031 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -31,6 +31,7 @@ protected: void send_aoa_ssa(); void send_attitude() const override; void send_simstate() const override; + void send_wind() const; bool persist_streamrates() const override { return true; } diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 64f67a164b..1c5a3049d7 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -763,7 +763,6 @@ private: void update_load_factor(void); void send_fence_status(mavlink_channel_t chan); void send_servo_out(mavlink_channel_t chan); - void send_wind(mavlink_channel_t chan); void Log_Write_Fast(void); void Log_Write_Attitude(void);