SITL: SIM_Sailboat: remove use of AHRS

This commit is contained in:
Iampete1 2021-08-29 20:04:37 +01:00 committed by Peter Barker
parent 5de6c690d8
commit 7d536666b4

View File

@ -22,7 +22,6 @@
#include "SIM_Sailboat.h"
#include <AP_Math/AP_Math.h>
#include <AP_AHRS/AP_AHRS.h>
#include <string.h>
#include <stdio.h>
@ -189,7 +188,10 @@ void Sailboat::update(const struct sitl_input &input)
const float wind_apparent_dir_ef = degrees(atan2f(wind_apparent_ef.y, wind_apparent_ef.x));
const float wind_apparent_speed = safe_sqrt(sq(wind_apparent_ef.x)+sq(wind_apparent_ef.y));
const float wind_apparent_dir_bf = wrap_180(wind_apparent_dir_ef - degrees(AP::ahrs().yaw));
float roll, pitch, yaw;
dcm.to_euler(&roll, &pitch, &yaw);
const float wind_apparent_dir_bf = wrap_180(wind_apparent_dir_ef - degrees(yaw));
// set RPM and airspeed from wind speed, allows to test RPM and Airspeed wind vane back end in SITL
rpm[0] = wind_apparent_speed;