APM:Libraries
GPIOTest.cpp
Go to the documentation of this file.
1 #include <stdio.h>
2 #include <unistd.h>
3 
4 #include <AP_Common/AP_Common.h>
6 #include <AP_Menu/AP_Menu.h>
7 
8 void setup();
9 void loop();
10 int parse_gpio_pin_number(uint8_t argc, const Menu::arg *argv);
11 
12 #define MENU_FUNC(func) FUNCTOR_BIND(&commands, &MenuCommands::func, int8_t, uint8_t, const Menu::arg *)
13 
15 
16 int parse_gpio_pin_number(uint8_t argc, const Menu::arg *argv) {
17  if (argc != 2) {
18  fprintf(stderr, "Input and output commands take only one argument, which is the GPIO pin number\n");
19  return -1;
20  }
21 
22  long int pin = argv[1].i;
23  if (pin <= 0) {
24  fprintf(stderr, "Invalid pin number: %ld\n", pin);
25  return -1;
26  }
27 
28  return pin;
29 }
30 
31 static int8_t test_gpio_input(uint8_t argc, const Menu::arg *argv, bool use_channel) {
32  AP_HAL::DigitalSource *ch = nullptr;
33  int pin = parse_gpio_pin_number(argc, argv);
34 
35  if (pin <= 0) return -1;
36 
37  if (use_channel) {
38  ch = hal.gpio->channel(pin);
39  ch->mode(HAL_GPIO_INPUT);
40  } else {
41  hal.gpio->pinMode(pin, HAL_GPIO_INPUT);
42  }
43 
44  hal.console->printf("Ok, I'll start reading pin number %d and printing the value read on intervals of 1 second.", pin);
45  while (1) {
46  hal.console->printf("%u ", use_channel ? ch->read() : hal.gpio->read(pin));
47  sleep(1);
48  }
49  return 0;
50 }
51 
52 static int8_t test_gpio_output(uint8_t argc, const Menu::arg *argv, bool use_channel) {
53  AP_HAL::DigitalSource *ch = nullptr;
54  int pin = parse_gpio_pin_number(argc, argv);
55 
56  if (pin <= 0) return -1;
57 
58  if (use_channel) {
59  ch = hal.gpio->channel(pin);
60  ch->mode(HAL_GPIO_OUTPUT);
61  } else {
62  hal.gpio->pinMode(pin, HAL_GPIO_OUTPUT);
63  }
64 
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);
67  uint8_t signal = 0;
68  while (1) {
69  signal ^= 1;
70  if (use_channel) {
71  ch->write(signal);
72  } else {
73  hal.gpio->write(pin, signal);
74  }
75  sleep(1);
76  }
77  return 0;
78 }
79 
80 class MenuCommands {
81 public:
82  int8_t gpio_input(uint8_t argc, const Menu::arg *argv) {
83  return ::test_gpio_input(argc, argv, false);
84  }
85 
86  int8_t gpio_output(uint8_t argc, const Menu::arg *argv) {
87  return ::test_gpio_output(argc, argv, false);
88  }
89 
90  int8_t gpio_input_channel(uint8_t argc, const Menu::arg *argv) {
91  hal.console->printf("GPIO Input using digital source\n");
92  return test_gpio_input(argc, argv, true);
93  }
94 
95  int8_t gpio_output_channel(uint8_t argc, const Menu::arg *argv) {
96  hal.console->printf("GPIO Output using digital source\n");
97  return test_gpio_output(argc, argv, true);
98  }
99 
100 };
101 
103 
105  {"input", MENU_FUNC(gpio_input)},
106  {"output", MENU_FUNC(gpio_output)},
107  {"input_ch", MENU_FUNC(gpio_input_channel)},
108  {"output_ch", MENU_FUNC(gpio_output_channel)}
109 };
110 
111 MENU(main_menu, "GPIOTest: Please select one of the operations followed by the GPIO pin number", test_menu_commands);
112 
113 void setup(void)
114 {
115  Menu::set_port(hal.console);
116  hal.console->set_blocking_writes(true);
117 
118  while (1) {
119  main_menu.run();
120  }
121 }
122 
123 void loop(void)
124 {
125 }
126 
127 AP_HAL_MAIN();
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
void setup()
Definition: GPIOTest.cpp:113
int parse_gpio_pin_number(uint8_t argc, const Menu::arg *argv)
Definition: GPIOTest.cpp:16
AP_HAL::UARTDriver * console
Definition: HAL.h:110
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: GPIOTest.cpp:14
int8_t gpio_output_channel(uint8_t argc, const Menu::arg *argv)
Definition: GPIOTest.cpp:95
void loop()
Definition: GPIOTest.cpp:123
static int8_t test_gpio_input(uint8_t argc, const Menu::arg *argv, bool use_channel)
Definition: GPIOTest.cpp:31
MenuCommands commands
Definition: GPIOTest.cpp:102
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)
Definition: GPIOTest.cpp:86
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
int8_t gpio_input_channel(uint8_t argc, const Menu::arg *argv)
Definition: GPIOTest.cpp:90
virtual void pinMode(uint8_t pin, uint8_t output)=0
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
const HAL & get_HAL()
#define HAL_GPIO_INPUT
Definition: GPIO.h:7
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)
Definition: GPIOTest.cpp:82
virtual uint8_t read()=0
AP_HAL::GPIO * gpio
Definition: HAL.h:111
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
static void set_port(AP_HAL::BetterStream *port)
Definition: AP_Menu.h:56
AP_HAL_MAIN()
static int8_t test_gpio_output(uint8_t argc, const Menu::arg *argv, bool use_channel)
Definition: GPIOTest.cpp:52
long i
integer form of the argument (if a number)
Definition: AP_Menu.h:36
static int8_t pin
Definition: AnalogIn.cpp:15
const struct Menu::command test_menu_commands[]
Definition: GPIOTest.cpp:104
virtual void write(uint8_t value)=0
#define MENU_FUNC(func)
Definition: GPIOTest.cpp:12