Plane: titrotor: is_motor_tilting: dont cast to uint8

This commit is contained in:
Iampete1 2023-02-25 17:13:51 +00:00 committed by Andrew Tridgell
parent 9ac488d500
commit d97bd6f5c3
1 changed files with 1 additions and 1 deletions

View File

@ -45,7 +45,7 @@ public:
bool tilt_over_max_angle(void) const;
bool is_motor_tilting(uint8_t motor) const {
return (((uint8_t)tilt_mask.get()) & (1U<<motor));
return tilt_mask.get() & (1U<<motor);
}
bool fully_fwd() const;