mirror of https://github.com/ArduPilot/ardupilot
AP_Menu: save a little ram by reducing MENU_ARGS_MAX to 3
* we only ever use 3 in arducopter's gyro gain setup
This commit is contained in:
parent
d5d97be837
commit
104ad8f6c8
|
@ -20,8 +20,8 @@
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#define MENU_COMMANDLINE_MAX 32 ///< maximum input line length
|
#define MENU_COMMANDLINE_MAX 32 ///< maximum input line length
|
||||||
#define MENU_ARGS_MAX 4 ///< maximum number of arguments
|
#define MENU_ARGS_MAX 3 ///< maximum number of arguments
|
||||||
#define MENU_COMMAND_MAX 14 ///< maximum size of a command name
|
#define MENU_COMMAND_MAX 14 ///< maximum size of a command name
|
||||||
|
|
||||||
/// Class defining and handling one menu tree
|
/// Class defining and handling one menu tree
|
||||||
class Menu {
|
class Menu {
|
||||||
|
|
Loading…
Reference in New Issue