aboutsummaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2012-10-28 15:27:13 +0100
committerThomas Gubler <thomasgubler@gmail.com>2012-10-28 15:27:13 +0100
commit8d764170aa42fa0bf3d15fe5a91d2b52e0cc2036 (patch)
treebf83d33c14851e548823d81b64e49be3e86b0e48 /nuttx/configs
parente5f56a1a8fe3c81fcb182cace9e81bbaaa3d0031 (diff)
parent1a70b2f4ed0feffd9c57721db3661f15e64af5cb (diff)
downloadpx4-firmware-8d764170aa42fa0bf3d15fe5a91d2b52e0cc2036.tar.gz
px4-firmware-8d764170aa42fa0bf3d15fe5a91d2b52e0cc2036.tar.bz2
px4-firmware-8d764170aa42fa0bf3d15fe5a91d2b52e0cc2036.zip
Merge remote-tracking branch 'origin/master' into fw_control
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/px4fmu/common/ld.script9
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h44
-rw-r--r--nuttx/configs/px4fmu/include/drv_gpio.h107
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig2
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig4
-rw-r--r--nuttx/configs/px4fmu/src/Makefile1
-rw-r--r--nuttx/configs/px4fmu/src/drv_gpio.c195
7 files changed, 16 insertions, 346 deletions
diff --git a/nuttx/configs/px4fmu/common/ld.script b/nuttx/configs/px4fmu/common/ld.script
index b1852b0bd..de8179e8d 100644
--- a/nuttx/configs/px4fmu/common/ld.script
+++ b/nuttx/configs/px4fmu/common/ld.script
@@ -88,6 +88,15 @@ SECTIONS
} > flash
/*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ /*
* Construction data for parameters.
*/
__param ALIGN(4): {
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
index a7dae6552..3f0f26ba1 100755
--- a/nuttx/configs/px4fmu/include/board.h
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -45,9 +45,6 @@
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
-//#include "stm32_rcc.h"
-//#include "stm32_sdio.h"
-//#include "stm32_internal.h"
/************************************************************************************
* Definitions
@@ -298,7 +295,7 @@
* Note that these are unshifted addresses.
*/
#define PX4_I2C_OBDEV_HMC5883 0x1e
-#define PX4_I2C_OBDEV_MS5611 NOTDEFINED
+#define PX4_I2C_OBDEV_MS5611 0x76
#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
#define PX4_I2C_OBDEV_PX4IO_BL 0x18
@@ -327,11 +324,9 @@
/*
* Tone alarm output
*/
-#ifdef CONFIG_TONE_ALARM
-# define TONE_ALARM_TIMER 3 /* timer 3 */
-# define TONE_ALARM_CHANNEL 3 /* channel 3 */
-# define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
-#endif
+#define TONE_ALARM_TIMER 3 /* timer 3 */
+#define TONE_ALARM_CHANNEL 3 /* channel 3 */
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
/************************************************************************************
* Public Data
@@ -362,37 +357,6 @@ extern "C" {
EXTERN void stm32_boardinitialize(void);
-/************************************************************************************
- * Button support.
- *
- * Description:
- * up_buttoninit() must be called to initialize button resources. After
- * that, up_buttons() may be called to collect the current state of all
- * buttons or up_irqbutton() may be called to register button interrupt
- * handlers.
- *
- * After up_buttoninit() has been called, up_buttons() may be called to
- * collect the state of all buttons. up_buttons() returns an 8-bit bit set
- * with each bit associated with a button. See the BUTTON_*_BIT
- * definitions in board.h for the meaning of each bit.
- *
- * up_irqbutton() may be called to register an interrupt handler that will
- * be called when a button is depressed or released. The ID value is a
- * button enumeration value that uniquely identifies a button resource. See the
- * BUTTON_* definitions in board.h for the meaning of enumeration
- * value. The previous interrupt handler address is returned (so that it may
- * restored, if so desired).
- *
- ************************************************************************************/
-
-#ifdef CONFIG_ARCH_BUTTONS
-EXTERN void up_buttoninit(void);
-EXTERN uint8_t up_buttons(void);
-#ifdef CONFIG_ARCH_IRQBUTTONS
-EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
-#endif
-#endif
-
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/configs/px4fmu/include/drv_gpio.h b/nuttx/configs/px4fmu/include/drv_gpio.h
deleted file mode 100644
index 22f80d038..000000000
--- a/nuttx/configs/px4fmu/include/drv_gpio.h
+++ /dev/null
@@ -1,107 +0,0 @@
-/****************************************************************************
- *
- * 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 GPIO driver interface.
- *
- * This header defines the basic interface to platform-specific GPIOs.
- */
-
-#ifndef _BOARD_DRV_GPIO_H
-#define _BOARD_DRV_GPIO_H
-
-/*
- * PX4FMU GPIO numbers.
- *
- * For shared pins, alternate function 1 selects the non-GPIO mode
- * (USART2, CAN2, etc.)
- */
-#define GPIO_EXT_1 (1<<0) /**< high-power GPIO 1 */
-#define GPIO_EXT_2 (1<<1) /**< high-power GPIO 1 */
-#define GPIO_MULTI_1 (1<<2) /**< USART2 CTS */
-#define GPIO_MULTI_2 (1<<3) /**< USART2 RTS */
-#define GPIO_MULTI_3 (1<<4) /**< USART2 TX */
-#define GPIO_MULTI_4 (1<<5) /**< USART2 RX */
-#define GPIO_CAN_TX (1<<6) /**< CAN2 TX */
-#define GPIO_CAN_RX (1<<7) /**< CAN2 RX */
-
-/**
- * Default GPIO device - other devices may also support this protocol if
- * they also export GPIO-like things. This is always the GPIOs on the
- * main board.
- */
-#define GPIO_DEVICE_PATH "/dev/gpio"
-
-/*
- * IOCTL definitions.
- *
- * For all ioctls, the (arg) argument is a bitmask of GPIOs to be affected
- * by the operation, with the LSB being the lowest-numbered GPIO.
- *
- * Note that there may be board-specific relationships between GPIOs;
- * applications using GPIOs should be aware of this.
- */
-#define _GPIOCBASE 0x6700
-#define GPIOC(_x) _IOC(_GPIOCBASE, _x)
-
-/** reset all board GPIOs to their default state */
-#define GPIO_RESET GPIOC(0)
-
-/** configure the board GPIOs in (arg) as outputs */
-#define GPIO_SET_OUTPUT GPIOC(1)
-
-/** configure the board GPIOs in (arg) as inputs */
-#define GPIO_SET_INPUT GPIOC(2)
-
-/** configure the board GPIOs in (arg) for the first alternate function (if supported) */
-#define GPIO_SET_ALT_1 GPIOC(3)
-
-/** configure the board GPIO (arg) for the second alternate function (if supported) */
-#define GPIO_SET_ALT_2 GPIOC(4)
-
-/** configure the board GPIO (arg) for the third alternate function (if supported) */
-#define GPIO_SET_ALT_3 GPIOC(5)
-
-/** configure the board GPIO (arg) for the fourth alternate function (if supported) */
-#define GPIO_SET_ALT_4 GPIOC(6)
-
-/** set the GPIOs in (arg) */
-#define GPIO_SET GPIOC(10)
-
-/** clear the GPIOs in (arg) */
-#define GPIO_CLEAR GPIOC(11)
-
-/** read all the GPIOs and return their values in *(uint32_t *)arg */
-#define GPIO_GET GPIOC(12)
-
-#endif /* _DRV_GPIO_H */
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 46df8a45d..67fe69a30 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -97,7 +97,7 @@ CONFIGURED_APPS += drivers/l3gd20
CONFIGURED_APPS += drivers/px4io
CONFIGURED_APPS += drivers/stm32
CONFIGURED_APPS += drivers/stm32/tone_alarm
-CONFIGURED_APPS += px4/fmu
+CONFIGURED_APPS += drivers/px4fmu
# Testing stuff
CONFIGURED_APPS += px4/sensors_bringup
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index c2656217d..91cd0366d 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -179,7 +179,7 @@ CONFIG_STM32_I2C1=y
CONFIG_STM32_I2C2=y
CONFIG_STM32_I2C3=y
CONFIG_STM32_CAN1=n
-CONFIG_STM32_CAN2=y
+CONFIG_STM32_CAN2=n
CONFIG_STM32_DAC=n
CONFIG_STM32_PWR=y
# APB2:
@@ -542,7 +542,7 @@ CONFIG_DEBUG_I2C=n
CONFIG_DEBUG_INPUT=n
CONFIG_HAVE_CXX=y
-CONFIG_HAVE_CXXINITIALIZE=n
+CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_MM_REGIONS=2
CONFIG_ARCH_LOWPUTC=y
CONFIG_MSEC_PER_TICK=1
diff --git a/nuttx/configs/px4fmu/src/Makefile b/nuttx/configs/px4fmu/src/Makefile
index d88040013..13b26b84f 100644
--- a/nuttx/configs/px4fmu/src/Makefile
+++ b/nuttx/configs/px4fmu/src/Makefile
@@ -41,7 +41,6 @@ ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = up_leds.c \
- drv_gpio.c \
drv_led.c drv_eeprom.c
COBJS = $(CSRCS:.c=$(OBJEXT))
diff --git a/nuttx/configs/px4fmu/src/drv_gpio.c b/nuttx/configs/px4fmu/src/drv_gpio.c
deleted file mode 100644
index be95420dd..000000000
--- a/nuttx/configs/px4fmu/src/drv_gpio.c
+++ /dev/null
@@ -1,195 +0,0 @@
-/****************************************************************************
- *
- * 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.
- *
- ****************************************************************************/
-
-/*
- * GPIO driver for PX4FMU.
- *
- */
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-#include <errno.h>
-
-#include <nuttx/spi.h>
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "chip.h"
-#include "stm32_internal.h"
-#include "px4fmu-internal.h"
-
-#include <arch/board/drv_gpio.h>
-
-static int px4fmu_gpio_ioctl(struct file *filep, int cmd, unsigned long arg);
-
-static const struct file_operations px4fmu_gpio_fops = {
- .ioctl = px4fmu_gpio_ioctl,
-};
-
-static struct {
- uint32_t input;
- uint32_t output;
- uint32_t alt;
-} gpio_tab[] = {
- {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
- {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
- {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1},
- {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1},
- {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1},
- {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1},
- {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2},
- {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2},
-};
-
-#define NGPIO (sizeof(gpio_tab) / sizeof(gpio_tab[0]))
-
-
-static void
-px4fmu_gpio_reset(void)
-{
- /*
- * Setup default GPIO config - all pins as GPIOs, GPIO driver chip
- * to input mode.
- */
- for (unsigned i = 0; i < NGPIO; i++)
- stm32_configgpio(gpio_tab[i].input);
-
- stm32_gpiowrite(GPIO_GPIO_DIR, 0);
- stm32_configgpio(GPIO_GPIO_DIR);
-}
-
-static void
-px4fmu_gpio_set_function(uint32_t gpios, int function)
-{
- /*
- * GPIOs 0 and 1 must have the same direction as they are buffered
- * by a shared 2-port driver. Any attempt to set either sets both.
- */
- if (gpios & 3) {
- gpios |= 3;
-
- /* flip the buffer to output mode if required */
- if (GPIO_SET_OUTPUT == function)
- stm32_gpiowrite(GPIO_GPIO_DIR, 1);
- }
-
- /* configure selected GPIOs as required */
- for (unsigned i = 0; i < NGPIO; i++) {
- if (gpios & (1<<i)) {
- switch (function) {
- case GPIO_SET_INPUT:
- stm32_configgpio(gpio_tab[i].input);
- break;
- case GPIO_SET_OUTPUT:
- stm32_configgpio(gpio_tab[i].output);
- break;
- case GPIO_SET_ALT_1:
- if (gpio_tab[i].alt != 0)
- stm32_configgpio(gpio_tab[i].alt);
- break;
- }
- }
- }
-
- /* flip buffer to input mode if required */
- if ((GPIO_SET_INPUT == function) && (gpios & 3))
- stm32_gpiowrite(GPIO_GPIO_DIR, 0);
-}
-
-static void
-px4fmu_gpio_write(uint32_t gpios, int function)
-{
- int value = (function == GPIO_SET) ? 1 : 0;
-
- for (unsigned i = 0; i < NGPIO; i++)
- if (gpios & (1<<i))
- stm32_gpiowrite(gpio_tab[i].output, value);
-}
-
-static uint32_t
-px4fmu_gpio_read(void)
-{
- uint32_t bits = 0;
-
- for (unsigned i = 0; i < NGPIO; i++)
- if (stm32_gpioread(gpio_tab[i].input))
- bits |= (1 << i);
-
- return bits;
-}
-
-void
-px4fmu_gpio_init(void)
-{
- /* reset all GPIOs to default state */
- px4fmu_gpio_reset();
-
- /* register the driver */
- register_driver(GPIO_DEVICE_PATH, &px4fmu_gpio_fops, 0666, NULL);
-}
-
-static int
-px4fmu_gpio_ioctl(struct file *filep, int cmd, unsigned long arg)
-{
- int result = OK;
-
- switch (cmd) {
-
- case GPIO_RESET:
- px4fmu_gpio_reset();
- break;
-
- case GPIO_SET_OUTPUT:
- case GPIO_SET_INPUT:
- case GPIO_SET_ALT_1:
- px4fmu_gpio_set_function(arg, cmd);
- break;
-
- case GPIO_SET:
- case GPIO_CLEAR:
- px4fmu_gpio_write(arg, cmd);
- break;
-
- case GPIO_GET:
- *(uint32_t *)arg = px4fmu_gpio_read();
- break;
-
- default:
- result = -ENOTTY;
- }
- return result;
-}
-