Merged nuttx/nuttx into master

This commit is contained in:
Ken Fazzone 2016-06-06 14:15:35 -04:00
commit d982019be3
27 changed files with 536 additions and 312 deletions

View File

@ -11884,6 +11884,23 @@
in the OS and is simply a wrapper around the MDIOC_BULKERASE
IOCTL command. It used to be called (only) from
apps/system/flash_eraseall, but that has been removed because it
violated the OS/applicatin interface -- by calling flash_eraseall().
The old code can be found in the Obsoleted' repository (2016-06-03).
violated the OS/application interface -- by calling flash_eraseall().
The old code can be found in the Obsoleted' repository (and a revised
version can be found at apps/fsutils/flash_eraseall) (2016-06-03).
* arch/arm/src/lpc43xx: Fix errors in GPIO interrupt logic. From v01d
(phreakuencies) (2016-06-04)
* arch/arm/src/kl and lpc11xx: rename xyz_lowputc to up_putc. Remove
all references to up_lowputc, everywhere (2016-06-04).
* configs/stm32f103-minimum: Add minnsh configuration. From Alan
Carvalho de Assis (2016-06-04).
* arch/arm/src/stm32: Add the up_getc() function to STM32 in order to
support the minnsh configuration. From Alan Carvalho de Assis
(2016-06-04).
* arch/arm/src/stm32: STM32 Timer Driver: Change calculation of per-
timer pre-scaler value. Add support for all timers (2016-6-03)
* drivers/lcd: Correct conditional compilation in ST7565 driver. From
Pierre-noel Bouteville (2016-6-03)
* arch/arm/src/stm32: Correct conditional compilation in STM32 timer
capture logic. From Pierre-noel Bouteville (2016-6-03)
* arch/arm/src/efm32: Fix EFM32 FLASH conditional compilation. From
Pierre-noel Bouteville (2016-6-03)

12
TODO
View File

@ -1,4 +1,4 @@
NuttX TODO List (Last updated May 28, 2016)
NuttX TODO List (Last updated June 6, 2016)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This file summarizes known NuttX bugs, limitations, inconsistencies with
@ -23,7 +23,7 @@ nuttx/:
(11) Libraries (libc/, libm/)
(11) File system/Generic drivers (fs/, drivers/)
(8) Graphics subsystem (graphics/)
(1) Build system / Toolchains
(2) Build system / Toolchains
(3) Linux/Cywgin simulation (arch/sim)
(4) ARM (arch/arm/)
@ -1601,6 +1601,14 @@ o Build system
Status: Open
Priority: Low.
Title: NATIVE WINDOWS BUILD BROKEN
Description: The way that apps/ no generates Kmenu files depends on changes added
to apps/tools/mkkconfig.sh. Similar changes need to be made to
apps/tools/mkkconfig.bat to restore the Windows Native build.
Status: Open
Priority: Low, since I am not aware of anyone using the Windows Native build.
But, of course, very high if you want to use it.
o Other drivers (drivers/)
^^^^^^^^^^^^^^^^^^^^^^^^

View File

@ -2430,7 +2430,7 @@
# if defined(CONFIG_ARCH_CHIP_STM32F469A)
# define STM32_NETHERNET 0 /* No Ethernet MAC */
# elif defined(CONFIG_ARCH_CHIP_STM32F469I) || \
# defined(CONFIG_ARCH_CHIP_STM32F469B) || \
defined(CONFIG_ARCH_CHIP_STM32F469B) || \
defined(CONFIG_ARCH_CHIP_STM32F469N)
# define STM32_NETHERNET 1 /* 100/100 Ethernet MAC */
# endif

View File

@ -70,7 +70,7 @@ CMN_CSRCS += up_dumpnvic.c
endif
CHIP_ASRCS =
CHIP_CSRCS = kl_clockconfig.c kl_gpio.c kl_idle.c kl_irq.c kl_lowgetc.c
CHIP_CSRCS = kl_clockconfig.c kl_gpio.c kl_idle.c kl_irq.c kl_getc.c
CHIP_CSRCS += kl_lowputc.c kl_serial.c kl_start.c kl_cfmconfig.c
ifneq ($(CONFIG_SCHED_TICKLESS),y)

View File

@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/kl/kl_lowgetc.c
* arch/arm/src/kl/kl_getc.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Copyright (C) 2013, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -41,40 +41,23 @@
#include <stdint.h>
#include <arch/irq.h>
#include <arch/board/board.h>
#include "up_internal.h"
#include "up_arch.h"
#include "kl_config.h"
#include "kl_lowgetc.h"
#include "chip/kl_uart.h"
#include "kl_getc.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Select UART parameters for the selected console */
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
# define CONSOLE_BASE KL_UART0_BASE
# define CONSOLE_FREQ BOARD_CORECLK_FREQ
# define CONSOLE_BAUD CONFIG_UART0_BAUD
# define CONSOLE_BITS CONFIG_UART0_BITS
# define CONSOLE_PARITY CONFIG_UART0_PARITY
#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
# define CONSOLE_BASE KL_UART1_BASE
# define CONSOLE_FREQ BOARD_BUSCLK_FREQ
# define CONSOLE_BAUD CONFIG_UART1_BAUD
# define CONSOLE_BITS CONFIG_UART1_BITS
# define CONSOLE_PARITY CONFIG_UART1_PARITY
#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
# define CONSOLE_BASE KL_UART2_BASE
# define CONSOLE_FREQ BOARD_BUSCLK_FREQ
# define CONSOLE_BAUD CONFIG_UART2_BAUD
# define CONSOLE_BITS CONFIG_UART2_BITS
# define CONSOLE_PARITY CONFIG_UART2_PARITY
#endif
/****************************************************************************
@ -82,14 +65,18 @@
****************************************************************************/
/****************************************************************************
* Name: kl_lowgetc
* Name: up_getc
*
* Description:
* Input one byte from the serial console
*
* REVIST: If used with the serial driver enabled, then this could
* interfere with the serial driver operations. Serial interrupts should
* be disabled when this function executes in that case.
*
****************************************************************************/
int kl_lowgetc(void)
int up_getc(void)
{
uint8_t ch = 0;
@ -98,11 +85,11 @@ int kl_lowgetc(void)
* we have data in the buffer to read.
*/
while ((getreg8(CONSOLE_BASE+KL_UART_S1_OFFSET) & UART_S1_RDRF) == 0);
while ((getreg8(CONSOLE_BASE + KL_UART_S1_OFFSET) & UART_S1_RDRF) == 0);
/* Then read a character from the UART data register */
ch = getreg8(CONSOLE_BASE+KL_UART_D_OFFSET);
ch = getreg8(CONSOLE_BASE + KL_UART_D_OFFSET);
#endif
return (int)ch;

View File

@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/kl/kl_lowgetc.h
* arch/arm/src/kl/kl_getc.h
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Copyright (C) 2013, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -33,42 +33,16 @@
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_KL_KINETIS_LOWGETC_H
#define __ARCH_ARM_SRC_KL_KINETIS_LOWGETC_H
#ifndef __ARCH_ARM_SRC_KL_KINETIS_GETC_H
#define __ARCH_ARM_SRC_KL_KINETIS_GETC_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "kl_config.h"
#include "chip/kl_uart.h"
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
#ifdef HAVE_SERIAL_CONSOLE
int kl_lowgetc(void);
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_KL_KINETIS_LOWGETC_H */
#endif /* __ARCH_ARM_SRC_KL_KINETIS_GETC_H */

View File

@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/kl/kl_serial.c
*
* Copyright (C) 2013-2012 Gregory Nutt. All rights reserved.
* Copyright (C) 2013-2012, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -59,15 +59,14 @@
#include "kl_config.h"
#include "kl_lowputc.h"
#include "kl_lowgetc.h"
#include "chip.h"
#include "kl_gpio.h"
#include "chip/kl_uart.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Some sanity checks *******************************************************/
/* Is there at least one UART enabled and configured as a RS-232 device? */
@ -958,18 +957,4 @@ int up_putc(int ch)
return ch;
}
/****************************************************************************
* Name: up_getc
*
* Description:
* Provide priority, low-level access to support OS debug writes
*
****************************************************************************/
int up_getc(void)
{
/* Check for LF */
return kl_lowgetc();
}
#endif /* USE_SERIALDRIVER */

