GPIO.cpp 1.8 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  1. #include "GPIO.h"
  2. using namespace HALSITL;
  3. extern const AP_HAL::HAL& hal;
  4. #define SITL_WOW_ALTITUDE 0.01
  5. void GPIO::init()
  6. {}
  7. void GPIO::pinMode(uint8_t pin, uint8_t output)
  8. {}
  9. uint8_t GPIO::read(uint8_t pin)
  10. {
  11. if (!_sitlState->_sitl) {
  12. return 0;
  13. }
  14. // weight on wheels pin support
  15. if (pin == _sitlState->_sitl->wow_pin.get()) {
  16. return _sitlState->_sitl->state.altitude < SITL_WOW_ALTITUDE ? 1 : 0;
  17. }
  18. uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
  19. return static_cast<uint16_t>((mask & (1U << pin)) ? 1 : 0);
  20. }
  21. void GPIO::write(uint8_t pin, uint8_t value)
  22. {
  23. if (!_sitlState->_sitl) {
  24. return;
  25. }
  26. uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
  27. uint16_t new_mask = mask;
  28. if (pin == _sitlState->_sitl->wow_pin.get()) {
  29. return;
  30. }
  31. if (value) {
  32. new_mask |= (1U << pin);
  33. } else {
  34. new_mask &= ~(1U << pin);
  35. }
  36. if (mask != new_mask) {
  37. _sitlState->_sitl->pin_mask.set_and_notify(new_mask);
  38. }
  39. }
  40. void GPIO::toggle(uint8_t pin)
  41. {
  42. write(pin, !read(pin));
  43. }
  44. /* Alternative interface: */
  45. AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
  46. if (n < 16) { // (ie. sizeof(pin_mask)*8)
  47. return new DigitalSource(static_cast<uint8_t>(n));
  48. } else {
  49. return nullptr;
  50. }
  51. }
  52. bool GPIO::usb_connected(void)
  53. {
  54. return false;
  55. }
  56. DigitalSource::DigitalSource(uint8_t pin) :
  57. _pin(pin)
  58. {}
  59. void DigitalSource::mode(uint8_t output)
  60. {}
  61. uint8_t DigitalSource::read()
  62. {
  63. return hal.gpio->read(_pin);
  64. }
  65. void DigitalSource::write(uint8_t value)
  66. {
  67. value = static_cast<uint8_t>(value ? 1 : 0);
  68. return hal.gpio->write(_pin, value);
  69. }
  70. void DigitalSource::toggle()
  71. {
  72. return hal.gpio->write(_pin, !hal.gpio->read(_pin));
  73. }