Plane: move sending of WIND message to GCS namespace

This commit is contained in:
Peter Barker 2019-11-25 09:28:33 +11:00 committed by Andrew Tridgell
parent e75fa6fb15
commit f17ea78a6c
3 changed files with 4 additions and 4 deletions

View File

@ -304,9 +304,9 @@ void GCS_MAVLINK_Plane::send_simstate() const
#endif #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( mavlink_msg_wind_send(
chan, chan,
degrees(atan2f(-wind.y, -wind.x)), // use negative, to give 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: case MSG_WIND:
CHECK_PAYLOAD_SIZE(WIND); CHECK_PAYLOAD_SIZE(WIND);
plane.send_wind(chan); send_wind();
break; break;
case MSG_ADSB_VEHICLE: case MSG_ADSB_VEHICLE:

View File

@ -31,6 +31,7 @@ protected:
void send_aoa_ssa(); void send_aoa_ssa();
void send_attitude() const override; void send_attitude() const override;
void send_simstate() const override; void send_simstate() const override;
void send_wind() const;
bool persist_streamrates() const override { return true; } bool persist_streamrates() const override { return true; }

View File

@ -763,7 +763,6 @@ private:
void update_load_factor(void); void update_load_factor(void);
void send_fence_status(mavlink_channel_t chan); void send_fence_status(mavlink_channel_t chan);
void send_servo_out(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_Fast(void);
void Log_Write_Attitude(void); void Log_Write_Attitude(void);