12 #define MENU_FUNC(func) FUNCTOR_BIND(&commands, &MenuCommands::func, int8_t, uint8_t, const Menu::arg *) 18 fprintf(stderr,
"Input and output commands take only one argument, which is the GPIO pin number\n");
22 long int pin = argv[1].
i;
24 fprintf(stderr,
"Invalid pin number: %ld\n", pin);
35 if (pin <= 0)
return -1;
44 hal.
console->
printf(
"Ok, I'll start reading pin number %d and printing the value read on intervals of 1 second.", pin);
56 if (pin <= 0)
return -1;
65 hal.
console->
printf(
"Now I'll start toggling the signal on the pin number %d on intervals of 1 second." 66 " It's recommended to verify that the signal is reaching it (e.g. by using a LED)\n", pin);
111 MENU(main_menu,
"GPIOTest: Please select one of the operations followed by the GPIO pin number", test_menu_commands);
MENU(main_menu, "GPIOTest: Please select one of the operations followed by the GPIO pin number", test_menu_commands)
virtual void set_blocking_writes(bool blocking)=0
int parse_gpio_pin_number(uint8_t argc, const Menu::arg *argv)
AP_HAL::UARTDriver * console
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
int8_t gpio_output_channel(uint8_t argc, const Menu::arg *argv)
static int8_t test_gpio_input(uint8_t argc, const Menu::arg *argv, bool use_channel)
virtual void write(uint8_t pin, uint8_t value)=0
virtual void mode(uint8_t output)=0
int8_t gpio_output(uint8_t argc, const Menu::arg *argv)
virtual void printf(const char *,...) FMT_PRINTF(2
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
int8_t gpio_input_channel(uint8_t argc, const Menu::arg *argv)
virtual void pinMode(uint8_t pin, uint8_t output)=0
Common definitions and utility routines for the ArduPilot libraries.
virtual uint8_t read(uint8_t pin)=0
int8_t gpio_input(uint8_t argc, const Menu::arg *argv)
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
static int8_t test_gpio_output(uint8_t argc, const Menu::arg *argv, bool use_channel)
const struct Menu::command test_menu_commands[]
virtual void write(uint8_t value)=0