mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
17fc5499f8
commit
b2fdd39c06
|
@ -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…
Reference in New Issue