mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_Airspeed: use FALLTHROUGH define
When falling through on a case switch, allow to add an empty statement with the correct attribute to tell the compiler this behavior is intended.
This commit is contained in:
parent
3102247a85
commit
e2e836f676
@ -263,7 +263,7 @@ void AP_Airspeed::read(void)
|
|||||||
switch ((enum pitot_tube_order)_tube_order.get()) {
|
switch ((enum pitot_tube_order)_tube_order.get()) {
|
||||||
case PITOT_TUBE_ORDER_NEGATIVE:
|
case PITOT_TUBE_ORDER_NEGATIVE:
|
||||||
airspeed_pressure = -airspeed_pressure;
|
airspeed_pressure = -airspeed_pressure;
|
||||||
// no break
|
FALLTHROUGH;
|
||||||
case PITOT_TUBE_ORDER_POSITIVE:
|
case PITOT_TUBE_ORDER_POSITIVE:
|
||||||
if (airspeed_pressure < -32) {
|
if (airspeed_pressure < -32) {
|
||||||
// we're reading more than about -8m/s. The user probably has
|
// we're reading more than about -8m/s. The user probably has
|
||||||
|
Loading…
Reference in New Issue
Block a user