Browse Source

Sub: mark use of get_velocity_NED as UNUSED_RESULT

velocity will stay at zero, which seems a reasonable thing to continue
with in this function
gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
b2fdd39c06
  1. 2
      ArduSub/surface_bottom_detector.cpp

2
ArduSub/surface_bottom_detector.cpp

@ -19,7 +19,7 @@ void Sub::update_surface_and_bottom_detector() @@ -19,7 +19,7 @@ void Sub::update_surface_and_bottom_detector()
}
Vector3f velocity;
ahrs.get_velocity_NED(velocity);
UNUSED_RESULT(ahrs.get_velocity_NED(velocity));
// check that we are not moving up or down
bool vel_stationary = velocity.z > -0.05 && velocity.z < 0.05;

Loading…
Cancel
Save