mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_HAL: add toggle to GPIO
This commit is contained in:
parent
b1278fa006
commit
ac36a09747
@ -17,7 +17,8 @@ class AP_HAL::DigitalSource {
|
|||||||
public:
|
public:
|
||||||
virtual void mode(uint8_t output) = 0;
|
virtual void mode(uint8_t output) = 0;
|
||||||
virtual uint8_t read() = 0;
|
virtual uint8_t read() = 0;
|
||||||
virtual void write(uint8_t value) = 0;
|
virtual void write(uint8_t value) = 0;
|
||||||
|
virtual void toggle() = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
class AP_HAL::GPIO {
|
class AP_HAL::GPIO {
|
||||||
@ -27,6 +28,7 @@ public:
|
|||||||
virtual void pinMode(uint8_t pin, uint8_t output) = 0;
|
virtual void pinMode(uint8_t pin, uint8_t output) = 0;
|
||||||
virtual uint8_t read(uint8_t pin) = 0;
|
virtual uint8_t read(uint8_t pin) = 0;
|
||||||
virtual void write(uint8_t pin, uint8_t value) = 0;
|
virtual void write(uint8_t pin, uint8_t value) = 0;
|
||||||
|
virtual void toggle(uint8_t pin) = 0;
|
||||||
virtual int8_t analogPinToDigitalPin(uint8_t pin) = 0;
|
virtual int8_t analogPinToDigitalPin(uint8_t pin) = 0;
|
||||||
|
|
||||||
/* Alternative interface: */
|
/* Alternative interface: */
|
||||||
|
@ -97,6 +97,23 @@ void AVRGPIO::write(uint8_t pin, uint8_t value) {
|
|||||||
SREG = oldSREG;
|
SREG = oldSREG;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AVRGPIO::toggle(uint8_t pin) {
|
||||||
|
uint8_t bit = digitalPinToBitMask(pin);
|
||||||
|
uint8_t port = digitalPinToPort(pin);
|
||||||
|
volatile uint8_t *out;
|
||||||
|
|
||||||
|
if (port == NOT_A_PIN) return;
|
||||||
|
|
||||||
|
out = portOutputRegister(port);
|
||||||
|
|
||||||
|
uint8_t oldSREG = SREG;
|
||||||
|
cli();
|
||||||
|
|
||||||
|
*out ^= bit;
|
||||||
|
|
||||||
|
SREG = oldSREG;
|
||||||
|
}
|
||||||
|
|
||||||
/* Implement GPIO Interrupt 6, used for MPU6000 data ready on APM2. */
|
/* Implement GPIO Interrupt 6, used for MPU6000 data ready on APM2. */
|
||||||
bool AVRGPIO::attach_interrupt(
|
bool AVRGPIO::attach_interrupt(
|
||||||
uint8_t interrupt_num, AP_HAL::Proc proc, uint8_t mode) {
|
uint8_t interrupt_num, AP_HAL::Proc proc, uint8_t mode) {
|
||||||
@ -171,5 +188,19 @@ void AVRDigitalSource::write(uint8_t value) {
|
|||||||
SREG = oldSREG;
|
SREG = oldSREG;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AVRDigitalSource::toggle() {
|
||||||
|
const uint8_t bit = _bit;
|
||||||
|
const uint8_t port = _port;
|
||||||
|
volatile uint8_t* out;
|
||||||
|
out = portOutputRegister(port);
|
||||||
|
|
||||||
|
uint8_t oldSREG = SREG;
|
||||||
|
cli();
|
||||||
|
|
||||||
|
*out ^= bit;
|
||||||
|
|
||||||
|
SREG = oldSREG;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -5,12 +5,27 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include "AP_HAL_AVR_Namespace.h"
|
#include "AP_HAL_AVR_Namespace.h"
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
|
# define HAL_GPIO_A_LED_PIN 37
|
||||||
|
# define HAL_GPIO_B_LED_PIN 36
|
||||||
|
# define HAL_GPIO_C_LED_PIN 35
|
||||||
|
# define HAL_GPIO_LED_ON HIGH
|
||||||
|
# define HAL_GPIO_LED_OFF LOW
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
# define HAL_GPIO_A_LED_PIN 27
|
||||||
|
# define HAL_GPIO_B_LED_PIN 26
|
||||||
|
# define HAL_GPIO_C_LED_PIN 25
|
||||||
|
# define HAL_GPIO_LED_ON LOW
|
||||||
|
# define HAL_GPIO_LED_OFF HIGH
|
||||||
|
#endif
|
||||||
|
|
||||||
class AP_HAL_AVR::AVRDigitalSource : public AP_HAL::DigitalSource {
|
class AP_HAL_AVR::AVRDigitalSource : public AP_HAL::DigitalSource {
|
||||||
public:
|
public:
|
||||||
AVRDigitalSource(uint8_t bit, uint8_t port) : _bit(bit), _port(port) {}
|
AVRDigitalSource(uint8_t bit, uint8_t port) : _bit(bit), _port(port) {}
|
||||||
void mode(uint8_t output);
|
void mode(uint8_t output);
|
||||||
uint8_t read();
|
uint8_t read();
|
||||||
void write(uint8_t value);
|
void write(uint8_t value);
|
||||||
|
void toggle();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const uint8_t _bit;
|
const uint8_t _bit;
|
||||||
@ -25,6 +40,7 @@ public:
|
|||||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
int8_t analogPinToDigitalPin(uint8_t pin);
|
||||||
uint8_t read(uint8_t pin);
|
uint8_t read(uint8_t pin);
|
||||||
void write(uint8_t pin, uint8_t value);
|
void write(uint8_t pin, uint8_t value);
|
||||||
|
void toggle(uint8_t pin);
|
||||||
AP_HAL::DigitalSource* channel(uint16_t);
|
AP_HAL::DigitalSource* channel(uint16_t);
|
||||||
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc proc,
|
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc proc,
|
||||||
uint8_t mode);
|
uint8_t mode);
|
||||||
|
@ -1,54 +1,60 @@
|
|||||||
|
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
|
||||||
using namespace Empty;
|
using namespace Empty;
|
||||||
|
|
||||||
EmptyGPIO::EmptyGPIO()
|
EmptyGPIO::EmptyGPIO()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void EmptyGPIO::init()
|
void EmptyGPIO::init()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void EmptyGPIO::pinMode(uint8_t pin, uint8_t output)
|
void EmptyGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
int8_t EmptyGPIO::analogPinToDigitalPin(uint8_t pin)
|
int8_t EmptyGPIO::analogPinToDigitalPin(uint8_t pin)
|
||||||
{
|
{
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
uint8_t EmptyGPIO::read(uint8_t pin) {
|
uint8_t EmptyGPIO::read(uint8_t pin) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void EmptyGPIO::write(uint8_t pin, uint8_t value)
|
void EmptyGPIO::write(uint8_t pin, uint8_t value)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
/* Alternative interface: */
|
void EmptyGPIO::toggle(uint8_t pin)
|
||||||
AP_HAL::DigitalSource* EmptyGPIO::channel(uint16_t n) {
|
{}
|
||||||
return new EmptyDigitalSource(0);
|
|
||||||
}
|
/* Alternative interface: */
|
||||||
|
AP_HAL::DigitalSource* EmptyGPIO::channel(uint16_t n) {
|
||||||
/* Interrupt interface: */
|
return new EmptyDigitalSource(0);
|
||||||
bool EmptyGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
|
}
|
||||||
uint8_t mode) {
|
|
||||||
return true;
|
/* Interrupt interface: */
|
||||||
}
|
bool EmptyGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
|
||||||
|
uint8_t mode) {
|
||||||
|
return true;
|
||||||
EmptyDigitalSource::EmptyDigitalSource(uint8_t v) :
|
}
|
||||||
_v(v)
|
|
||||||
{}
|
|
||||||
|
EmptyDigitalSource::EmptyDigitalSource(uint8_t v) :
|
||||||
void EmptyDigitalSource::mode(uint8_t output)
|
_v(v)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
uint8_t EmptyDigitalSource::read() {
|
void EmptyDigitalSource::mode(uint8_t output)
|
||||||
return _v;
|
{}
|
||||||
}
|
|
||||||
|
uint8_t EmptyDigitalSource::read() {
|
||||||
void EmptyDigitalSource::write(uint8_t value) {
|
return _v;
|
||||||
_v = value;
|
}
|
||||||
}
|
|
||||||
|
void EmptyDigitalSource::write(uint8_t value) {
|
||||||
|
_v = value;
|
||||||
|
}
|
||||||
|
|
||||||
|
void EmptyDigitalSource::toggle() {
|
||||||
|
_v = !_v;
|
||||||
|
}
|
||||||
|
@ -1,35 +1,37 @@
|
|||||||
|
|
||||||
#ifndef __AP_HAL_EMPTY_GPIO_H__
|
#ifndef __AP_HAL_EMPTY_GPIO_H__
|
||||||
#define __AP_HAL_EMPTY_GPIO_H__
|
#define __AP_HAL_EMPTY_GPIO_H__
|
||||||
|
|
||||||
#include <AP_HAL_Empty.h>
|
#include <AP_HAL_Empty.h>
|
||||||
|
|
||||||
class Empty::EmptyGPIO : public AP_HAL::GPIO {
|
class Empty::EmptyGPIO : public AP_HAL::GPIO {
|
||||||
public:
|
public:
|
||||||
EmptyGPIO();
|
EmptyGPIO();
|
||||||
void init();
|
void init();
|
||||||
void pinMode(uint8_t pin, uint8_t output);
|
void pinMode(uint8_t pin, uint8_t output);
|
||||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
int8_t analogPinToDigitalPin(uint8_t pin);
|
||||||
uint8_t read(uint8_t pin);
|
uint8_t read(uint8_t pin);
|
||||||
void write(uint8_t pin, uint8_t value);
|
void write(uint8_t pin, uint8_t value);
|
||||||
|
void toggle(uint8_t pin);
|
||||||
/* Alternative interface: */
|
|
||||||
AP_HAL::DigitalSource* channel(uint16_t n);
|
/* Alternative interface: */
|
||||||
|
AP_HAL::DigitalSource* channel(uint16_t n);
|
||||||
/* Interrupt interface: */
|
|
||||||
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
|
/* Interrupt interface: */
|
||||||
uint8_t mode);
|
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
|
||||||
|
uint8_t mode);
|
||||||
};
|
|
||||||
|
};
|
||||||
class Empty::EmptyDigitalSource : public AP_HAL::DigitalSource {
|
|
||||||
public:
|
class Empty::EmptyDigitalSource : public AP_HAL::DigitalSource {
|
||||||
EmptyDigitalSource(uint8_t v);
|
public:
|
||||||
void mode(uint8_t output);
|
EmptyDigitalSource(uint8_t v);
|
||||||
uint8_t read();
|
void mode(uint8_t output);
|
||||||
void write(uint8_t value);
|
uint8_t read();
|
||||||
private:
|
void write(uint8_t value);
|
||||||
uint8_t _v;
|
void toggle();
|
||||||
};
|
private:
|
||||||
|
uint8_t _v;
|
||||||
#endif // __AP_HAL_EMPTY_GPIO_H__
|
};
|
||||||
|
|
||||||
|
#endif // __AP_HAL_EMPTY_GPIO_H__
|
||||||
|
@ -120,7 +120,7 @@ void PX4GPIO::write(uint8_t pin, uint8_t value)
|
|||||||
switch (pin) {
|
switch (pin) {
|
||||||
|
|
||||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
|
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
|
||||||
case A_LED_PIN: // Arming LED
|
case HAL_GPIO_A_LED_PIN: // Arming LED
|
||||||
if (value == LOW) {
|
if (value == LOW) {
|
||||||
ioctl(_led_fd, LED_OFF, LED_RED);
|
ioctl(_led_fd, LED_OFF, LED_RED);
|
||||||
} else {
|
} else {
|
||||||
@ -128,10 +128,10 @@ void PX4GPIO::write(uint8_t pin, uint8_t value)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case B_LED_PIN: // not used yet
|
case HAL_GPIO_B_LED_PIN: // not used yet
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case C_LED_PIN: // GPS LED
|
case HAL_GPIO_C_LED_PIN: // GPS LED
|
||||||
if (value == LOW) {
|
if (value == LOW) {
|
||||||
ioctl(_led_fd, LED_OFF, LED_BLUE);
|
ioctl(_led_fd, LED_OFF, LED_BLUE);
|
||||||
} else {
|
} else {
|
||||||
@ -187,6 +187,35 @@ void PX4GPIO::write(uint8_t pin, uint8_t value)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PX4GPIO::toggle(uint8_t pin)
|
||||||
|
{
|
||||||
|
switch (pin) {
|
||||||
|
|
||||||
|
case HAL_GPIO_A_LED_PIN: // Arming LED
|
||||||
|
ioctl(_led_fd, LED_OFF, LED_RED);
|
||||||
|
ioctl(_led_fd, LED_ON, LED_RED);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case HAL_GPIO_B_LED_PIN: // not used yet
|
||||||
|
break;
|
||||||
|
|
||||||
|
case HAL_GPIO_C_LED_PIN: // GPS LED
|
||||||
|
ioctl(_led_fd, LED_OFF, LED_BLUE);
|
||||||
|
ioctl(_led_fd, LED_ON, LED_BLUE);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case PX4_GPIO_PIEZO_PIN: // Piezo beeper
|
||||||
|
ioctl(_tone_alarm_fd, TONE_SET_ALARM, 3); // Alarm on !!
|
||||||
|
ioctl(_tone_alarm_fd, TONE_SET_ALARM, 0); // Alarm off !!
|
||||||
|
break;
|
||||||
|
|
||||||
|
case PX4_GPIO_EXT_RELAY_PIN: // Ext Relay
|
||||||
|
ioctl(_gpio_fd, GPIO_CLEAR, GPIO_EXT_1);
|
||||||
|
ioctl(_gpio_fd, GPIO_SET, GPIO_EXT_1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/* Alternative interface: */
|
/* Alternative interface: */
|
||||||
AP_HAL::DigitalSource* PX4GPIO::channel(uint16_t n) {
|
AP_HAL::DigitalSource* PX4GPIO::channel(uint16_t n) {
|
||||||
return new PX4DigitalSource(0);
|
return new PX4DigitalSource(0);
|
||||||
@ -214,4 +243,8 @@ void PX4DigitalSource::write(uint8_t value) {
|
|||||||
_v = value;
|
_v = value;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PX4DigitalSource::toggle() {
|
||||||
|
_v = !_v;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
@ -13,6 +13,14 @@
|
|||||||
#define PX4_GPIO_EXT_IO_ACC1_PIN 115
|
#define PX4_GPIO_EXT_IO_ACC1_PIN 115
|
||||||
#define PX4_GPIO_EXT_IO_ACC2_PIN 116
|
#define PX4_GPIO_EXT_IO_ACC2_PIN 116
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
|
# define HAL_GPIO_A_LED_PIN 27
|
||||||
|
# define HAL_GPIO_B_LED_PIN 26
|
||||||
|
# define HAL_GPIO_C_LED_PIN 25
|
||||||
|
# define HAL_GPIO_LED_ON LOW
|
||||||
|
# define HAL_GPIO_LED_OFF HIGH
|
||||||
|
#endif
|
||||||
|
|
||||||
class PX4::PX4GPIO : public AP_HAL::GPIO {
|
class PX4::PX4GPIO : public AP_HAL::GPIO {
|
||||||
public:
|
public:
|
||||||
PX4GPIO();
|
PX4GPIO();
|
||||||
@ -21,6 +29,7 @@ public:
|
|||||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
int8_t analogPinToDigitalPin(uint8_t pin);
|
||||||
uint8_t read(uint8_t pin);
|
uint8_t read(uint8_t pin);
|
||||||
void write(uint8_t pin, uint8_t value);
|
void write(uint8_t pin, uint8_t value);
|
||||||
|
void toggle(uint8_t pin);
|
||||||
|
|
||||||
/* Alternative interface: */
|
/* Alternative interface: */
|
||||||
AP_HAL::DigitalSource* channel(uint16_t n);
|
AP_HAL::DigitalSource* channel(uint16_t n);
|
||||||
@ -40,7 +49,8 @@ public:
|
|||||||
PX4DigitalSource(uint8_t v);
|
PX4DigitalSource(uint8_t v);
|
||||||
void mode(uint8_t output);
|
void mode(uint8_t output);
|
||||||
uint8_t read();
|
uint8_t read();
|
||||||
void write(uint8_t value);
|
void write(uint8_t value);
|
||||||
|
void toggle();
|
||||||
private:
|
private:
|
||||||
uint8_t _v;
|
uint8_t _v;
|
||||||
};
|
};
|
||||||
|
@ -1,62 +1,71 @@
|
|||||||
|
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
|
|
||||||
using namespace SMACCM;
|
using namespace SMACCM;
|
||||||
|
|
||||||
SMACCMGPIO::SMACCMGPIO()
|
SMACCMGPIO::SMACCMGPIO()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void SMACCMGPIO::init()
|
void SMACCMGPIO::init()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void SMACCMGPIO::pinMode(uint8_t pin, uint8_t output)
|
void SMACCMGPIO::pinMode(uint8_t pin, uint8_t output)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
int8_t SMACCMGPIO::analogPinToDigitalPin(uint8_t pin)
|
int8_t SMACCMGPIO::analogPinToDigitalPin(uint8_t pin)
|
||||||
{
|
{
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t SMACCMGPIO::read(uint8_t pin)
|
uint8_t SMACCMGPIO::read(uint8_t pin)
|
||||||
{
|
{
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void SMACCMGPIO::write(uint8_t pin, uint8_t value)
|
void SMACCMGPIO::write(uint8_t pin, uint8_t value)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Alternative interface: */
|
void SMACCMGPIO::toggle(uint8_t pin)
|
||||||
AP_HAL::DigitalSource* SMACCMGPIO::channel(uint16_t n)
|
{
|
||||||
{
|
}
|
||||||
return NULL;
|
|
||||||
}
|
/* Alternative interface: */
|
||||||
|
AP_HAL::DigitalSource* SMACCMGPIO::channel(uint16_t n)
|
||||||
/* Interrupt interface: */
|
{
|
||||||
bool SMACCMGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
|
return NULL;
|
||||||
uint8_t mode)
|
}
|
||||||
{
|
|
||||||
return true;
|
/* Interrupt interface: */
|
||||||
}
|
bool SMACCMGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
|
||||||
|
uint8_t mode)
|
||||||
SMACCMDigitalSource::SMACCMDigitalSource(uint8_t v) :
|
{
|
||||||
_v(v)
|
return true;
|
||||||
{
|
}
|
||||||
}
|
|
||||||
|
SMACCMDigitalSource::SMACCMDigitalSource(uint8_t v) :
|
||||||
void SMACCMDigitalSource::mode(uint8_t output)
|
_v(v)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t SMACCMDigitalSource::read()
|
void SMACCMDigitalSource::mode(uint8_t output)
|
||||||
{
|
{
|
||||||
return _v;
|
}
|
||||||
}
|
|
||||||
|
uint8_t SMACCMDigitalSource::read()
|
||||||
void SMACCMDigitalSource::write(uint8_t value)
|
{
|
||||||
{
|
return _v;
|
||||||
_v = value;
|
}
|
||||||
}
|
|
||||||
|
void SMACCMDigitalSource::write(uint8_t value)
|
||||||
|
{
|
||||||
|
_v = value;
|
||||||
|
}
|
||||||
|
|
||||||
|
void SMACCMDigitalSource::toggle()
|
||||||
|
{
|
||||||
|
_v = !_v;
|
||||||
|
}
|
@ -1,35 +1,46 @@
|
|||||||
|
|
||||||
#ifndef __AP_HAL_SMACCM_GPIO_H__
|
#ifndef __AP_HAL_SMACCM_GPIO_H__
|
||||||
#define __AP_HAL_SMACCM_GPIO_H__
|
#define __AP_HAL_SMACCM_GPIO_H__
|
||||||
|
|
||||||
#include <AP_HAL_SMACCM.h>
|
#include <AP_HAL_SMACCM.h>
|
||||||
|
|
||||||
class SMACCM::SMACCMGPIO : public AP_HAL::GPIO {
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SMACCM
|
||||||
public:
|
// XXX these are just copied, may not make sense
|
||||||
SMACCMGPIO();
|
# define HAL_GPIO_A_LED_PIN 27
|
||||||
void init();
|
# define HAL_GPIO_B_LED_PIN 26
|
||||||
void pinMode(uint8_t pin, uint8_t output);
|
# define HAL_GPIO_C_LED_PIN 25
|
||||||
int8_t analogPinToDigitalPin(uint8_t pin);
|
# define HAL_GPIO_LED_ON LOW
|
||||||
uint8_t read(uint8_t pin);
|
# define HAL_GPIO_LED_OFF HIGH
|
||||||
void write(uint8_t pin, uint8_t value);
|
#endif
|
||||||
|
|
||||||
/* Alternative interface: */
|
class SMACCM::SMACCMGPIO : public AP_HAL::GPIO {
|
||||||
AP_HAL::DigitalSource* channel(uint16_t n);
|
public:
|
||||||
|
SMACCMGPIO();
|
||||||
/* Interrupt interface: */
|
void init();
|
||||||
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
|
void pinMode(uint8_t pin, uint8_t output);
|
||||||
uint8_t mode);
|
int8_t analogPinToDigitalPin(uint8_t pin);
|
||||||
|
uint8_t read(uint8_t pin);
|
||||||
};
|
void write(uint8_t pin, uint8_t value);
|
||||||
|
void toggle(uint8_t pin);
|
||||||
class SMACCM::SMACCMDigitalSource : public AP_HAL::DigitalSource {
|
|
||||||
public:
|
/* Alternative interface: */
|
||||||
SMACCMDigitalSource(uint8_t v);
|
AP_HAL::DigitalSource* channel(uint16_t n);
|
||||||
void mode(uint8_t output);
|
|
||||||
uint8_t read();
|
/* Interrupt interface: */
|
||||||
void write(uint8_t value);
|
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
|
||||||
private:
|
uint8_t mode);
|
||||||
uint8_t _v;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_SMACCM_GPIO_H__
|
class SMACCM::SMACCMDigitalSource : public AP_HAL::DigitalSource {
|
||||||
|
public:
|
||||||
|
SMACCMDigitalSource(uint8_t v);
|
||||||
|
void mode(uint8_t output);
|
||||||
|
uint8_t read();
|
||||||
|
void write(uint8_t value);
|
||||||
|
void toggle();
|
||||||
|
private:
|
||||||
|
uint8_t _v;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // __AP_HAL_SMACCM_GPIO_H__
|
||||||
|
Loading…
Reference in New Issue
Block a user