HAL_PX4: added GPIO driver

This commit is contained in:
Marco Bauer 2013-07-11 13:01:59 +10:00 committed by Andrew Tridgell
parent ac5d925115
commit a3b216bce3
4 changed files with 213 additions and 23 deletions

View File

@ -12,6 +12,8 @@ namespace PX4 {
class PX4AnalogIn;
class PX4AnalogSource;
class PX4Util;
class PX4GPIO;
class PX4DigitalSource;
}
#endif //__AP_HAL_PX4_NAMESPACE_H__

View File

@ -0,0 +1,145 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
#include "GPIO.h"
#include "defines.h"
#include "config.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
/* PX4 headers */
#include <drivers/drv_led.h>
#include <drivers/drv_tone_alarm.h>
#include <drivers/drv_gpio.h>
#define LOW 1
#define HIGH 0
extern const AP_HAL::HAL& hal;
using namespace PX4;
PX4GPIO::PX4GPIO()
{}
void PX4GPIO::init()
{
_led_fd = open(LED_DEVICE_PATH, O_RDWR);
if (_led_fd == -1) {
hal.scheduler->panic("Unable to open " LED_DEVICE_PATH);
}
if (ioctl(_led_fd, LED_OFF, LED_BLUE) != 0) {
hal.console->printf("GPIO: Unable to setup GPIO LED BLUE\n");
}
if (ioctl(_led_fd, LED_OFF, LED_RED) != 0) {
hal.console->printf("GPIO: Unable to setup GPIO LED RED\n");
}
_tone_alarm_fd = open("/dev/tone_alarm", O_WRONLY);
if (_tone_alarm_fd == -1) {
hal.scheduler->panic("Unable to open /dev/tone_alarm");
}
_gpio_fd = open(GPIO_DEVICE_PATH, O_RDWR);
if (_gpio_fd == -1) {
hal.scheduler->panic("Unable to open GPIO");
}
if (ioctl(_gpio_fd, GPIO_CLEAR, GPIO_EXT_1) != 0) {
hal.console->printf("GPIO: Unable to setup GPIO_1\n");
}
}
void PX4GPIO::pinMode(uint8_t pin, uint8_t output)
{}
int8_t PX4GPIO::analogPinToDigitalPin(uint8_t pin)
{
return -1;
}
uint8_t PX4GPIO::read(uint8_t pin) {
return 0;
}
void PX4GPIO::write(uint8_t pin, uint8_t value)
{
//char *user_tune = "MBL4O6C";
switch (pin) {
case A_LED_PIN: // Arming LED
if (value == LOW) {
ioctl(_led_fd, LED_OFF, LED_RED);
} else {
ioctl(_led_fd, LED_ON, LED_RED);
}
break;
case B_LED_PIN: // not used yet
break;
case C_LED_PIN: // GPS LED
if (value == LOW) {
ioctl(_led_fd, LED_OFF, LED_BLUE);
} else {
ioctl(_led_fd, LED_ON, LED_BLUE);
}
break;
case PIEZO_PIN: // Piezo beeper
if (value == LOW) { // this is inverted
ioctl(_tone_alarm_fd, TONE_SET_ALARM, 3); // Alarm on !!
//::write(_tone_alarm_fd, &user_tune, sizeof(user_tune));
} else {
ioctl(_tone_alarm_fd, TONE_SET_ALARM, 0); // Alarm off !!
}
break;
case 99: // Ext Relay
if (value == LOW) {
ioctl(_gpio_fd, GPIO_CLEAR, GPIO_EXT_1);
} else {
ioctl(_gpio_fd, GPIO_SET, GPIO_EXT_1);
}
break;
}
}
/* Alternative interface: */
AP_HAL::DigitalSource* PX4GPIO::channel(uint16_t n) {
return new PX4DigitalSource(0);
}
/* Interrupt interface: */
bool PX4GPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
{
return true;
}
PX4DigitalSource::PX4DigitalSource(uint8_t v) :
_v(v)
{}
void PX4DigitalSource::mode(uint8_t output)
{}
uint8_t PX4DigitalSource::read() {
return _v;
}
void PX4DigitalSource::write(uint8_t value) {
_v = value;
}
#endif // CONFIG_HAL_BOARD

View File

@ -0,0 +1,39 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_HAL_PX4_GPIO_H__
#define __AP_HAL_PX4_GPIO_H__
#include <AP_HAL_PX4.h>
class PX4::PX4GPIO : public AP_HAL::GPIO {
public:
PX4GPIO();
void init();
void pinMode(uint8_t pin, uint8_t output);
int8_t analogPinToDigitalPin(uint8_t pin);
uint8_t read(uint8_t pin);
void write(uint8_t pin, uint8_t value);
/* Alternative interface: */
AP_HAL::DigitalSource* channel(uint16_t n);
/* Interrupt interface: */
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode);
private:
int _led_fd;
int _tone_alarm_fd;
int _gpio_fd;
};
class PX4::PX4DigitalSource : public AP_HAL::DigitalSource {
public:
PX4DigitalSource(uint8_t v);
void mode(uint8_t output);
uint8_t read();
void write(uint8_t value);
private:
uint8_t _v;
};
#endif // __AP_HAL_EMPTY_GPIO_H__

