Browse Source

Rover: use floats for get/set output scaled

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
f178717212
  1. 2
      Rover/defines.h
  2. 2
      Rover/sailboat.cpp

2
Rover/defines.h

@ -11,7 +11,7 @@ @@ -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)

2
Rover/sailboat.cpp

@ -293,7 +293,7 @@ void Sailboat::get_throttle_and_mainsail_out(float desired_speed, float &throttl @@ -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 {

Loading…
Cancel
Save