Skip to content

Commit

Permalink
SITL: Sailboat: write rpm and airspeed for windvane backends
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and rmackay9 committed May 27, 2019
1 parent f26e1dc commit 5839c1e
Showing 1 changed file with 4 additions and 0 deletions.
4 changes: 4 additions & 0 deletions libraries/SITL/SIM_Sailboat.cpp
Expand Up @@ -116,6 +116,10 @@ void Sailboat::update(const struct sitl_input &input)

const float wind_apparent_dir_bf = wrap_180(wind_apparent_dir_ef - degrees(AP::ahrs().yaw));

// set RPM and airspeed from wind speed, allows to test RPM and Airspeed wind vane back end in SITL
rpm1 = wind_apparent_speed;
airspeed_pitot = wind_apparent_speed;

// calculate angle-of-attack from wind to mainsail
float aoa_deg = MAX(fabsf(wind_apparent_dir_bf) - mainsail_angle_bf, 0);

Expand Down

0 comments on commit 5839c1e

Please sign in to comment.