View File

@ -15,6 +15,7 @@
#include "RCOutput.h"
#include "AnalogIn.h"
#include "Util.h"
#include "GPIO.h"
#include <AP_HAL_Empty.h>
#include <AP_HAL_Empty_Private.h>
@ -33,7 +34,7 @@ using namespace PX4;
static Empty::EmptySemaphore i2cSemaphore;
static Empty::EmptyI2CDriver i2cDriver(&i2cSemaphore);
static Empty::EmptySPIDeviceManager spiDeviceManager;
static Empty::EmptyGPIO gpioDriver;
//static Empty::EmptyGPIO gpioDriver;
static PX4ConsoleDriver consoleDriver;
static PX4Scheduler schedulerInstance;
@ -42,6 +43,7 @@ static PX4RCInput rcinDriver;
static PX4RCOutput rcoutDriver;
static PX4AnalogIn analogIn;
static PX4Util utilInstance;
static PX4GPIO gpioDriver;
#define UARTA_DEFAULT_DEVICE "/dev/ttyACM0"
#define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
@ -54,9 +56,9 @@ static PX4UARTDriver uartCDriver(UARTC_DEFAULT_DEVICE, "APM_uartC");
HAL_PX4::HAL_PX4() :
AP_HAL::HAL(
&uartADriver, /* uartA */
&uartBDriver, /* uartB */
&uartCDriver, /* uartC */
&uartADriver, /* uartA */
&uartBDriver, /* uartB */
&uartCDriver, /* uartC */
&i2cDriver, /* i2c */
&spiDeviceManager, /* spi */
&analogIn, /* analogin */
@ -69,9 +71,9 @@ HAL_PX4::HAL_PX4() :
&utilInstance) /* util */
{}
bool _px4_thread_should_exit = false; /**< Daemon exit flag */
static bool thread_running = false; /**< Daemon status flag */
static int daemon_task; /**< Handle of daemon task / thread */
bool _px4_thread_should_exit = false; /**< Daemon exit flag */
static bool thread_running = false; /**< Daemon status flag */
static int daemon_task; /**< Handle of daemon task / thread */
static bool ran_overtime;
extern const AP_HAL::HAL& hal;
@ -117,6 +119,8 @@ static int main_loop(int argc, char **argv)
hal.rcin->init(NULL);
hal.rcout->init(NULL);
hal.analogin->init(NULL);
hal.gpio->init();
/*
run setup() at low priority to ensure CLI doesn't hang the
@ -153,7 +157,7 @@ static int main_loop(int argc, char **argv)
*/
hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, NULL);
loop();
loop();
if (ran_overtime) {
/*
@ -181,7 +185,7 @@ static int main_loop(int argc, char **argv)
*/
hrt_call_after(&loop_call, 500, (hrt_callout)semaphore_yield, &loop_semaphore);
sem_wait(&loop_semaphore);
}
}
thread_running = false;
return 0;
}
@ -203,7 +207,7 @@ void HAL_PX4::init(int argc, char * const argv[]) const
const char *deviceC = UARTC_DEFAULT_DEVICE;
if (argc < 1) {
printf("%s: missing command (try '%s start')",
printf("%s: missing command (try '%s start')",
SKETCHNAME, SKETCHNAME);
usage();
exit(1);
@ -248,31 +252,31 @@ void HAL_PX4::init(int argc, char * const argv[]) const
exit(0);
}
if (strcmp(argv[i], "-d") == 0) {
if (strcmp(argv[i], "-d") == 0) {
// set terminal device
if (argc > i + 1) {
if (argc > i + 1) {
deviceA = strdup(argv[i+1]);
} else {
printf("missing parameter to -d DEVICE\n");
} else {
printf("missing parameter to -d DEVICE\n");
usage();
exit(1);
}
}
}
}
if (strcmp(argv[i], "-d2") == 0) {
if (strcmp(argv[i], "-d2") == 0) {
// set uartC terminal device
if (argc > i + 1) {
if (argc > i + 1) {
deviceC = strdup(argv[i+1]);
} else {
printf("missing parameter to -d2 DEVICE\n");
} else {
printf("missing parameter to -d2 DEVICE\n");
usage();
exit(1);
}
}
}
}
}
usage();
exit(1);
exit(1);
}
const HAL_PX4 AP_HAL_PX4;