mirror of https://github.com/ArduPilot/ardupilot
Plane: stop using bit-packing for quadplane state
This commit is contained in:
parent
4df758f52a
commit
c69366ac10
|
@ -443,13 +443,13 @@ private:
|
|||
Transition *transition = nullptr;
|
||||
|
||||
// true when waiting for pilot throttle
|
||||
bool throttle_wait:1;
|
||||
bool throttle_wait;
|
||||
|
||||
// true when quad is assisting a fixed wing mode
|
||||
bool assisted_flight:1;
|
||||
bool assisted_flight;
|
||||
|
||||
// are we in a guided takeoff?
|
||||
bool guided_takeoff:1;
|
||||
bool guided_takeoff;
|
||||
|
||||
/* if we arm in guided mode when we arm then go into a "waiting
|
||||
for takeoff command" state. In this state we are waiting for
|
||||
|
|
Loading…
Reference in New Issue