APM:Libraries
GPIO.cpp
Go to the documentation of this file.
1 
2 #include "GPIO.h"
3 
4 using namespace HALSITL;
5 
6 extern const AP_HAL::HAL& hal;
7 
8 void GPIO::init()
9 {}
10 
11 void GPIO::pinMode(uint8_t pin, uint8_t output)
12 {}
13 
14 int8_t GPIO::analogPinToDigitalPin(uint8_t pin)
15 {
16  return pin;
17 }
18 
19 uint8_t GPIO::read(uint8_t pin)
20 {
21  if (!_sitlState->_sitl) {
22  return 0;
23  }
24  uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
25  return static_cast<uint16_t>((mask & (1U << pin)) ? 1 : 0);
26 }
27 
28 void GPIO::write(uint8_t pin, uint8_t value)
29 {
30  if (!_sitlState->_sitl) {
31  return;
32  }
33  uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
34  uint16_t new_mask = mask;
35  if (value) {
36  new_mask |= (1U << pin);
37  } else {
38  new_mask &= ~(1U << pin);
39  }
40  if (mask != new_mask) {
41  _sitlState->_sitl->pin_mask.set_and_notify(new_mask);
42  }
43 }
44 
45 void GPIO::toggle(uint8_t pin)
46 {
47  write(pin, !read(pin));
48 }
49 
50 /* Alternative interface: */
52  if (n < 16) { // (ie. sizeof(pin_mask)*8)
53  return new DigitalSource(static_cast<uint8_t>(n));
54  } else {
55  return nullptr;
56  }
57 
58 }
59 
60 /* Interrupt interface: */
61 bool GPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
62  uint8_t mode) {
63  return true;
64 }
65 
66 bool GPIO::usb_connected(void)
67 {
68  return false;
69 }
70 
72  _pin(pin)
73 {}
74 
75 void DigitalSource::mode(uint8_t output)
76 {}
77 
78 uint8_t DigitalSource::read()
79 {
80  return hal.gpio->read(_pin);
81 }
82 
83 void DigitalSource::write(uint8_t value)
84 {
85  value = static_cast<uint8_t>(value ? 1 : 0);
86  return hal.gpio->write(_pin, value);
87 }
88 
90 {
91  return hal.gpio->write(_pin, !hal.gpio->read(_pin));
92 }
int8_t analogPinToDigitalPin(uint8_t pin)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
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)
virtual void write(uint8_t pin, uint8_t value)=0
bool usb_connected(void)
AP_Int16 pin_mask
Definition: SITL.h:140
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)
virtual uint8_t read(uint8_t pin)=0
AP_HAL::GPIO * gpio
Definition: HAL.h:111
SITL::SITL * _sitl
Definition: SITL_State.h:165
float value
void mode(uint8_t output)
DigitalSource(uint8_t pin)
Definition: GPIO.cpp:71
static int8_t pin
Definition: AnalogIn.cpp:15
void write(uint8_t value)