2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2014-09-18 10:35:22 -03:00
|
|
|
|
2014-11-05 09:56:12 -04:00
|
|
|
#include <stdint.h>
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_Linux.h"
|
2024-05-09 09:56:42 -03:00
|
|
|
#include "GPIO_RPI_HAL.h"
|
2014-09-18 10:35:22 -03:00
|
|
|
|
2020-03-09 19:43:10 -03:00
|
|
|
/**
|
|
|
|
* @brief Check for valid Raspberry Pi pin range
|
|
|
|
*
|
|
|
|
* @tparam pin
|
|
|
|
* @return uint8_t
|
|
|
|
*/
|
|
|
|
template <uint8_t pin> constexpr uint8_t RPI_GPIO_()
|
|
|
|
{
|
|
|
|
static_assert(pin > 1 && pin < 32, "Invalid pin value.");
|
|
|
|
return pin;
|
|
|
|
}
|
2014-09-18 10:35:22 -03:00
|
|
|
|
2024-05-09 09:56:42 -03:00
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
namespace Linux {
|
|
|
|
|
2020-03-24 17:09:18 -03:00
|
|
|
/**
|
|
|
|
* @brief Class for Raspberry PI GPIO control
|
|
|
|
*
|
|
|
|
*/
|
2016-07-29 16:14:02 -03:00
|
|
|
class GPIO_RPI : public AP_HAL::GPIO {
|
2014-09-18 10:35:22 -03:00
|
|
|
public:
|
2015-10-20 18:13:25 -03:00
|
|
|
GPIO_RPI();
|
2019-08-15 01:02:02 -03:00
|
|
|
void init() override;
|
|
|
|
void pinMode(uint8_t pin, uint8_t output) override;
|
|
|
|
void pinMode(uint8_t pin, uint8_t output, uint8_t alt) override;
|
|
|
|
uint8_t read(uint8_t pin) override;
|
|
|
|
void write(uint8_t pin, uint8_t value) override;
|
|
|
|
void toggle(uint8_t pin) override;
|
2014-09-18 10:35:22 -03:00
|
|
|
|
|
|
|
/* Alternative interface: */
|
2019-08-15 01:02:02 -03:00
|
|
|
AP_HAL::DigitalSource* channel(uint16_t n) override;
|
2014-09-18 10:35:22 -03:00
|
|
|
|
|
|
|
/* return true if USB cable is connected */
|
2019-08-15 01:02:02 -03:00
|
|
|
bool usb_connected(void) override;
|
2016-06-20 11:10:59 -03:00
|
|
|
|
|
|
|
private:
|
2024-05-09 09:56:42 -03:00
|
|
|
GPIO_RPI_HAL* gpioDriver;
|
2014-09-18 10:35:22 -03:00
|
|
|
};
|
2016-07-29 16:14:02 -03:00
|
|
|
|
|
|
|
}
|