mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_WindVane: rename abs to true wind
This commit is contained in:
parent
412be730e4
commit
102a231c3f
@ -293,7 +293,7 @@ void AP_WindVane::update()
|
||||
update_true_wind_speed_and_direction();
|
||||
} else {
|
||||
// no wind speed sensor, so can't do true wind calcs
|
||||
_direction_absolute = _direction_apparent_ef;
|
||||
_direction_true = _direction_apparent_ef;
|
||||
_speed_true = 0.0f;
|
||||
return;
|
||||
}
|
||||
@ -331,7 +331,7 @@ void AP_WindVane::send_wind(mavlink_channel_t chan)
|
||||
// send wind
|
||||
mavlink_msg_wind_send(
|
||||
chan,
|
||||
wrap_360(degrees(get_absolute_wind_direction_rad())),
|
||||
wrap_360(degrees(get_true_wind_direction_rad())),
|
||||
get_true_wind_speed(),
|
||||
0);
|
||||
}
|
||||
@ -344,7 +344,7 @@ void AP_WindVane::update_true_wind_speed_and_direction()
|
||||
Vector3f veh_velocity;
|
||||
if (!AP::ahrs().get_velocity_NED(veh_velocity)) {
|
||||
// if no vehicle speed use apparent speed and direction directly
|
||||
_direction_absolute = _direction_apparent_ef;
|
||||
_direction_true = _direction_apparent_ef;
|
||||
_speed_true = _speed_apparent;
|
||||
return;
|
||||
}
|
||||
@ -357,7 +357,7 @@ void AP_WindVane::update_true_wind_speed_and_direction()
|
||||
Vector2f wind_true_vec = Vector2f(wind_apparent_vec.x + veh_velocity.x, wind_apparent_vec.y + veh_velocity.y);
|
||||
|
||||
// calculate true speed and direction
|
||||
_direction_absolute = wrap_PI(atan2f(wind_true_vec.y, wind_true_vec.x) - radians(180));
|
||||
_direction_true = wrap_PI(atan2f(wind_true_vec.y, wind_true_vec.x) - radians(180));
|
||||
_speed_true = wind_true_vec.length();
|
||||
}
|
||||
|
||||
|
@ -57,8 +57,8 @@ public:
|
||||
return wrap_PI(_direction_apparent_ef - AP::ahrs().yaw);
|
||||
}
|
||||
|
||||
// get the absolute wind direction in radians, 0 = wind coming from north
|
||||
float get_absolute_wind_direction_rad() const { return _direction_absolute; }
|
||||
// get the true wind direction in radians, 0 = wind coming from north
|
||||
float get_true_wind_direction_rad() const { return _direction_true; }
|
||||
|
||||
// Return apparent wind speed
|
||||
float get_apparent_wind_speed() const { return _speed_apparent; }
|
||||
@ -112,7 +112,7 @@ private:
|
||||
|
||||
// wind direction variables
|
||||
float _direction_apparent_ef; // wind's apparent direction in radians (0 = ahead of vehicle)
|
||||
float _direction_absolute; // wind's absolute direction in radians (0 = North)
|
||||
float _direction_true; // wind's true direction in radians (0 = North)
|
||||
|
||||
// wind speed variables
|
||||
float _speed_apparent; // wind's apparent speed in m/s
|
||||
|
Loading…
Reference in New Issue
Block a user