APM:Libraries
GPIO.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_SITL.h"
4 
5 class HALSITL::GPIO : public AP_HAL::GPIO {
6 public:
7  explicit GPIO(SITL_State *sitlState): _sitlState(sitlState) {}
8  void init();
9  void pinMode(uint8_t pin, uint8_t output);
10  int8_t analogPinToDigitalPin(uint8_t pin);
11  uint8_t read(uint8_t pin);
12  void write(uint8_t pin, uint8_t value);
13  void toggle(uint8_t pin);
14 
15  /* Alternative interface: */
16  AP_HAL::DigitalSource* channel(uint16_t n);
17 
18  /* Interrupt interface: */
19  bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
20  uint8_t mode);
21 
22  /* return true if USB cable is connected */
23  bool usb_connected(void);
24 
25 private:
27 };
28 
30 public:
31  explicit DigitalSource(uint8_t pin);
32  void mode(uint8_t output);
33  uint8_t read();
34  void write(uint8_t value);
35  void toggle();
36 
37 private:
38  uint8_t _pin;
39 };
int8_t analogPinToDigitalPin(uint8_t pin)
SITL_State * _sitlState
Definition: GPIO.h:26
void(* Proc)(void)
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
void write(uint8_t pin, uint8_t value)
bool usb_connected(void)
void pinMode(uint8_t pin, uint8_t output)
uint8_t read(uint8_t pin)
void toggle(uint8_t pin)
AP_HAL::DigitalSource * channel(uint16_t n)
GPIO(SITL_State *sitlState)
Definition: GPIO.h:7
static SITL_State sitlState
float value
static int8_t pin
Definition: AnalogIn.cpp:15