From f1787172120f2c3b010aa553bdda066f75f64224 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 18 Sep 2021 18:54:27 +0100 Subject: [PATCH] Rover: use floats for get/set output scaled --- Rover/defines.h | 2 +- Rover/sailboat.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Rover/defines.h b/Rover/defines.h index 49f5a5034a..aa010f7539 100644 --- a/Rover/defines.h +++ b/Rover/defines.h @@ -11,7 +11,7 @@ #define ENABLE ENABLED #define DISABLE DISABLED -#define SERVO_MAX 4500 // This value represents 45 degrees and is just an arbitrary representation of servo max travel. +#define SERVO_MAX 4500.0 // This value represents 45 degrees and is just an arbitrary representation of servo max travel. // types of failsafe events #define FAILSAFE_EVENT_THROTTLE (1<<0) diff --git a/Rover/sailboat.cpp b/Rover/sailboat.cpp index d55331e8ec..7a8d137212 100644 --- a/Rover/sailboat.cpp +++ b/Rover/sailboat.cpp @@ -293,7 +293,7 @@ void Sailboat::get_throttle_and_mainsail_out(float desired_speed, float &throttl mast_rotation_angle = 90.0f; if (wind_dir_apparent_abs > 135.0f) { // wind is almost directly behind, keep wing on current tack - if (SRV_Channels::get_output_scaled(SRV_Channel::k_mast_rotation) < 0) { + if (is_negative(SRV_Channels::get_output_scaled(SRV_Channel::k_mast_rotation))) { mast_rotation_angle *= -1.0f; } } else {