ardupilot/libraries/AP_Menu/examples/menu/menu.pde

55 lines
1012 B
Plaintext
Raw Normal View History

#include <AP_Common.h>
#include <AP_Math.h>
#include <AP_Param.h>
2014-08-13 09:12:08 -03:00
#include <StorageManager.h>
2012-11-12 17:12:40 -04:00
#include <AP_Progmem.h>
#include <AP_Menu.h>
2012-11-12 17:12:40 -04:00
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
int8_t
menu_test(uint8_t argc, const Menu::arg *argv)
{
int i;
2012-11-12 17:12:40 -04:00
hal.console->printf("This is a test with %d arguments\n", argc);
2011-10-28 15:43:43 -03:00
for (i = 1; i < argc; i++) {
2012-11-12 17:12:40 -04:00
hal.console->printf("%d: int %ld float ", i, argv[i].i);
hal.console->println(argv[i].f, 6); // gross
2011-10-28 15:43:43 -03:00
}
2012-12-18 20:18:08 -04:00
return 0;
}
int8_t
menu_auto(uint8_t argc, const Menu::arg *argv)
{
2012-11-12 17:12:40 -04:00
hal.console->println("auto text");
2012-12-18 20:18:08 -04:00
return 0;
}
const struct Menu::command top_menu_commands[] PROGMEM = {
2011-10-28 15:43:43 -03:00
{"*", menu_auto},
{"test", menu_test},
};
MENU(top, "menu", top_menu_commands);
void
setup(void)
{
2012-11-12 17:12:40 -04:00
hal.console->println_P(PSTR("AP_Menu unit test"));
2011-10-28 15:43:43 -03:00
top.run();
}
void
loop(void)
{
hal.console->printf("not reached\n");
}
2012-11-12 17:12:40 -04:00
AP_HAL_MAIN();