2016-07-21 21:58:02 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "AP_HAL_SITL.h"
|
|
|
|
|
|
|
|
class HALSITL::GPIO : public AP_HAL::GPIO {
|
|
|
|
public:
|
2017-01-09 08:25:29 -04:00
|
|
|
explicit GPIO(SITL_State *sitlState): _sitlState(sitlState) {}
|
2019-02-21 19:06:59 -04:00
|
|
|
void init() override;
|
|
|
|
void pinMode(uint8_t pin, uint8_t output) override;
|
|
|
|
uint8_t read(uint8_t pin) override;
|
|
|
|
void write(uint8_t pin, uint8_t value) override;
|
|
|
|
void toggle(uint8_t pin) override;
|
2016-07-21 21:58:02 -03:00
|
|
|
|
|
|
|
/* Alternative interface: */
|
2019-02-21 19:06:59 -04:00
|
|
|
AP_HAL::DigitalSource* channel(uint16_t n) override;
|
2016-07-21 21:58:02 -03:00
|
|
|
|
|
|
|
/* return true if USB cable is connected */
|
2019-02-21 19:06:59 -04:00
|
|
|
bool usb_connected(void) override;
|
2016-07-21 21:58:02 -03:00
|
|
|
|
|
|
|
private:
|
2017-01-09 08:25:29 -04:00
|
|
|
SITL_State *_sitlState;
|
2016-07-21 21:58:02 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
class HALSITL::DigitalSource : public AP_HAL::DigitalSource {
|
|
|
|
public:
|
2017-01-09 08:25:29 -04:00
|
|
|
explicit DigitalSource(uint8_t pin);
|
2019-02-21 19:06:59 -04:00
|
|
|
void mode(uint8_t output) override;
|
|
|
|
uint8_t read() override;
|
|
|
|
void write(uint8_t value) override;
|
|
|
|
void toggle() override;
|
2016-07-21 21:58:02 -03:00
|
|
|
|
|
|
|
private:
|
2017-01-09 08:25:29 -04:00
|
|
|
uint8_t _pin;
|
2016-07-21 21:58:02 -03:00
|
|
|
};
|