aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h6
-rw-r--r--nuttx/configs/px4fmu/include/nsh_romfsimg.h42
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig7
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig2
4 files changed, 51 insertions, 6 deletions
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
index 0bc0b3021..294b6c398 100755
--- a/nuttx/configs/px4fmu/include/board.h
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -308,6 +308,10 @@
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
+#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2
+#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_2
+#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2
+
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1
#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2
@@ -321,6 +325,8 @@
#define PX4_SPIDEV_ACCEL 2
#define PX4_SPIDEV_MPU 3
+#define PX4_SPIDEV_ACCEL_MAG 2 // external for anti vibration test
+
/*
* Tone alarm output
*/
diff --git a/nuttx/configs/px4fmu/include/nsh_romfsimg.h b/nuttx/configs/px4fmu/include/nsh_romfsimg.h
new file mode 100644
index 000000000..15e4e7a8d
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/nsh_romfsimg.h
@@ -0,0 +1,42 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 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.
+ *
+ ****************************************************************************/
+
+/**
+ * nsh_romfsetc.h
+ *
+ * This file is a stub for 'make export' purposes; the actual ROMFS
+ * must be supplied by the library client.
+ */
+
+extern unsigned char romfs_img[];
+extern unsigned int romfs_img_len;
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 9e28ff485..1e5d7d4e1 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -65,7 +65,6 @@ CONFIGURED_APPS += systemcmds/perf
CONFIGURED_APPS += systemcmds/top
CONFIGURED_APPS += systemcmds/boardinfo
CONFIGURED_APPS += systemcmds/mixer
-CONFIGURED_APPS += systemcmds/eeprom
CONFIGURED_APPS += systemcmds/param
CONFIGURED_APPS += systemcmds/pwm
CONFIGURED_APPS += systemcmds/bl_update
@@ -110,20 +109,18 @@ endif
CONFIGURED_APPS += systemcmds/i2c
# Communication and Drivers
-CONFIGURED_APPS += drivers/boards/px4fmu
+#CONFIGURED_APPS += drivers/boards/px4fmu
CONFIGURED_APPS += drivers/device
CONFIGURED_APPS += drivers/ms5611
CONFIGURED_APPS += drivers/hmc5883
CONFIGURED_APPS += drivers/mpu6000
CONFIGURED_APPS += drivers/bma180
-CONFIGURED_APPS += drivers/l3gd20
CONFIGURED_APPS += drivers/px4io
CONFIGURED_APPS += drivers/stm32
-CONFIGURED_APPS += drivers/led
+#CONFIGURED_APPS += drivers/led
CONFIGURED_APPS += drivers/blinkm
CONFIGURED_APPS += drivers/stm32/tone_alarm
CONFIGURED_APPS += drivers/stm32/adc
-CONFIGURED_APPS += drivers/px4fmu
CONFIGURED_APPS += drivers/hil
CONFIGURED_APPS += drivers/gps
CONFIGURED_APPS += drivers/mb12xx
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index 130886aac..cf30b835f 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -85,7 +85,7 @@ CONFIG_ARCH_FPU=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
-CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=y