ardupilot/libraries/AP_HAL/GPIO.h

53 lines
1.4 KiB
C
Raw Normal View History

#ifndef __AP_HAL_GPIO_H__
#define __AP_HAL_GPIO_H__
#include <stdint.h>
#include "AP_HAL_Namespace.h"
#define HAL_GPIO_INPUT 0
#define HAL_GPIO_OUTPUT 1
2015-08-17 22:18:21 -03:00
#define HAL_GPIO_ALT 2
#define HAL_GPIO_INTERRUPT_LOW 0
#define HAL_GPIO_INTERRUPT_HIGH 1
#define HAL_GPIO_INTERRUPT_FALLING 2
#define HAL_GPIO_INTERRUPT_RISING 3
class AP_HAL::DigitalSource {
public:
virtual void mode(uint8_t output) = 0;
virtual uint8_t read() = 0;
2013-08-08 10:14:06 -03:00
virtual void write(uint8_t value) = 0;
virtual void toggle() = 0;
};
class AP_HAL::GPIO {
public:
GPIO() {}
virtual void init() = 0;
virtual void pinMode(uint8_t pin, uint8_t output) = 0;
// optional interface on some boards
virtual void pinMode(uint8_t pin, uint8_t output, uint8_t alt) {};
virtual uint8_t read(uint8_t pin) = 0;
virtual void write(uint8_t pin, uint8_t value) = 0;
2013-08-08 10:14:06 -03:00
virtual void toggle(uint8_t pin) = 0;
virtual void setPWMPeriod(uint8_t pin, uint32_t time_us) {};
virtual void setPWMDuty(uint8_t pin, uint8_t percent) {};
virtual int8_t analogPinToDigitalPin(uint8_t pin) = 0;
/* Alternative interface: */
2012-12-06 14:45:45 -04:00
virtual AP_HAL::DigitalSource* channel(uint16_t n) = 0;
/* Interrupt interface: */
2012-12-06 14:45:45 -04:00
virtual bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
uint8_t mode) = 0;
/* return true if USB cable is connected */
virtual bool usb_connected(void) = 0;
};
#endif // __AP_HAL_GPIO_H__