aboutsummaryrefslogtreecommitdiff
path: root/apps/drivers
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-10-31 00:37:15 -0700
committerpx4dev <px4@purgatory.org>2012-10-31 00:37:15 -0700
commit34a3b260f34398994a315388b3ffed22a1fe22fb (patch)
treecbea6c3fff4e2701921827b122df9d348c38ac1c /apps/drivers
parentb685d46dbfc583a26a92f1466dca64f9d45c3c4e (diff)
downloadpx4-firmware-34a3b260f34398994a315388b3ffed22a1fe22fb.tar.gz
px4-firmware-34a3b260f34398994a315388b3ffed22a1fe22fb.tar.bz2
px4-firmware-34a3b260f34398994a315388b3ffed22a1fe22fb.zip
Move the last of the board-specific code for PX4FMU out of the NuttX tree. Now it's just configuration.
Diffstat (limited to 'apps/drivers')
-rw-r--r--apps/drivers/boards/px4fmu/px4fmu_init.c64
-rw-r--r--apps/drivers/boards/px4fmu/px4fmu_led.c88
-rw-r--r--apps/drivers/boards/px4fmu/px4fmu_pwm_servo.c10
-rw-r--r--apps/drivers/drv_led.h64
-rw-r--r--apps/drivers/led/Makefile38
-rw-r--r--apps/drivers/led/led.cpp115
6 files changed, 311 insertions, 68 deletions
diff --git a/apps/drivers/boards/px4fmu/px4fmu_init.c b/apps/drivers/boards/px4fmu/px4fmu_init.c
index 38a284017..568d861c9 100644
--- a/apps/drivers/boards/px4fmu/px4fmu_init.c
+++ b/apps/drivers/boards/px4fmu/px4fmu_init.c
@@ -64,9 +64,9 @@
#include "stm32_uart.h"
#include <arch/board/board.h>
-#include <arch/board/drv_led.h>
#include <drivers/drv_hrt.h>
+#include <drivers/drv_led.h>
#include <systemlib/cpuload.h>
@@ -131,9 +131,6 @@ __EXPORT void stm32_boardinitialize(void)
static struct spi_dev_s *spi1;
static struct spi_dev_s *spi3;
-static struct i2c_dev_s *i2c1;
-static struct i2c_dev_s *i2c2;
-static struct i2c_dev_s *i2c3;
#include <math.h>
@@ -153,10 +150,6 @@ __EXPORT int nsh_archinitialize(void)
{
int result;
- /* INIT 1 Lowest level NuttX initialization has been done at this point, LEDs and UARTs are configured */
-
- /* INIT 2 Configuring PX4 low-level peripherals, these will be always needed */
-
/* configure the high-resolution time/callout interface */
#ifdef CONFIG_HRT_TIMER
hrt_init();
@@ -190,14 +183,12 @@ __EXPORT int nsh_archinitialize(void)
message("\r\n");
+ // initial LED state
+ drv_led_start();
up_ledoff(LED_BLUE);
up_ledoff(LED_AMBER);
-
up_ledon(LED_BLUE);
- /* Configure user-space led driver */
- px4fmu_led_init();
-
/* Configure SPI-based devices */
spi1 = up_spiinitialize(1);
@@ -219,38 +210,6 @@ __EXPORT int nsh_archinitialize(void)
message("[boot] Successfully initialized SPI port 1\r\n");
-#if 0
- /* initialize I2C2 bus */
-
- i2c2 = up_i2cinitialize(2);
-
- if (!i2c2) {
- message("[boot] FAILED to initialize I2C bus 2\n");
- up_ledon(LED_AMBER);
- return -ENODEV;
- }
-
- /* set I2C2 speed */
- I2C_SETFREQUENCY(i2c2, 400000);
-
-
- i2c3 = up_i2cinitialize(3);
-
- if (!i2c3) {
- message("[boot] FAILED to initialize I2C bus 3\n");
- up_ledon(LED_AMBER);
- return -ENODEV;
- }
-
- /* set I2C3 speed */
- I2C_SETFREQUENCY(i2c3, 400000);
-
- /* try to attach, don't fail if device is not responding */
- (void)eeprom_attach(i2c3, FMU_BASEBOARD_EEPROM_ADDRESS,
- FMU_BASEBOARD_EEPROM_TOTAL_SIZE_BYTES,
- FMU_BASEBOARD_EEPROM_PAGE_SIZE_BYTES,
- FMU_BASEBOARD_EEPROM_PAGE_WRITE_TIME_US, "/dev/baseboard_eeprom", 1);
-#endif
#if defined(CONFIG_STM32_SPI3)
/* Get the SPI port */
@@ -276,24 +235,7 @@ __EXPORT int nsh_archinitialize(void)
message("[boot] Successfully bound SPI port 3 to the MMCSD driver\n");
#endif /* SPI3 */
-#if 0
- /* initialize I2C1 bus */
-
- i2c1 = up_i2cinitialize(1);
- if (!i2c1) {
- message("[boot] FAILED to initialize I2C bus 1\n");
- up_ledon(LED_AMBER);
- return -ENODEV;
- }
-
- /* set I2C1 speed */
- I2C_SETFREQUENCY(i2c1, 400000);
-
- /* INIT 3: MULTIPORT-DEPENDENT INITIALIZATION */
-
- /* Get board information if available */
-#endif
#ifdef CONFIG_ADC
int adc_state = adc_devinit();
diff --git a/apps/drivers/boards/px4fmu/px4fmu_led.c b/apps/drivers/boards/px4fmu/px4fmu_led.c
new file mode 100644
index 000000000..fd1e159aa
--- /dev/null
+++ b/apps/drivers/boards/px4fmu/px4fmu_led.c
@@ -0,0 +1,88 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4fmu_led.c
+ *
+ * PX4FMU LED backend.
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "px4fmu_internal.h"
+
+__EXPORT void up_ledinit()
+{
+ /* Configure LED1-2 GPIOs for output */
+
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+}
+
+__EXPORT void up_ledon(int led)
+{
+ if (led == 0)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+ if (led == 1)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED2, false);
+ }
+}
+
+__EXPORT void up_ledoff(int led)
+{
+ if (led == 0)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+ if (led == 1)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+}
diff --git a/apps/drivers/boards/px4fmu/px4fmu_pwm_servo.c b/apps/drivers/boards/px4fmu/px4fmu_pwm_servo.c
index d1ff8c112..cb8918306 100644
--- a/apps/drivers/boards/px4fmu/px4fmu_pwm_servo.c
+++ b/apps/drivers/boards/px4fmu/px4fmu_pwm_servo.c
@@ -46,13 +46,9 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
-#include "chip.h"
-#include "up_internal.h"
-#include "up_arch.h"
-
-#include "stm32_internal.h"
-#include "stm32_gpio.h"
-#include "stm32_tim.h"
+#include <stm32_internal.h>
+#include <stm32_gpio.h>
+#include <stm32_tim.h>
__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
{
diff --git a/apps/drivers/drv_led.h b/apps/drivers/drv_led.h
new file mode 100644
index 000000000..bf21787f2
--- /dev/null
+++ b/apps/drivers/drv_led.h
@@ -0,0 +1,64 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file drv_led.h
+ *
+ * LED driver API
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
+#define LED_DEVICE_PATH "/dev/led"
+
+#define _LED_BASE 0x2800
+
+/* PX4 LED colour codes */
+#define LED_AMBER 0
+#define LED_RED 0 /* some boards have red rather than amber */
+#define LED_BLUE 1
+
+#define LED_ON _IOC(_LED_BASE, 0)
+#define LED_OFF _IOC(_LED_BASE, 1)
+
+__BEGIN_DECLS
+
+/*
+ * Initialise the LED driver.
+ */
+__EXPORT extern void drv_led_start();
+
+__END_DECLS
diff --git a/apps/drivers/led/Makefile b/apps/drivers/led/Makefile
new file mode 100644
index 000000000..7de188259
--- /dev/null
+++ b/apps/drivers/led/Makefile
@@ -0,0 +1,38 @@
+############################################################################
+#
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Makefile to build the LED driver.
+#
+
+include $(APPDIR)/mk/app.mk
diff --git a/apps/drivers/led/led.cpp b/apps/drivers/led/led.cpp
new file mode 100644
index 000000000..12d864be2
--- /dev/null
+++ b/apps/drivers/led/led.cpp
@@ -0,0 +1,115 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file led.cpp
+ *
+ * LED driver.
+ */
+
+#include <nuttx/config.h>
+#include <drivers/device/device.h>
+#include <drivers/drv_led.h>
+
+/* Ideally we'd be able to get these from up_internal.h */
+//#include <up_internal.h>
+__BEGIN_DECLS
+extern void up_ledinit();
+extern void up_ledon(int led);
+extern void up_ledoff(int led);
+__END_DECLS
+
+class LED : device::CDev
+{
+public:
+ LED();
+ ~LED();
+
+ virtual int init();
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+};
+
+LED::LED() :
+ CDev("led", LED_DEVICE_PATH)
+{
+ // force immediate init/device registration
+ init();
+}
+
+LED::~LED()
+{
+}
+
+int
+LED::init()
+{
+ CDev::init();
+ up_ledinit();
+
+ return 0;
+}
+
+int
+LED::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = OK;
+
+ switch (cmd) {
+ case LED_ON:
+ up_ledon(arg);
+ break;
+
+ case LED_OFF:
+ up_ledoff(arg);
+ break;
+
+ default:
+ result = CDev::ioctl(filp, cmd, arg);
+ }
+ return result;
+}
+
+namespace
+{
+LED *gLED;
+}
+
+void
+drv_led_start()
+{
+ if (gLED == nullptr) {
+ gLED = new LED;
+ if (gLED != nullptr)
+ gLED->init();
+ }
+} \ No newline at end of file