Rover: use AP_WindVane's send_wind

This commit is contained in:
Randy Mackay 2018-11-01 14:27:25 +09:00
parent 0aaa6bf054
commit 4dbff6af7e
2 changed files with 1 additions and 17 deletions

View File

@ -279,21 +279,6 @@ void Rover::send_fence_status(mavlink_channel_t chan)
fence_send_mavlink_status(chan);
}
void Rover::send_wind(mavlink_channel_t chan)
{
// exit immediately if no wind vane
if (!rover.g2.windvane.enabled()) {
return;
}
// send wind
mavlink_msg_wind_send(
chan,
wrap_360(degrees(g2.windvane.get_absolute_wind_direction_rad())),
g2.windvane.get_true_wind_speed(),
0);
}
void Rover::send_wheel_encoder(mavlink_channel_t chan)
{
// send wheel encoder data using rpm message
@ -372,7 +357,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
case MSG_WIND:
CHECK_PAYLOAD_SIZE(WIND);
rover.send_wind(chan);
rover.g2.windvane.send_wind(chan);
break;
case MSG_PID_TUNING:

View File

@ -479,7 +479,6 @@ private:
void send_pid_tuning(mavlink_channel_t chan);
void send_wheel_encoder(mavlink_channel_t chan);
void send_fence_status(mavlink_channel_t chan);
void send_wind(mavlink_channel_t chan);
void gcs_data_stream_send(void);
void gcs_update(void);
void gcs_retry_deferred(void);