mirror of https://github.com/ArduPilot/ardupilot
Planner: Fixed too long enum display text.
This commit is contained in:
parent
2ee8237b5f
commit
58a4d7a4c9
|
@ -365,7 +365,7 @@ namespace ArdupilotMega
|
||||||
STABILIZE = 0, // hold level position
|
STABILIZE = 0, // hold level position
|
||||||
[DisplayText("Acro")]
|
[DisplayText("Acro")]
|
||||||
ACRO = 1, // rate control
|
ACRO = 1, // rate control
|
||||||
[DisplayText("Altitude Hold")]
|
[DisplayText("Alt Hold")]
|
||||||
ALT_HOLD = 2, // AUTO control
|
ALT_HOLD = 2, // AUTO control
|
||||||
[DisplayText("Auto")]
|
[DisplayText("Auto")]
|
||||||
AUTO = 3, // AUTO control
|
AUTO = 3, // AUTO control
|
||||||
|
@ -373,11 +373,11 @@ namespace ArdupilotMega
|
||||||
GUIDED = 4, // AUTO control
|
GUIDED = 4, // AUTO control
|
||||||
[DisplayText("Loiter")]
|
[DisplayText("Loiter")]
|
||||||
LOITER = 5, // Hold a single location
|
LOITER = 5, // Hold a single location
|
||||||
[DisplayText("Return to Launch")]
|
[DisplayText("RTL")]
|
||||||
RTL = 6, // AUTO control
|
RTL = 6, // AUTO control
|
||||||
[DisplayText("Circle")]
|
[DisplayText("Circle")]
|
||||||
CIRCLE = 7,
|
CIRCLE = 7,
|
||||||
[DisplayText("Position Hold")]
|
[DisplayText("Pos Hold")]
|
||||||
POSITION = 8,
|
POSITION = 8,
|
||||||
[DisplayText("Land")]
|
[DisplayText("Land")]
|
||||||
LAND = 9, // AUTO control
|
LAND = 9, // AUTO control
|
||||||
|
|
Loading…
Reference in New Issue