Browse Source

Sub: wrap_180_cd no longer returns floats for integer arguments

master
Peter Barker 5 years ago committed by Peter Barker
parent
commit
d32a7b3a29
  1. 2
      ArduSub/commands_logic.cpp

2
ArduSub/commands_logic.cpp

@ -720,7 +720,7 @@ bool Sub::verify_yaw() @@ -720,7 +720,7 @@ bool Sub::verify_yaw()
}
// check if we are within 2 degrees of the target heading
return (fabsf(wrap_180_cd(ahrs.yaw_sensor-yaw_look_at_heading)) <= 200);
return (abs(wrap_180_cd(ahrs.yaw_sensor-yaw_look_at_heading)) <= 200);
}
/********************************************************************************/

Loading…
Cancel
Save