View File

@ -71,7 +71,7 @@ endif
CHIP_ASRCS =
CHIP_CSRCS = lpc11_clockconfig.c lpc11_gpio.c lpc11_i2c.c lpc11_idle.c
CHIP_CSRCS += lpc11_irq.c lpc11_lowputc.c lpc11_lowgetc.c lpc11_serial.c
CHIP_CSRCS += lpc11_irq.c lpc11_lowputc.c lpc11_getc.c lpc11_serial.c
CHIP_CSRCS += lpc11_spi.c lpc11_ssp.c lpc11_start.c
# Configuration-dependent LPC11xx files

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/lpc11/lpc11_lowgetc.c
* arch/arm/src/lpc11/lpc11_getc.c
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -41,42 +41,22 @@
#include <stdint.h>
#include <arch/irq.h>
#include <arch/board/board.h>
#include "up_internal.h"
#include "up_arch.h"
#include "chip/lpc11_syscon.h"
#include "chip/lpc11_uart.h"
#include "lpc11_gpio.h"
#include "lpc11_lowgetc.h"
#include "lpc11_serial.h"
#include "lpc11_getc.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Select UART parameters for the selected console */
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC11_UART0_BASE
# define CONSOLE_FREQ BOARD_CORECLK_FREQ
# define CONSOLE_BAUD CONFIG_UART0_BAUD
# define CONSOLE_BITS CONFIG_UART0_BITS
# define CONSOLE_PARITY CONFIG_UART0_PARITY
#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC11_UART1_BASE
# define CONSOLE_FREQ BOARD_BUSCLK_FREQ
# define CONSOLE_BAUD CONFIG_UART1_BAUD
# define CONSOLE_BITS CONFIG_UART1_BITS
# define CONSOLE_PARITY CONFIG_UART1_PARITY
#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC11_UART2_BASE
# define CONSOLE_FREQ BOARD_BUSCLK_FREQ
# define CONSOLE_BAUD CONFIG_UART2_BAUD
# define CONSOLE_BITS CONFIG_UART2_BITS
# define CONSOLE_PARITY CONFIG_UART2_PARITY
#endif
/****************************************************************************
@ -84,14 +64,18 @@
****************************************************************************/
/****************************************************************************
* Name: lpc11_lowgetc
* Name: up_getc
*
* Description:
* Input one byte from the serial console
* Input one byte from the serial console.
*
* REVIST: If used with the serial driver enabled, then this could
* interfere with the serial driver operations. Serial interrupts should
* be disabled when this function executes in that case.
*
****************************************************************************/
int lpc11_lowgetc(void)
int up_getc(void)
{
uint8_t ch = 0;

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lpc11/lpc11_lowgetc.h
* arch/arm/src/lpc11/lpc11_getc.h
*
* Copyright (C) 2015, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -33,8 +33,8 @@
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC11XX_LPC11_LOWGETC_H
#define __ARCH_ARM_SRC_LPC11XX_LPC11_LOWGETC_H
#ifndef __ARCH_ARM_SRC_LPC11XX_LPC11_GETC_H
#define __ARCH_ARM_SRC_LPC11XX_LPC11_GETC_H
/************************************************************************************
* Included Files
@ -42,33 +42,6 @@
#include <nuttx/config.h>
#include "lpc11_serial.h"
#include "chip/lpc11_uart.h"
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
#ifdef HAVE_SERIAL_CONSOLE
int lpc11_lowgetc(void);
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LPC11XX_LPC11_LOWGETC_H */
#endif /* __ARCH_ARM_SRC_LPC11XX_LPC11_GETC_H */

View File

@ -64,7 +64,6 @@
#include "chip.h"
#include "chip/lpc11_uart.h"
#include "lpc11_gpio.h"
#include "lpc11_lowgetc.h"
#include "lpc11_serial.h"
/****************************************************************************
@ -1041,19 +1040,4 @@ int up_putc(int ch)
return ch;
}
/****************************************************************************
* Name: up_getc
*
* Description:
* Provide priority, low-level access to support OS debug writes
*
****************************************************************************/
int up_getc(void)
{
/* Check for LF */
return lpc11_lowgetc();
}
#endif /* USE_SERIALDRIVER */

View File

@ -150,13 +150,6 @@ endchoice # LPC43XX Boot Configuration
menu "LPC43xx Peripheral Support"
config LPC43_GPIO_IRQ
bool "GPIO interrupt support"
default n
---help---
Enable support for GPIO interrupts
config LPC43_ADC0
bool "ADC0"
default n
@ -321,6 +314,12 @@ config LPC43_WWDT
endmenu # LPC43xx Peripheral Support
config LPC43_GPIO_IRQ
bool "GPIO interrupt support"
default n
---help---
Enable support for GPIO interrupts
if LPC43_ETHERNET
menu "Ethernet MAC configuration"

View File

@ -180,7 +180,10 @@ int lpc43_gpioint_pinconfig(uint16_t gpiocfg)
unsigned int pin = ((gpiocfg & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT);
unsigned int pinint = ((gpiocfg & GPIO_PININT_MASK) >> GPIO_PININT_SHIFT);
uint32_t bitmask = (1 << pinint);
uint32_t regval;
uint32_t pinsel;
uint32_t isel;
uint32_t einr;
uint32_t einf;
DEBUGASSERT(port < NUM_GPIO_PORTS && pin < NUM_GPIO_PINS && GPIO_IS_PININT(gpiocfg));
@ -197,66 +200,69 @@ int lpc43_gpioint_pinconfig(uint16_t gpiocfg)
if (pinint < 4)
{
regval = getreg32(LPC43_SCU_PINTSEL0);
regval &= ~SCU_PINTSEL0_MASK(pinint);
regval |= ((pin << SCU_PINTSEL0_INTPIN_SHIFT(pinint)) |
pinsel = getreg32(LPC43_SCU_PINTSEL0);
pinsel &= ~SCU_PINTSEL0_MASK(pinint);
pinsel |= ((pin << SCU_PINTSEL0_INTPIN_SHIFT(pinint)) |
(port << SCU_PINTSEL0_PORTSEL_SHIFT(pinint)));
putreg32(regval, LPC43_SCU_PINTSEL0);
putreg32(pinsel, LPC43_SCU_PINTSEL0);
}
else
{
regval = getreg32(LPC43_SCU_PINTSEL1);
regval &= ~SCU_PINTSEL1_MASK(pinint);
regval |= ((pin << SCU_PINTSEL1_INTPIN_SHIFT(pinint)) |
pinsel = getreg32(LPC43_SCU_PINTSEL1);
pinsel &= ~SCU_PINTSEL1_MASK(pinint);
pinsel |= ((pin << SCU_PINTSEL1_INTPIN_SHIFT(pinint)) |
(port << SCU_PINTSEL1_PORTSEL_SHIFT(pinint)));
putreg32(regval, LPC43_SCU_PINTSEL1);
putreg32(pinsel, LPC43_SCU_PINTSEL1);
}
/* Set level or edge sensitive */
regval = getreg32(LPC43_GPIOINT_ISEL);
if (GPIO_IS_LEVEL(gpiocfg))
{
regval |= bitmask;
}
else
{
regval &= ~bitmask;
}
putreg32(regval, LPC43_GPIOINT_ISEL);
/* Configure the active high level or rising edge
/* Configure the active level or rising/falling edge
*
* TODO: this works for edge sensitive, but not level sensitive, active
* level is only controlled in IENF.
* ISEL
* 0 = Edge sensitive
* 1 = Level sensitive
* EINR 0-7:
* 0 = Disable rising edge or level interrupt.
* 1 = Enable rising edge or level interrupt.
* EINF 0-7:
* 0 = Disable falling edge interrupt or set active interrupt level
* LOW.
* 1 = Enable falling edge interrupt enabled or set active interrupt
* level HIGH
*/
regval = getreg32(LPC43_GPIOINT_IENR);
if (GPIO_IS_ACTIVE_HI(gpiocfg))
isel = getreg32(LPC43_GPIOINT_ISEL) & ~bitmask;
einr = getreg32(LPC43_GPIOINT_IENR) & ~bitmask;
einf = getreg32(LPC43_GPIOINT_IENF) & ~bitmask;
switch (gpiocfg & GPIO_INT_MASK)
{
regval |= bitmask;
}
else
{
regval &= ~bitmask;
case GPIO_INT_LEVEL_HI:
einf |= bitmask; /* Enable active level HI */
case GPIO_INT_LEVEL_LOW:
isel |= bitmask; /* Level sensitive */
einr |= bitmask; /* Enable level interrupt */
break;
case GPIO_INT_EDGE_RISING:
einr |= bitmask; /* Enable rising edge interrupt */
break;
case GPIO_INT_EDGE_BOTH:
einr |= bitmask; /* Enable rising edge interrupt */
case GPIO_INT_EDGE_FALLING:
einf |= bitmask; /* Enable falling edge interrupt */
break;
/* Default is edge sensitive but with both edges disabled. */
default:
break;
}
putreg32(regval, LPC43_GPIOINT_IENR);
putreg32(isel, LPC43_GPIOINT_ISEL);
putreg32(einr, LPC43_GPIOINT_IENR);
putreg32(einf, LPC43_GPIOINT_IENF);
/* Configure the active high low or falling edge */
regval = getreg32(LPC43_GPIOINT_IENF);
if (GPIO_IS_ACTIVE_LOW(gpiocfg))
{
regval |= bitmask;
}
else
{
regval &= ~bitmask;
}
putreg32(regval, LPC43_GPIOINT_IENF);
return OK;
}

View File

@ -110,7 +110,7 @@ CHIP_ASRCS =
CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c
CHIP_CSRCS += stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c
CHIP_CSRCS += stm32_irq.c stm32_dma.c stm32_lowputc.c stm32_lowgetc.c
CHIP_CSRCS += stm32_irq.c stm32_dma.c stm32_lowputc.c stm32_getc.c
CHIP_CSRCS += stm32_serial.c stm32_spi.c stm32_sdio.c stm32_tim.c
CHIP_CSRCS += stm32_waste.c stm32_ccm.c stm32_uid.c stm32_capture.c

View File

@ -92,7 +92,7 @@
#include "stm32_usbdev.h"
#include "stm32_wdg.h"
#include "stm32_lowputc.h"
#include "stm32_lowgetc.h"
#include "stm32_getc.h"
#include "stm32_eth.h"
#endif /* __ARCH_ARM_SRC_STM32_STM32_H */

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_lowgetc.c
* arch/arm/src/stm32/stm32_getc.c
*
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -89,6 +89,10 @@
* Description:
* Read one byte from the serial console
*
* REVIST: If used with the serial driver enabled, then this could
* interfere with the serial driver operations. Serial interrupts should
* be disabled when this function executes in that case.
*
****************************************************************************/
int up_getc(void)

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_lowgetc.h
* arch/arm/src/stm32/stm32_getc.h
*
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -33,8 +33,8 @@
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_STM32_STM32_LOWGETC_H
#define __ARCH_ARM_SRC_STM32_STM32_LOWGETC_H
#ifndef __ARCH_ARM_SRC_STM32_STM32_GETC_H
#define __ARCH_ARM_SRC_STM32_STM32_GETC_H
/************************************************************************************
* Included Files
@ -44,4 +44,4 @@
#include "chip.h"
#endif /* __ARCH_ARM_SRC_STM32_STM32_LOWGETC_H */
#endif /* __ARCH_ARM_SRC_STM32_STM32_GETC_H */

View File

@ -166,8 +166,8 @@ enum stm32_chanmode_e
struct stm32_pwmchan_s
{
uint8_t channel; /* Timer output channel: {1,..4} */
uint32_t pincfg; /* Output pin configuration */
uint8_t channel; /* Timer output channel: {1,..4} */
uint32_t pincfg; /* Output pin configuration */
enum stm32_chanmode_e mode;
};
@ -176,21 +176,23 @@ struct stm32_pwmchan_s
struct stm32_pwmtimer_s
{
FAR const struct pwm_ops_s *ops; /* PWM operations */
uint8_t timid; /* Timer ID {1,...,17} */
struct stm32_pwmchan_s channels[PWM_NCHANNELS];
uint8_t timtype; /* See the TIMTYPE_* definitions */
enum stm32_timmode_e mode;
uint8_t timid; /* Timer ID {1,...,17} */
struct stm32_pwmchan_s channels[PWM_NCHANNELS];
uint8_t timtype; /* See the TIMTYPE_* definitions */
enum stm32_timmode_e mode;
#ifdef CONFIG_PWM_PULSECOUNT
uint8_t irq; /* Timer update IRQ */
uint8_t prev; /* The previous value of the RCR (pre-loaded) */
uint8_t curr; /* The current value of the RCR (pre-loaded) */
uint32_t count; /* Remaining pluse count */
uint8_t irq; /* Timer update IRQ */
uint8_t prev; /* The previous value of the RCR (pre-loaded) */
uint8_t curr; /* The current value of the RCR (pre-loaded) */
uint32_t count; /* Remaining pluse count */
#else
uint32_t frequency; /* Current frequency setting */
#endif
uint32_t base; /* The base address of the timer */
uint32_t pclk; /* The frequency of the peripheral clock
uint32_t base; /* The base address of the timer */
uint32_t pclk; /* The frequency of the peripheral clock
* that drives the timer module. */
#ifdef CONFIG_PWM_PULSECOUNT
FAR void *handle; /* Handle used for upper-half callback */
FAR void *handle; /* Handle used for upper-half callback */
#endif
};
@ -758,7 +760,7 @@ static struct stm32_pwmtimer_s g_pwm13dev =
.irq = STM32_IRQ_TIM13,
#endif
.base = STM32_TIM13_BASE,
.pclk = STM32_APB1_TIM13_CLKIN,
.pclk = STM32_APB1_TIM13_CLKIN,
};
#endif
@ -1066,14 +1068,14 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
DEBUGASSERT(priv != NULL && info != NULL);
#if defined(CONFIG_PWM_MULTICHAN)
pwmvdbg("TIM%d frequency: %d\n",
pwmvdbg("TIM%u frequency: %u\n",
priv->timid, info->frequency);
#elif defined(CONFIG_PWM_PULSECOUNT)
pwmvdbg("TIM%d channel: %d frequency: %d duty: %08x count: %d\n",
pwmvdbg("TIM%u channel: %u frequency: %u duty: %08x count: %u\n",
priv->timid, priv->channel, info->frequency,
info->duty, info->count);
#else
pwmvdbg("TIM%d channel: %d frequency: %d duty: %08x\n",
pwmvdbg("TIM%u channel: %u frequency: %u duty: %08x\n",
priv->timid, priv->channel, info->frequency, info->duty);
#endif
@ -1144,7 +1146,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
reload = 65535;
}
pwmvdbg("TIM%d PCLK: %d frequency: %d TIMCLK: %d prescaler: %d reload: %d\n",
pwmvdbg("TIM%u PCLK: %u frequency: %u TIMCLK: %u prescaler: %u reload: %u\n",
priv->timid, priv->pclk, info->frequency, timclk, prescaler, reload);
/* Set up the timer CR1 register:
@ -1207,7 +1209,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
break;
default:
pwmdbg("No such timer mode: %d\n", (int)priv->mode);
pwmdbg("No such timer mode: %u\n", (unsigned int)priv->mode);
return -EINVAL;
}
}
@ -1334,7 +1336,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
if (j >= PWM_NCHANNELS)
{
pwmdbg("No such channel: %d\n", channel);
pwmdbg("No such channel: %u\n", channel);
return -EINVAL;
}
#else
@ -1350,7 +1352,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
ccr = b16toi(duty * reload + b16HALF);
pwmvdbg("ccr: %d\n", ccr);
pwmvdbg("ccr: %u\n", ccr);
switch (mode)
{
@ -1385,7 +1387,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
#endif
default:
pwmdbg("No such mode: %d\n", (int)mode);
pwmdbg("No such mode: %u\n", (unsigned int)mode);
return -EINVAL;
}
@ -1492,7 +1494,7 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
break;
default:
pwmdbg("No such channel: %d\n", channel);
pwmdbg("No such channel: %u\n", channel);
return -EINVAL;
}
}
@ -1634,6 +1636,89 @@ static int pwm_timer(FAR struct stm32_pwmtimer_s *priv,
return OK;
}
#ifndef CONFIG_PWM_PULSECOUNT
/****************************************************************************
* Name: pwm_update_duty
*
* Description:
* Try to change only channel duty.
*
* Input parameters:
* priv - A reference to the lower half PWM driver state structure
* channel - Channel to by updated
* duty - New duty.
*
* Returned Value:
* Zero on success; a negated errno value on failure
*
****************************************************************************/
static int pwm_update_duty(FAR struct stm32_pwmtimer_s *priv, uint8_t channel,
ub16_t duty)
{
/* Register offset */
int ccr_offset;
/* Calculated values */
uint32_t reload;
uint32_t ccr;
DEBUGASSERT(priv != NULL);
pwmvdbg("TIM%u channel: %u duty: %08x\n",
priv->timid, channel, duty);
#ifndef CONFIG_PWM_MULTICHAN
DEBUGASSERT(channel == priv->channels[0].channel);
DEBUGASSERT(chan->duty >= 0 && chan->duty < uitoub16(100));
#endif
/* Get the reload values */
reload = pwm_getreg(priv, STM32_GTIM_ARR_OFFSET);
/* Duty cycle:
*
* duty cycle = ccr / reload (fractional value)
*/
ccr = b16toi(duty * reload + b16HALF);
pwmvdbg("ccr: %u\n", ccr);
switch (channel)
{
case 1: /* Register offset for Channel 1 */
ccr_offset = STM32_GTIM_CCR1_OFFSET;
break;
case 2: /* Register offset for Channel 2 */
ccr_offset = STM32_GTIM_CCR2_OFFSET;
break;
case 3: /* Register offset for Channel 3 */
ccr_offset = STM32_GTIM_CCR3_OFFSET;
break;
case 4: /* Register offset for Channel 4 */
ccr_offset = STM32_GTIM_CCR4_OFFSET;
break;
default:
pwmdbg("No such channel: %u\n", channel);
return -EINVAL;
}
/* Set the duty cycle by writing to the CCR register for this channel */
pwm_putreg(priv, ccr_offset, (uint16_t)ccr);
return OK;
}
#endif
/****************************************************************************
* Name: pwm_interrupt
*
@ -1710,7 +1795,7 @@ static int pwm_interrupt(struct stm32_pwmtimer_s *priv)
/* Now all of the time critical stuff is done so we can do some debug output */
pwmllvdbg("Update interrupt SR: %04x prev: %d curr: %d count: %d\n",
pwmllvdbg("Update interrupt SR: %04x prev: %u curr: %u count: %u\n",
regval, priv->prev, priv->curr, priv->count);
return OK;
@ -1945,7 +2030,7 @@ static int pwm_setup(FAR struct pwm_lowerhalf_s *dev)
uint32_t pincfg;
int i;
pwmvdbg("TIM%d\n", priv->timid);
pwmvdbg("TIM%u\n", priv->timid);
pwm_dumpregs(priv, "Initially");
/* Enable APB1/2 clocking for timer. */
@ -1993,7 +2078,7 @@ static int pwm_shutdown(FAR struct pwm_lowerhalf_s *dev)
uint32_t pincfg;
int i;
pwmvdbg("TIM%d\n", priv->timid);
pwmvdbg("TIM%u\n", priv->timid);
/* Make sure that the output has been stopped */
@ -2064,7 +2149,7 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev,
if (priv->timtype != TIMTYPE_ADVANCED)
{
pwmdbg("ERROR: TIM%d cannot support pulse count: %d\n",
pwmdbg("ERROR: TIM%u cannot support pulse count: %u\n",
priv->timid, info->count);
return -EPERM;
}
@ -2082,8 +2167,42 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev,
static int pwm_start(FAR struct pwm_lowerhalf_s *dev,
FAR const struct pwm_info_s *info)
{
int ret = OK;
FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev;
return pwm_timer(priv, info);
#ifndef CONFIG_PWM_PULSECOUNT
/* if frequency has not changed we just update duty */
if (info->frequency == priv->frequency)
{
#ifdef CONFIG_PWM_MULTICHAN
int i;
for (i = 0; ret == OK && i < CONFIG_PWM_NCHANNELS; i++)
{
ret = pwm_update_duty(priv,info->channels[i].channel,
info->channels[i].duty);
}
#else
ret = pwm_update_duty(priv,priv->channels[0].channel,info->duty);
#endif
}
else
#endif
{
ret = pwm_timer(priv, info);
#ifndef CONFIG_PWM_PULSECOUNT
/* Save current frequency */
if (ret == OK)
{
priv->frequency = info->frequency;
}
#endif
}
return ret;
}
#endif
@ -2114,7 +2233,7 @@ static int pwm_stop(FAR struct pwm_lowerhalf_s *dev)
uint32_t regval;
irqstate_t flags;
pwmvdbg("TIM%d\n", priv->timid);
pwmvdbg("TIM%u\n", priv->timid);
/* Disable interrupts momentary to stop any ongoing timer processing and
* to prevent any concurrent access to the reset register.
@ -2122,6 +2241,10 @@ static int pwm_stop(FAR struct pwm_lowerhalf_s *dev)
flags = enter_critical_section();
/* Stopped so frequency is zero */
priv->frequency = 0;
/* Disable further interrupts and stop the timer */
pwm_putreg(priv, STM32_GTIM_DIER_OFFSET, 0);
@ -2265,7 +2388,7 @@ static int pwm_ioctl(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg
/* There are no platform-specific ioctl commands */
pwmvdbg("TIM%d\n", priv->timid);
pwmvdbg("TIM%u\n", priv->timid);
#endif
return -ENOTTY;
}
@ -2295,7 +2418,7 @@ FAR struct pwm_lowerhalf_s *stm32_pwminitialize(int timer)
{
FAR struct stm32_pwmtimer_s *lower;
pwmvdbg("TIM%d\n", timer);
pwmvdbg("TIM%u\n", timer);
switch (timer)
{

View File

@ -76,6 +76,7 @@ CONFIG_ARCH="arm"
# CONFIG_ARCH_CHIP_DM320 is not set
# CONFIG_ARCH_CHIP_EFM32 is not set
# CONFIG_ARCH_CHIP_IMX1 is not set
# CONFIG_ARCH_CHIP_IMX6 is not set
# CONFIG_ARCH_CHIP_KINETIS is not set
# CONFIG_ARCH_CHIP_KL is not set
# CONFIG_ARCH_CHIP_LM is not set
@ -94,6 +95,7 @@ CONFIG_ARCH_CHIP_SAM34=y
# CONFIG_ARCH_CHIP_SAMV7 is not set
# CONFIG_ARCH_CHIP_STM32 is not set
# CONFIG_ARCH_CHIP_STM32F7 is not set
# CONFIG_ARCH_CHIP_STM32L4 is not set
# CONFIG_ARCH_CHIP_STR71X is not set
# CONFIG_ARCH_CHIP_TMS570 is not set
# CONFIG_ARCH_CHIP_MOXART is not set
@ -115,12 +117,15 @@ CONFIG_ARCH_CORTEXM3=y
# CONFIG_ARCH_CORTEXR7F is not set
CONFIG_ARCH_FAMILY="armv7-m"
CONFIG_ARCH_CHIP="sam34"
# CONFIG_ARM_TOOLCHAIN_IAR is not set
CONFIG_ARM_TOOLCHAIN_GNU=y
# CONFIG_ARMV7M_USEBASEPRI is not set
CONFIG_ARCH_HAVE_CMNVECTOR=y
# CONFIG_ARMV7M_CMNVECTOR is not set
# CONFIG_ARMV7M_LAZYFPU is not set
# CONFIG_ARCH_HAVE_FPU is not set
# CONFIG_ARCH_HAVE_DPFPU is not set
# CONFIG_ARCH_HAVE_TRUSTZONE is not set
CONFIG_ARM_HAVE_MPU_UNIFIED=y
# CONFIG_ARM_MPU is not set
@ -131,6 +136,7 @@ CONFIG_ARM_HAVE_MPU_UNIFIED=y
# CONFIG_ARMV7M_HAVE_DCACHE is not set
# CONFIG_ARMV7M_HAVE_ITCM is not set
# CONFIG_ARMV7M_HAVE_DTCM is not set
# CONFIG_ARMV7M_TOOLCHAIN_IARL is not set
CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y
# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set
@ -335,7 +341,7 @@ CONFIG_NSH_MMCSDMINOR=0
CONFIG_LIB_BOARDCTL=y
# CONFIG_BOARDCTL_RESET is not set
# CONFIG_BOARDCTL_UNIQUEID is not set
# CONFIG_BOARDCTL_TSCTEST is not set
CONFIG_BOARDCTL_TSCTEST=y
# CONFIG_BOARDCTL_ADCTEST is not set
# CONFIG_BOARDCTL_PWMTEST is not set
# CONFIG_BOARDCTL_GRAPHICS is not set
@ -508,10 +514,14 @@ CONFIG_ADS7843E_THRESHY=39
# CONFIG_DJOYSTICK is not set
# CONFIG_AJOYSTICK is not set
# CONFIG_IOEXPANDER is not set
#
# LCD Driver Support
#
CONFIG_LCD=y
#
# Common LCD Settings
# Common Graphic LCD Settings
#
# CONFIG_LCD_CONSOLE is not set
# CONFIG_LCD_NOGETRUN is not set
@ -540,11 +550,7 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_LCD_RLANDSCAPE is not set
# CONFIG_LCD_ILI9341 is not set
# CONFIG_LCD_RA8875 is not set
#
# Alphanumeric/Segment LCD Devices
#
# CONFIG_LCD_LCD1602 is not set
# CONFIG_SLCD is not set
#
# LED Support
@ -586,10 +592,6 @@ CONFIG_UART0_SERIALDRIVER=y
# CONFIG_USART7_SERIALDRIVER is not set
# CONFIG_USART8_SERIALDRIVER is not set
# CONFIG_OTHER_UART_SERIALDRIVER is not set
#
# USART Configuration
#
CONFIG_MCU_SERIAL=y
CONFIG_STANDARD_SERIAL=y
# CONFIG_SERIAL_IFLOWCONTROL is not set
@ -675,6 +677,7 @@ CONFIG_NX_LCDDRIVER=y
CONFIG_NX_NPLANES=1
CONFIG_NX_BGCOLOR=0x0
CONFIG_NX_WRITEONLY=y
# CONFIG_NX_UPDATE is not set
#
# Supported Pixel Depths
@ -838,6 +841,8 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_ARCH_ROMGETC is not set
# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
CONFIG_ARCH_HAVE_TLS=y
# CONFIG_TLS is not set
# CONFIG_LIBC_NETDB is not set
#
@ -956,6 +961,7 @@ CONFIG_CXX_NEWLONG=y
# Network Utilities
#
# CONFIG_NETUTILS_CODECS is not set
# CONFIG_NETUTILS_ESP8266 is not set
# CONFIG_NETUTILS_FTPC is not set
# CONFIG_NETUTILS_JSON is not set
# CONFIG_NETUTILS_SMTP is not set
@ -1078,6 +1084,7 @@ CONFIG_NXWIDGETS_LISTENERSTACK=1596
# NXWidget Configuration
#
CONFIG_NXWIDGETS_BPP=16
# CONFIG_NXWIDGETS_GREYSCALE is not set
CONFIG_NXWIDGETS_SIZEOFCHAR=1
#

View File

@ -80,6 +80,7 @@ CONFIG_ARCH="arm"
# CONFIG_ARCH_CHIP_DM320 is not set
# CONFIG_ARCH_CHIP_EFM32 is not set
# CONFIG_ARCH_CHIP_IMX1 is not set
# CONFIG_ARCH_CHIP_IMX6 is not set
# CONFIG_ARCH_CHIP_KINETIS is not set
# CONFIG_ARCH_CHIP_KL is not set
# CONFIG_ARCH_CHIP_LM is not set
@ -98,6 +99,7 @@ CONFIG_ARCH_CHIP_SAMA5=y
# CONFIG_ARCH_CHIP_SAMV7 is not set
# CONFIG_ARCH_CHIP_STM32 is not set
# CONFIG_ARCH_CHIP_STM32F7 is not set
# CONFIG_ARCH_CHIP_STM32L4 is not set
# CONFIG_ARCH_CHIP_STR71X is not set
# CONFIG_ARCH_CHIP_TMS570 is not set
# CONFIG_ARCH_CHIP_MOXART is not set
@ -119,9 +121,12 @@ CONFIG_ARCH_CORTEXA5=y
# CONFIG_ARCH_CORTEXR7F is not set
CONFIG_ARCH_FAMILY="armv7-a"
CONFIG_ARCH_CHIP="sama5"
# CONFIG_ARM_TOOLCHAIN_IAR is not set
# CONFIG_ARM_TOOLCHAIN_GNU is not set
CONFIG_ARCH_HAVE_FPU=y
# CONFIG_ARCH_HAVE_DPFPU is not set
CONFIG_ARCH_FPU=y
# CONFIG_ARCH_HAVE_TRUSTZONE is not set
# CONFIG_ARM_HAVE_MPU_UNIFIED is not set
CONFIG_ARCH_HAVE_LOWVECTORS=y
CONFIG_ARCH_LOWVECTORS=y
@ -131,6 +136,8 @@ CONFIG_ARCH_LOWVECTORS=y
# ARMv7-A Configuration Options
#
# CONFIG_ARMV7A_HAVE_GICv2 is not set
# CONFIG_ARMV7A_HAVE_GTM is not set
# CONFIG_ARMV7A_HAVE_PTM is not set
# CONFIG_ARMV7A_HAVE_L2CC is not set
# CONFIG_ARMV7A_HAVE_L2CC_PL310 is not set
# CONFIG_ARMV7A_TOOLCHAIN_BUILDROOT is not set
@ -182,7 +189,6 @@ CONFIG_SAMA5_HAVE_PIOE=y
# CONFIG_SAMA5_HAVE_TC is not set
# CONFIG_SAMA5_HAVE_TC1 is not set
# CONFIG_SAMA5_HAVE_TC2 is not set
# CONFIG_ARCH_HAVE_TRUSTZONE is not set
# CONFIG_SAMA5_HAVE_TWI3 is not set
# CONFIG_SAMA5_HAVE_VDEC is not set
# CONFIG_SAMA5_FLEXCOM is not set
@ -437,7 +443,7 @@ CONFIG_SAMA5D3xEK_TSD_DEVMINOR=0
# CONFIG_SAMA5D3xEK_SLOWCLOCK is not set
CONFIG_LIB_BOARDCTL=y
# CONFIG_BOARDCTL_UNIQUEID is not set
# CONFIG_BOARDCTL_TSCTEST is not set
CONFIG_BOARDCTL_TSCTEST=y
# CONFIG_BOARDCTL_ADCTEST is not set
# CONFIG_BOARDCTL_PWMTEST is not set
# CONFIG_BOARDCTL_GRAPHICS is not set
@ -603,7 +609,12 @@ CONFIG_INPUT=y
# CONFIG_DJOYSTICK is not set
# CONFIG_AJOYSTICK is not set
# CONFIG_IOEXPANDER is not set
#
# LCD Driver Support
#
# CONFIG_LCD is not set
# CONFIG_SLCD is not set
#
# LED Support
@ -645,10 +656,6 @@ CONFIG_USART1_SERIALDRIVER=y
# CONFIG_USART7_SERIALDRIVER is not set
# CONFIG_USART8_SERIALDRIVER is not set
# CONFIG_OTHER_UART_SERIALDRIVER is not set
#
# USART Configuration
#
CONFIG_MCU_SERIAL=y
CONFIG_STANDARD_SERIAL=y
# CONFIG_SERIAL_IFLOWCONTROL is not set
@ -743,6 +750,7 @@ CONFIG_NX_NPLANES=1
CONFIG_NX_BGCOLOR=0x95fa
# CONFIG_NX_ANTIALIASING is not set
# CONFIG_NX_WRITEONLY is not set
# CONFIG_NX_UPDATE is not set
#
# Supported Pixel Depths
@ -907,6 +915,8 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_ARCH_ROMGETC is not set
# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
CONFIG_ARCH_HAVE_TLS=y
# CONFIG_TLS is not set
# CONFIG_LIBC_NETDB is not set
# CONFIG_NETDB_HOSTFILE is not set
@ -945,6 +955,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
#
# Examples
#
# CONFIG_EXAMPLES_ADC is not set
# CONFIG_EXAMPLES_CHAT is not set
# CONFIG_EXAMPLES_CONFIGDATA is not set
# CONFIG_EXAMPLES_CPUHOG is not set
@ -1031,6 +1042,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
# Network Utilities
#
# CONFIG_NETUTILS_CODECS is not set
# CONFIG_NETUTILS_ESP8266 is not set
# CONFIG_NETUTILS_FTPC is not set
# CONFIG_NETUTILS_JSON is not set
# CONFIG_NETUTILS_SMTP is not set
@ -1155,6 +1167,7 @@ CONFIG_NXWIDGETS_LISTENERSTACK=1596
# NXWidget Configuration
#
CONFIG_NXWIDGETS_BPP=16
# CONFIG_NXWIDGETS_GREYSCALE is not set
CONFIG_NXWIDGETS_SIZEOFCHAR=1
#

View File

@ -264,6 +264,13 @@ CONFIG_SAMV7_USART0=y
# CONFIG_SAMV7_USART2 is not set
# CONFIG_SAMV7_WDT is not set
# CONFIG_SAMV7_RSWDT is not set
# CONFIG_SAMV7_JTAG_DISABLE is not set
CONFIG_SAMV7_JTAG_FULL_ENABLE=y
# CONFIG_SAMV7_JTAG_FULL_SW_ENABLE is not set
# CONFIG_SAMV7_JTAG_SW_ENABLE is not set
# CONFIG_SAMV7_ERASE_DISABLE is not set
CONFIG_SAMV7_ERASE_ENABLE=y
# CONFIG_SAMV7_SYSTEMRESET is not set
CONFIG_SAMV7_GPIO_IRQ=y
CONFIG_SAMV7_GPIOA_IRQ=y
CONFIG_SAMV7_GPIOB_IRQ=y
@ -549,10 +556,14 @@ CONFIG_MXT_THRESHY=8
# CONFIG_DJOYSTICK is not set
# CONFIG_AJOYSTICK is not set
# CONFIG_IOEXPANDER is not set
#
# LCD Driver Support
#
CONFIG_LCD=y
#
# Common LCD Settings
# Common Graphic LCD Settings
#
# CONFIG_LCD_CONSOLE is not set
CONFIG_LCD_NOGETRUN=y
@ -581,11 +592,7 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_LCD_RLANDSCAPE is not set
# CONFIG_LCD_ILI9341 is not set
# CONFIG_LCD_RA8875 is not set
#
# Alphanumeric/Segment LCD Devices
#
# CONFIG_LCD_LCD1602 is not set
# CONFIG_SLCD is not set
#
# LED Support
@ -639,10 +646,12 @@ CONFIG_AT25_SPIFREQUENCY=20000000
# CONFIG_MTD_AT45DB is not set
# CONFIG_MTD_M25P is not set
# CONFIG_MTD_S25FL1 is not set
# CONFIG_MTD_N25QXXX is not set
# CONFIG_MTD_SMART is not set
# CONFIG_MTD_RAMTRON is not set
# CONFIG_MTD_SST25 is not set
# CONFIG_MTD_SST25XX is not set
# CONFIG_MTD_SST26 is not set
# CONFIG_MTD_SST39FV is not set
# CONFIG_MTD_W25 is not set
# CONFIG_EEPROM is not set
@ -676,10 +685,6 @@ CONFIG_USART0_SERIALDRIVER=y
# CONFIG_USART7_SERIALDRIVER is not set
# CONFIG_USART8_SERIALDRIVER is not set
# CONFIG_OTHER_UART_SERIALDRIVER is not set
#
# USART Configuration
#
CONFIG_MCU_SERIAL=y
CONFIG_STANDARD_SERIAL=y
# CONFIG_SERIAL_IFLOWCONTROL is not set
@ -773,6 +778,7 @@ CONFIG_NX_LCDDRIVER=y
CONFIG_NX_NPLANES=1
CONFIG_NX_BGCOLOR=0x95fa
CONFIG_NX_WRITEONLY=y
# CONFIG_NX_UPDATE is not set
#
# Supported Pixel Depths
@ -1036,6 +1042,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
#
# File System Utilities
#
# CONFIG_FSUTILS_FLASH_ERASEALL is not set
# CONFIG_FSUTILS_INIFILE is not set
# CONFIG_FSUTILS_PASSWD is not set
@ -1067,6 +1074,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
# Network Utilities
#
# CONFIG_NETUTILS_CODECS is not set
# CONFIG_NETUTILS_ESP8266 is not set
# CONFIG_NETUTILS_FTPC is not set
# CONFIG_NETUTILS_JSON is not set
# CONFIG_NETUTILS_SMTP is not set
@ -1191,6 +1199,7 @@ CONFIG_NXWIDGETS_LISTENERSTACK=2048
# NXWidget Configuration
#
CONFIG_NXWIDGETS_BPP=16
# CONFIG_NXWIDGETS_GREYSCALE is not set
CONFIG_NXWIDGETS_SIZEOFCHAR=1
#
@ -1362,6 +1371,7 @@ CONFIG_NXWM_HEXCALCULATOR_FONTID=5
# CONFIG_SYSTEM_FREE is not set
# CONFIG_SYSTEM_CLE is not set
# CONFIG_SYSTEM_CUTERM is not set
# CONFIG_SYSTEM_FLASH_ERASEALL is not set
# CONFIG_SYSTEM_INSTALL is not set
# CONFIG_SYSTEM_HEX2BIN is not set
CONFIG_SYSTEM_I2CTOOL=y

View File

@ -417,6 +417,10 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y
# CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG is not set
# CONFIG_STM32_FORCEPOWER is not set
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
#
# Timer Configuration
#
# CONFIG_STM32_TIM1_CAP is not set
# CONFIG_STM32_TIM3_CAP is not set
# CONFIG_STM32_TIM4_CAP is not set
@ -428,9 +432,17 @@ CONFIG_STM32_SERIALDRIVER=y
#
# U[S]ART Configuration
#
#
# U[S]ART Device Configuration
#
CONFIG_STM32_USART2_SERIALDRIVER=y
# CONFIG_STM32_USART2_1WIREDRIVER is not set
# CONFIG_USART2_RS485 is not set
#
# Serial Driver Configuration
#
# CONFIG_SERIAL_DISABLE_REORDERING is not set
# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
# CONFIG_STM32_USART_BREAKS is not set
@ -579,7 +591,7 @@ CONFIG_NSH_MMCSDMINOR=0
CONFIG_LIB_BOARDCTL=y
# CONFIG_BOARDCTL_RESET is not set
# CONFIG_BOARDCTL_UNIQUEID is not set
# CONFIG_BOARDCTL_TSCTEST is not set
CONFIG_BOARDCTL_TSCTEST=y
# CONFIG_BOARDCTL_ADCTEST is not set
# CONFIG_BOARDCTL_PWMTEST is not set
# CONFIG_BOARDCTL_GRAPHICS is not set
@ -739,7 +751,7 @@ CONFIG_INPUT=y
# CONFIG_INPUT_TSC2007 is not set
CONFIG_INPUT_ADS7843E=y
# CONFIG_ADS7843E_MULTIPLE is not set
CONFIG_ADS7843E_SPIDEV=0
CONFIG_ADS7843E_SPIDEV=3
CONFIG_ADS7843E_DEVMINOR=0
CONFIG_ADS7843E_SPIMODE=0
CONFIG_ADS7843E_FREQUENCY=100000
@ -752,10 +764,14 @@ CONFIG_ADS7843E_THRESHY=51
# CONFIG_DJOYSTICK is not set
# CONFIG_AJOYSTICK is not set
# CONFIG_IOEXPANDER is not set
#
# LCD Driver Support
#
CONFIG_LCD=y
#
# Common LCD Settings
# Common Graphic LCD Settings
#
# CONFIG_LCD_CONSOLE is not set
CONFIG_LCD_NOGETRUN=y
@ -787,11 +803,7 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_LCD_RLANDSCAPE is not set
# CONFIG_LCD_ILI9341 is not set
# CONFIG_LCD_RA8875 is not set
#
# Alphanumeric/Segment LCD Devices
#
# CONFIG_LCD_LCD1602 is not set
# CONFIG_SLCD is not set
#
# LED Support
@ -1649,7 +1661,7 @@ CONFIG_NXWM_TOUCHSCREEN_DEVINIT=y
CONFIG_NXWM_TOUCHSCREEN_DEVNO=0
CONFIG_NXWM_TOUCHSCREEN_DEVPATH="/dev/input0"
CONFIG_NXWM_TOUCHSCREEN_SIGNO=5
CONFIG_NXWM_TOUCHSCREEN_LISTENERPRIO=100
CONFIG_NXWM_TOUCHSCREEN_LISTENERPRIO=101
CONFIG_NXWM_TOUCHSCREEN_LISTENERSTACK=1596
#

View File

@ -434,6 +434,10 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y
# CONFIG_STM32_FORCEPOWER is not set
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
# CONFIG_STM32_FSMC_SRAM is not set
#
# Timer Configuration
#
# CONFIG_STM32_TIM1_CAP is not set
# CONFIG_STM32_TIM3_CAP is not set
# CONFIG_STM32_TIM4_CAP is not set
@ -451,9 +455,17 @@ CONFIG_STM32_SERIALDRIVER=y
#
# U[S]ART Configuration
#
#
# U[S]ART Device Configuration
#
CONFIG_STM32_USART3_SERIALDRIVER=y
# CONFIG_STM32_USART3_1WIREDRIVER is not set
# CONFIG_USART3_RS485 is not set
#
# Serial Driver Configuration
#
# CONFIG_SERIAL_DISABLE_REORDERING is not set
# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
# CONFIG_STM32_USART_BREAKS is not set
@ -593,7 +605,14 @@ CONFIG_NSH_MMCSDSLOTNO=0
# CONFIG_STM32_ILI9325_DISABLE is not set
CONFIG_STM3220G_LCD=y
CONFIG_LCD_RDSHIFT=5
# CONFIG_LIB_BOARDCTL is not set
CONFIG_LIB_BOARDCTL=y
# CONFIG_BOARDCTL_RESET is not set
# CONFIG_BOARDCTL_UNIQUEID is not set
CONFIG_BOARDCTL_TSCTEST=y
# CONFIG_BOARDCTL_ADCTEST is not set
# CONFIG_BOARDCTL_PWMTEST is not set
# CONFIG_BOARDCTL_GRAPHICS is not set
# CONFIG_BOARDCTL_IOCTL is not set
#
# RTOS Features
@ -766,10 +785,14 @@ CONFIG_STMPE811_TEMP_DISABLE=y
# CONFIG_DJOYSTICK is not set
# CONFIG_AJOYSTICK is not set
# CONFIG_IOEXPANDER is not set
#
# LCD Driver Support
#
CONFIG_LCD=y
#
# Common LCD Settings
# Common Graphic LCD Settings
#
# CONFIG_LCD_CONSOLE is not set
CONFIG_LCD_NOGETRUN=y
@ -797,12 +820,7 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_LCD_RLANDSCAPE is not set
# CONFIG_LCD_ILI9341 is not set
# CONFIG_LCD_RA8875 is not set
#
# Alphanumeric/Segment LCD Devices
#
# CONFIG_LCD_LCD1602 is not set
# CONFIG_LCD_BACKPACK is not set
# CONFIG_SLCD is not set
#
# LED Support
@ -1353,6 +1371,7 @@ CONFIG_HAVE_CXXINITIALIZE=y
# CONFIG_EXAMPLES_UDPBLASTER is not set
# CONFIG_EXAMPLES_DISCOVER is not set
# CONFIG_EXAMPLES_WEBSERVER is not set
# CONFIG_EXAMPLES_USBSERIAL is not set
# CONFIG_EXAMPLES_USBTERM is not set
# CONFIG_EXAMPLES_WATCHDOG is not set
# CONFIG_EXAMPLES_WGET is not set
@ -1546,6 +1565,7 @@ CONFIG_NXWIDGETS=y
# NX Server/Device Configuration
#
CONFIG_NXWIDGETS_FLICKERFREE=y
# CONFIG_NXWIDGETS_EXTERNINIT is not set
CONFIG_NXWIDGETS_DEVNO=0
CONFIG_NXWIDGET_SERVERINIT=y
CONFIG_NXWIDGETS_SERVERPRIO=110

View File

@ -444,6 +444,10 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
# CONFIG_STM32_CCMEXCLUDE is not set
# CONFIG_STM32_FSMC_SRAM is not set
#
# Timer Configuration
#
# CONFIG_STM32_TIM1_CAP is not set
# CONFIG_STM32_TIM2_CAP is not set
# CONFIG_STM32_TIM3_CAP is not set
@ -462,9 +466,17 @@ CONFIG_STM32_SERIALDRIVER=y
#
# U[S]ART Configuration
#
#
# U[S]ART Device Configuration
#
CONFIG_STM32_USART3_SERIALDRIVER=y
# CONFIG_STM32_USART3_1WIREDRIVER is not set
# CONFIG_USART3_RS485 is not set
#
# Serial Driver Configuration
#
# CONFIG_SERIAL_DISABLE_REORDERING is not set
# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
# CONFIG_STM32_USART_BREAKS is not set
@ -586,7 +598,14 @@ CONFIG_STM3240G_LCD_RDSHIFT=5
# CONFIG_STM3240G_ILI9325_DISABLE is not set
CONFIG_STM3240G_BOARDINIT_PRIO=196
CONFIG_STM3240G_BOARDINIT_STACK=2048
# CONFIG_LIB_BOARDCTL is not set
CONFIG_LIB_BOARDCTL=y
# CONFIG_BOARDCTL_RESET is not set
# CONFIG_BOARDCTL_UNIQUEID is not set
CONFIG_BOARDCTL_TSCTEST=y
# CONFIG_BOARDCTL_ADCTEST is not set
# CONFIG_BOARDCTL_PWMTEST is not set
# CONFIG_BOARDCTL_GRAPHICS is not set
# CONFIG_BOARDCTL_IOCTL is not set
#
# RTOS Features
@ -761,10 +780,14 @@ CONFIG_STMPE811_TEMP_DISABLE=y
# CONFIG_DJOYSTICK is not set
# CONFIG_AJOYSTICK is not set
# CONFIG_IOEXPANDER is not set
#
# LCD Driver Support
#
CONFIG_LCD=y
#
# Common LCD Settings
# Common Graphic LCD Settings
#
# CONFIG_LCD_CONSOLE is not set
CONFIG_LCD_NOGETRUN=y
@ -792,12 +815,7 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_LCD_RLANDSCAPE is not set
# CONFIG_LCD_ILI9341 is not set
# CONFIG_LCD_RA8875 is not set
#
# Alphanumeric/Segment LCD Devices
#
# CONFIG_LCD_LCD1602 is not set
# CONFIG_LCD_BACKPACK is not set
# CONFIG_SLCD is not set
#
# LED Support
@ -1176,6 +1194,7 @@ CONFIG_CXX_NEWLONG=y
# CONFIG_EXAMPLES_TIFF is not set
# CONFIG_EXAMPLES_TOUCHSCREEN is not set
# CONFIG_EXAMPLES_WEBSERVER is not set
# CONFIG_EXAMPLES_USBSERIAL is not set
# CONFIG_EXAMPLES_USBTERM is not set
# CONFIG_EXAMPLES_WATCHDOG is not set
@ -1232,6 +1251,7 @@ CONFIG_NXWIDGETS=y
# NX Server/Device Configuration
#
CONFIG_NXWIDGETS_FLICKERFREE=y
# CONFIG_NXWIDGETS_EXTERNINIT is not set
CONFIG_NXWIDGETS_DEVNO=0
CONFIG_NXWIDGETS_CLIENTPRIO=100
CONFIG_NXWIDGETS_LISTENERPRIO=100

View File

@ -437,6 +437,10 @@ CONFIG_STM32_JTAG_FULL_ENABLE=y
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
# CONFIG_STM32_CCMEXCLUDE is not set
# CONFIG_STM32_FSMC_SRAM is not set
#
# Timer Configuration
#
# CONFIG_STM32_TIM1_CAP is not set
# CONFIG_STM32_TIM2_CAP is not set
# CONFIG_STM32_TIM3_CAP is not set
@ -455,9 +459,17 @@ CONFIG_STM32_SERIALDRIVER=y
#
# U[S]ART Configuration
#
#
# U[S]ART Device Configuration
#
CONFIG_STM32_USART3_SERIALDRIVER=y
# CONFIG_STM32_USART3_1WIREDRIVER is not set
# CONFIG_USART3_RS485 is not set
#
# Serial Driver Configuration
#
# CONFIG_SERIAL_DISABLE_REORDERING is not set
# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
# CONFIG_STM32_USART_BREAKS is not set
@ -596,7 +608,14 @@ CONFIG_STM3240G_LCD=y
CONFIG_STM3240G_LCD_RDSHIFT=5
# CONFIG_STM3240G_ILI9320_DISABLE is not set
# CONFIG_STM3240G_ILI9325_DISABLE is not set
# CONFIG_LIB_BOARDCTL is not set
CONFIG_LIB_BOARDCTL=y
# CONFIG_BOARDCTL_RESET is not set
# CONFIG_BOARDCTL_UNIQUEID is not set
CONFIG_BOARDCTL_TSCTEST=y
# CONFIG_BOARDCTL_ADCTEST is not set
# CONFIG_BOARDCTL_PWMTEST is not set
# CONFIG_BOARDCTL_GRAPHICS is not set
# CONFIG_BOARDCTL_IOCTL is not set
#
# RTOS Features
@ -769,10 +788,14 @@ CONFIG_STMPE811_TEMP_DISABLE=y
# CONFIG_DJOYSTICK is not set
# CONFIG_AJOYSTICK is not set
# CONFIG_IOEXPANDER is not set
#
# LCD Driver Support
#
CONFIG_LCD=y
#
# Common LCD Settings
# Common Graphic LCD Settings
#
# CONFIG_LCD_CONSOLE is not set
CONFIG_LCD_NOGETRUN=y
@ -800,12 +823,7 @@ CONFIG_LCD_LANDSCAPE=y
# CONFIG_LCD_RLANDSCAPE is not set
# CONFIG_LCD_ILI9341 is not set
# CONFIG_LCD_RA8875 is not set
#
# Alphanumeric/Segment LCD Devices
#
# CONFIG_LCD_LCD1602 is not set
# CONFIG_LCD_BACKPACK is not set
# CONFIG_SLCD is not set
#
# LED Support
@ -1356,6 +1374,7 @@ CONFIG_HAVE_CXXINITIALIZE=y
# CONFIG_EXAMPLES_UDPBLASTER is not set
# CONFIG_EXAMPLES_DISCOVER is not set
# CONFIG_EXAMPLES_WEBSERVER is not set
# CONFIG_EXAMPLES_USBSERIAL is not set
# CONFIG_EXAMPLES_USBTERM is not set
# CONFIG_EXAMPLES_WATCHDOG is not set
# CONFIG_EXAMPLES_WGET is not set
@ -1551,6 +1570,7 @@ CONFIG_NXWIDGETS=y
# NX Server/Device Configuration
#
CONFIG_NXWIDGETS_FLICKERFREE=y
# CONFIG_NXWIDGETS_EXTERNINIT is not set
CONFIG_NXWIDGETS_DEVNO=0
CONFIG_NXWIDGET_SERVERINIT=y
CONFIG_NXWIDGETS_SERVERPRIO=110

View File

@ -265,6 +265,19 @@ struct boardioc_usbdev_ctrl_s
};
#endif /* CONFIG_BOARDCTL_USBDEVCTRL */
/****************************************************************************
* Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
@ -299,5 +312,10 @@ struct boardioc_usbdev_ctrl_s
int boardctl(unsigned int cmd, uintptr_t arg);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* CONFIG_LIB_BOARDCTL */
#endif /* __INCLUDE_SYS_BOARDCTL_H */

View File

@ -34,22 +34,28 @@
WD=$PWD
nuttx=$WD/../nuttx
TOOLSDIR=$nuttx/tools
UNLINK=$TOOLSDIR/unlink.sh
progname=$0
host=linux
wenv=cygwin
sizet=uint
APPSDIR=../apps
NXWDIR=../NxWidgets
unset testfile
function showusage {
echo ""
echo "USAGE: $progname [-w|l] [-c|n] [-s] <testlist-file>"
echo "USAGE: $progname [-w|l] [-c|n] [-s] [-a <appsdir>] [-n <nxdir>] <testlist-file>"
echo " $progname -h"
echo ""
echo "Where:"
echo " -w|l selects Windows (w) or Linux (l). Default: Linux"
echo " -c|n selects Windows native (n) or Cygwin (c). Default Cygwin"
echo " -s Use C++ unsigned long size_t in new operator. Default unsigned int"
echo " -a <appsdir> provides the relative path to the apps/ directory. Default ../apps"
echo " -n <nxdir> provides the relative path to the NxWidgets/ directory. Default ../NxWidgets"
echo " -h will show this help test and terminate"
echo " <testlist-file> selects the list of configurations to test. No default"
echo ""
@ -78,6 +84,14 @@ while [ ! -z "$1" ]; do
-s )
sizet=long
;;
-a )
shift
APPSDIR="$1"
;;
-n )
shift
NXWDIR="$1"
;;
-h )
showusage
;;
@ -196,11 +210,45 @@ function configure {
make olddefconfig 1>/dev/null 2>&1
}
# Build the NxWidgets libraries
function nxbuild {
if [ -e $APPSDIR/external ]; then
$UNLINK $APPSDIR/external
fi
unset nxconfig
if [ -d $NXWDIR ]; then
nxconfig=`grep CONFIG_NXWM=y $nuttx/.config`
fi
if [ ! -z "$nxconfig" ]; then
echo " Building NxWidgets..."
echo "------------------------------------------------------------------------------------"
cd $nuttx/$NXTOOLS || { echo "Failed to CD to $NXTOOLS"; exit 1; }
./install.sh $nuttx/$APPSDIR nxwm 1>/dev/null
make -C $nuttx/$APPSDIR/external TOPDIR=$nuttx APPDIR=$nuttx/$APPSDIR TOPDIR=$nuttx clean 1>/dev/null
cd $nuttx || { echo "Failed to CD to $nuttx"; exit 1; }
make -i context 1>/dev/null
cd $nuttx/$NXWIDGETSDIR || { echo "Failed to CD to $NXWIDGETSDIR"; exit 1; }
make -i TOPDIR=$nuttx clean 1>/dev/null
make -i TOPDIR=$nuttx 1>/dev/null
cd $nuttx/$NXWMDIR || { echo "Failed to CD to $NXWMDIR"; exit 1; }
make -i TOPDIR=$nuttx clean 1>/dev/null
make -i TOPDIR=$nuttx 1>/dev/null
fi
}
# Perform the next build
function build {
cd $nuttx || { echo "ERROR: failed to CD to $nuttx"; exit 1; }
echo " Building..."
echo " Building NuttX..."
echo "------------------------------------------------------------------------------------"
make -i 1>/dev/null
}
@ -211,12 +259,24 @@ function dotest {
echo "------------------------------------------------------------------------------------"
distclean
configure
nxbuild
build
}
# Perform the build test for each entry in the test list file
export APPSDIR=../apps
if [ ! -d $APPSDIR ]; then
export "ERROR: No directory found at $APPSDIR"
exit 1
fi
export APPSDIR
if [ -d $NXWDIR ]; then
NXWIDGETSDIR=$NXWDIR/libnxwidgets
NXWMDIR=$NXWDIR/nxwm
NXTOOLS=$NXWDIR/tools
fi
# Shouldn't have to do this