summaryrefslogtreecommitdiff
path: root/nuttx/configs/vsn
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-27 15:03:49 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-27 15:03:49 +0000
commit331b7968c8606a58e5458d98559ac6366a767dd2 (patch)
treedad89d8ac9b2ac797623e2869cf729612fa2ae3a /nuttx/configs/vsn
parent23a7ea577bec1494adf24fe09cf9835bd717da3a (diff)
downloadpx4-nuttx-331b7968c8606a58e5458d98559ac6366a767dd2.tar.gz
px4-nuttx-331b7968c8606a58e5458d98559ac6366a767dd2.tar.bz2
px4-nuttx-331b7968c8606a58e5458d98559ac6366a767dd2.zip
Updates from Uros
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3424 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/vsn')
-rw-r--r--nuttx/configs/vsn/include/board.h45
-rwxr-xr-xnuttx/configs/vsn/nsh/defconfig45
-rw-r--r--nuttx/configs/vsn/src/nsh.c89
-rw-r--r--nuttx/configs/vsn/src/sif.c29
-rw-r--r--nuttx/configs/vsn/src/vsn.h49
5 files changed, 99 insertions, 158 deletions
diff --git a/nuttx/configs/vsn/include/board.h b/nuttx/configs/vsn/include/board.h
index 733f1fc32..a1a30c4b1 100644
--- a/nuttx/configs/vsn/include/board.h
+++ b/nuttx/configs/vsn/include/board.h
@@ -55,51 +55,6 @@
/************************************************************************************
* Definitions
************************************************************************************/
-
-/* Board Peripheral Assignment
- *
- * RS232/Power connector:
- * - USART1, is the default bootloader and console
- *
- * Sensor Connector:
- * Digital:
- * - GPIOs: PB10, PB11 (or even TIM2 CH3 and CH4)
- * - USART3
- * - I2C2
- * Analog:
- * - ADC1
- * Supporting Analog Circuitry (not seen outside)
- * - RefTap (TIM3_CH3)
- * - Power PWM Out (TIM8_CH1 / TIM3_CH1)
- * - Filtered Out (TIM3_CH4)
- * (TIM8 could run at lower frequency, while TIM3 must run at highest possible)
- * - Gain selection muxed with SDcard I/Os.
- *
- * Radio connector:
- * - UART3 / UART4
- * - SPI2
- * - I2C1 (remapped pins vs. Expansion connector)
- * - CAN
- * - TIM4 CH[3:4]
- *
- * Expansion connector:
- * - WakeUp Pin
- * - System Wide Reset
- * - SPI1 is wired to expansion port
- * - I2C1
- * - USART2 [Rx, Tx, CTS, RTS]
- * - DAC [0:1]
- * - ADC2 on pins [0:7]
- * - TIM2 Channels [1:4]
- * - TIM5 Channels [1:4]
- *
- * Onboard Components:
- * - SPI3 has direct connection with FRAM
- * - SDCard, conencts the microSD and shares the control lines with Sensor Interface
- * to select Amplifier Gain
- * - ADC3 is used also for power management (can be shared with ADC1 on sensor connector
- * if not used)
- */
/* Clocking *************************************************************************/
diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig
index b4055a00e..875da63f8 100755
--- a/nuttx/configs/vsn/nsh/defconfig
+++ b/nuttx/configs/vsn/nsh/defconfig
@@ -102,6 +102,40 @@ CONFIG_STM32_BUILDROOT=y
CONFIG_STM32_DFU=n
#
+# STM32 JTAG Options
+#
+# CONFIG_STM32_JTAG_FULL_ENABLE -- Full JTAG Enable (Parallel and Serial)
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE -- Full but without the JNTRST pin
+# CONFIG_STM32_JTAG_SW_ENABLE - Serial (SWJ) dual pin only which, can
+# coexist besides the FRAM on SPI3
+#
+CONFIG_STM32_JTAG_FULL_ENABLE=n
+CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
+CONFIG_STM32_JTAG_SW_ENABLE=n
+
+#
+# STM32 Individual Peripheral Pin Mapping
+#
+CONFIG_STM32_TIM1_FULL_REMAP=n
+CONFIG_STM32_TIM1_PARTIAL_REMAP=n
+CONFIG_STM32_TIM2_FULL_REMAP=n
+CONFIG_STM32_TIM2_PARTIAL_REMAP_1=n
+CONFIG_STM32_TIM2_PARTIAL_REMAP_2=n
+CONFIG_STM32_TIM3_FULL_REMAP=n
+CONFIG_STM32_TIM3_PARTIAL_REMAP=n
+CONFIG_STM32_TIM4_REMAP=n
+CONFIG_STM32_USART1_REMAP=n
+CONFIG_STM32_USART2_REMAP=n
+CONFIG_STM32_USART3_FULL_REMAP=n
+CONFIG_STM32_USART3_PARTIAL_REMAP=n
+CONFIG_STM32_SPI1_REMAP=n
+CONFIG_STM32_SPI3_REMAP=n
+CONFIG_STM32_I2C1_REMAP=y
+CONFIG_STM32_CAN1_REMAP1=n
+CONFIG_STM32_CAN1_REMAP2=n
+
+
+#
# Individual subsystems can be enabled:
# AHB:
CONFIG_STM32_DMA1=n
@@ -139,17 +173,6 @@ CONFIG_STM32_TIM8=n
CONFIG_STM32_USART1=y
CONFIG_STM32_ADC3=n
-#
-# STM32 JTAG Options
-#
-# CONFIG_STM32_JTAG_FULL_ENABLE -- Full JTAG Enable (Parallel and Serial)
-# CONFIG_STM32_JTAG_NOJNTRST_ENABLE -- Full but without the JNTRST pin
-# CONFIG_STM32_JTAG_SW_ENABLE - Serial (SWJ) dual pin only which, can
-# coexist besides the FRAM on SPI3
-#
-CONFIG_STM32_JTAG_FULL_ENABLE=n
-CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
-CONFIG_STM32_JTAG_SW_ENABLE=n
#
# STM32F103Z specific serial device driver settings
diff --git a/nuttx/configs/vsn/src/nsh.c b/nuttx/configs/vsn/src/nsh.c
deleted file mode 100644
index c4e691ba9..000000000
--- a/nuttx/configs/vsn/src/nsh.c
+++ /dev/null
@@ -1,89 +0,0 @@
-/****************************************************************************
- * config/vsn/src/nsh.c
- * arch/arm/src/board/nsh.c
- *
- * Copyright (C) 2011 Uros Platise. All rights reserved.
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
- *
- * Authors: Uros Platise <uros.platise@isotel.eu>
- * Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * 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 NuttX 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <stdbool.h>
-#include <stdio.h>
-#include <debug.h>
-#include <errno.h>
-
-#include "vsn.h"
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* Configuration ************************************************************/
-
-/* PORT and SLOT number probably depend on the board configuration */
-
-#define CONFIG_NSH_HAVEUSBDEV 1
-
-/* Can't support USB features if USB is not enabled */
-
-#ifndef CONFIG_USBDEV
-# undef CONFIG_NSH_HAVEUSBDEV
-#endif
-
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nsh_archinitialize
- *
- * Description:
- * Perform architecture specific initialization
- *
- ****************************************************************************/
-
-int nsh_archinitialize(void)
-{
-// up_ramtron();
-// up_sdcard();
-
- return OK;
-}
diff --git a/nuttx/configs/vsn/src/sif.c b/nuttx/configs/vsn/src/sif.c
index cdd7967f9..9d5f8af6a 100644
--- a/nuttx/configs/vsn/src/sif.c
+++ b/nuttx/configs/vsn/src/sif.c
@@ -70,6 +70,7 @@
#include <nuttx/config.h>
#include <nuttx/fs.h>
+#include <nuttx/i2c.h>
#include <semaphore.h>
#include <stdio.h>
@@ -171,6 +172,9 @@ struct vsn_sif_s {
struct stm32_tim_dev_s * tim3; // Timer3 is used for PWM, and Analog RefTap
struct stm32_tim_dev_s * tim8; // Timer8 is used for Power Switch
+ struct i2c_dev_s * i2c1;
+ struct i2c_dev_s * i2c2;
+
sem_t exclusive_access;
};
@@ -226,7 +230,8 @@ void sif_gpio1_update(void)
case VSN_SIF_GPIO_OUTHIGH: val = GPIO_GP1_HIGH;break;
default: return;
}
- stm32_configgpio(val);
+ if (stm32_configgpio(val) == ERROR)
+ printf("Error updating1\n");
if ( stm32_gpioread(val) )
vsn_sif.gpio[0] |= VSN_SIF_GPIO_READ_MASK;
@@ -246,7 +251,8 @@ void sif_gpio2_update(void)
case VSN_SIF_GPIO_OUTHIGH: val = GPIO_GP2_HIGH;break;
default: return;
}
- stm32_configgpio(val);
+ if (stm32_configgpio(val) == ERROR)
+ printf("Error updating2\n");
if ( stm32_gpioread(val) )
vsn_sif.gpio[1] |= VSN_SIF_GPIO_READ_MASK;
@@ -289,30 +295,31 @@ int sif_anout_init(void)
vsn_sif.tim3 = stm32_tim_init(3);
vsn_sif.tim8 = stm32_tim_init(8);
+ vsn_sif.i2c1 = up_i2cinitialize(1);
+ vsn_sif.i2c2 = up_i2cinitialize(2);
+
if (!vsn_sif.tim3 || !vsn_sif.tim8) return ERROR;
// Use the TIM3 as PWM modulated analogue output
- STM32_TIM_SETCHANNEL(vsn_sif.tim3, GPIO_OUT_PWM_TIM3_CH4, STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
STM32_TIM_SETPERIOD(vsn_sif.tim3, 4096);
- STM32_TIM_SETCOMPARE(vsn_sif.tim3, GPIO_OUT_PWM_TIM3_CH4, 1024);
+ STM32_TIM_SETCOMPARE(vsn_sif.tim3, GPIO_OUT_PWM_TIM3_CH, 1024);
STM32_TIM_SETCLOCK(vsn_sif.tim3, 36e6);
STM32_TIM_SETMODE(vsn_sif.tim3, STM32_TIM_MODE_UP);
- stm32_configgpio(GPIO_OUT_HIZ);
+ //STM32_TIM_SETCHANNEL(vsn_sif.tim3, GPIO_OUT_PWM_TIM3_CH, STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
// Use the TIM8 to drive the upper power mosfet
STM32_TIM_SETISR(vsn_sif.tim8, sif_anout_isr, 0);
STM32_TIM_ENABLEINT(vsn_sif.tim8, 0);
-
- STM32_TIM_SETCHANNEL(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
+
STM32_TIM_SETPERIOD(vsn_sif.tim8, 4096);
- STM32_TIM_SETCOMPARE(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, 0);
+ STM32_TIM_SETCOMPARE(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH, 0);
STM32_TIM_SETCLOCK(vsn_sif.tim8, 36e6);
STM32_TIM_SETMODE(vsn_sif.tim8, STM32_TIM_MODE_UP);
- stm32_configgpio(GPIO_OUT_PWRPWM);
+ STM32_TIM_SETCHANNEL(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH, STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
return OK;
}
@@ -476,7 +483,7 @@ int sif_init(void)
int sif_main(int argc, char *argv[])
{
if (argc >= 2) {
- if (!strcmp(argv[1], "init")) {
+ if (!strcmp(argv[1], "init")) {
return sif_init();
}
else if (!strcmp(argv[1], "gpio") && argc == 4) {
@@ -489,7 +496,7 @@ int sif_main(int argc, char *argv[])
}
else if (!strcmp(argv[1], "pwr") && argc == 3) {
int val = atoi(argv[2]);
- STM32_TIM_SETCOMPARE(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, val);
+ STM32_TIM_SETCOMPARE(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH, val);
return 0;
}
else if (!strcmp(argv[1], "c")) {
diff --git a/nuttx/configs/vsn/src/vsn.h b/nuttx/configs/vsn/src/vsn.h
index 5d017b07a..c9058663e 100644
--- a/nuttx/configs/vsn/src/vsn.h
+++ b/nuttx/configs/vsn/src/vsn.h
@@ -51,6 +51,51 @@
/************************************************************************************
* PIN Definitions
************************************************************************************/
+
+ /* Board Peripheral Assignment
+ *
+ * RS232/Power connector:
+ * - USART1, is the default bootloader and console
+ *
+ * Sensor Connector:
+ * Digital:
+ * - GPIOs: PB10, PB11 (or even TIM2 CH3 and CH4)
+ * - USART3
+ * - I2C2
+ * Analog:
+ * - ADC1
+ * Supporting Analog Circuitry (not seen outside)
+ * - RefTap (TIM3_CH3)
+ * - Power PWM Out (TIM8_CH1 / TIM3_CH1)
+ * - Filtered Out (TIM3_CH4)
+ * (TIM8 could run at lower frequency, while TIM3 must run at highest possible)
+ * - Gain selection muxed with SDcard I/Os.
+ *
+ * Radio connector:
+ * - UART3 / UART4
+ * - SPI2
+ * - I2C1 (remapped pins vs. Expansion connector)
+ * - CAN
+ * - TIM4 CH[3:4]
+ *
+ * Expansion connector:
+ * - WakeUp Pin
+ * - System Wide Reset
+ * - SPI1 is wired to expansion port
+ * - I2C1
+ * - USART2 [Rx, Tx, CTS, RTS]
+ * - DAC [0:1]
+ * - ADC2 on pins [0:7]
+ * - TIM2 Channels [1:4]
+ * - TIM5 Channels [1:4]
+ *
+ * Onboard Components:
+ * - SPI3 has direct connection with FRAM
+ * - SDCard, conencts the microSD and shares the control lines with Sensor Interface
+ * to select Amplifier Gain
+ * - ADC3 is used also for power management (can be shared with ADC1 on sensor connector
+ * if not used)
+ */
/* LED */
@@ -94,7 +139,7 @@
#define GPIO_OUT_PWRON (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN6 |GPIO_OUTPUT_CLEAR)
#define GPIO_OUT_PWROFF (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN6 |GPIO_OUTPUT_SET)
#define GPIO_OUT_PWRPWM (GPIO_ALT |GPIO_CNF_AFPP |GPIO_MODE_10MHz|GPIO_PORTC|GPIO_PIN6 )
-#define GPIO_OUT_PWRPWM_TIM8_CH1P 1 /* TIM8.CH1 */
+#define GPIO_OUT_PWRPWM_TIM8_CH 1 /* TIM8.CH1 */
#define GPIO_OUT_HIZ (GPIO_INPUT |GPIO_CNF_INFLOAT |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
#define GPIO_OUT_PUP (GPIO_INPUT |GPIO_CNF_INPULLUP |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
@@ -103,7 +148,7 @@
#define GPIO_OUT_HIGH (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN1 |GPIO_OUTPUT_SET)
#define GPIO_OUT_AIN (GPIO_INPUT |GPIO_CNF_ANALOGIN |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
#define GPIO_OUT_PWM (GPIO_ALT |GPIO_CNF_AFPP |GPIO_MODE_10MHz|GPIO_PORTB|GPIO_PIN1 )
-#define GPIO_OUT_PWM_TIM3_CH4 4 /* TIM3.CH4 */
+#define GPIO_OUT_PWM_TIM3_CH 4 /* TIM3.CH4 */
/* Radio Connector */