Browse Source

nxphlite-v3:Using termios and HW flow control

Using PX4 contrib of termios and HW flow control in NuttX
   Kinetis.

   Removed stubs and updated defconfig.
sbg
David Sidrane 8 years ago committed by Daniel Agar
parent
commit
2b853ea00e
  1. 28
      nuttx-configs/nxphlite-v3/nsh/defconfig
  2. 25
      src/drivers/boards/nxphlite-v3/nxphlite_init.c

28
nuttx-configs/nxphlite-v3/nsh/defconfig

@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y @@ -28,6 +28,7 @@ CONFIG_BUILD_FLAT=y
# CONFIG_MOTOROLA_SREC is not set
CONFIG_RAW_BINARY=y
# CONFIG_UBOOT_UIMAGE is not set
# CONFIG_DFU_BINARY is not set
#
# Customize Header Files
@ -238,6 +239,8 @@ CONFIG_KINETIS_FTM0=y @@ -238,6 +239,8 @@ CONFIG_KINETIS_FTM0=y
# CONFIG_KINETIS_FTM1 is not set
CONFIG_KINETIS_FTM2=y
CONFIG_KINETIS_FTM3=y
# CONFIG_KINETIS_TPM1 is not set
# CONFIG_KINETIS_TPM2 is not set
CONFIG_KINETIS_LPTIMER=y
CONFIG_KINETIS_RTC=y
# CONFIG_KINETIS_EWM is not set
@ -279,6 +282,14 @@ CONFIG_KINETIS_PORTEINTS=y @@ -279,6 +282,14 @@ CONFIG_KINETIS_PORTEINTS=y
#
# Kinetis UART Configuration
#
#
# Serial Driver Configuration
#
CONFIG_KINETIS_UART_BREAKS=y
CONFIG_KINETIS_UART_EXTEDED_BREAK=y
CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y
# CONFIG_KINETIS_UART_SINGLEWIRE is not set
CONFIG_KINETIS_UARTFIFOS=y
#
@ -297,6 +308,7 @@ CONFIG_LPUART0_SERIAL_CONSOLE=y @@ -297,6 +308,7 @@ CONFIG_LPUART0_SERIAL_CONSOLE=y
# CONFIG_NO_LPUART_SERIAL_CONSOLE is not set
CONFIG_KINETIS_MERGE_TTY=y
CONFIG_KINETS_LPUART_LOWEST=y
CONFIG_SERIAL_TERMIOS=y
#
# Architecture Options
@ -317,6 +329,7 @@ CONFIG_ARCH_HAVE_MPU=y @@ -317,6 +329,7 @@ CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARCH_HAVE_EXTCLK is not set
# CONFIG_ARCH_HAVE_POWEROFF is not set
CONFIG_ARCH_HAVE_RESET=y
# CONFIG_ARCH_HAVE_RTC_SUBSECONDS is not set
# CONFIG_ARCH_USE_MPU is not set
# CONFIG_ARCH_IRQPRIO is not set
CONFIG_ARCH_STACKDUMP=y
@ -525,6 +538,11 @@ CONFIG_DEV_NULL=y @@ -525,6 +538,11 @@ CONFIG_DEV_NULL=y
#
# Buffering
#
#
# Common I/O Buffer Support
#
# CONFIG_DRIVERS_IOB is not set
# CONFIG_DRVR_WRITEBUFFER is not set
# CONFIG_DRVR_READAHEAD is not set
# CONFIG_RAMDISK is not set
@ -651,7 +669,7 @@ CONFIG_SERIAL_OFLOWCONTROL=y @@ -651,7 +669,7 @@ CONFIG_SERIAL_OFLOWCONTROL=y
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_IFLOWCONTROL_LOWER_WATERMARK=10
CONFIG_SERIAL_IFLOWCONTROL_UPPER_WATERMARK=90
# CONFIG_ARCH_HAVE_SERIAL_TERMIOS is not set
CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
# CONFIG_UART0_SERIAL_CONSOLE is not set
# CONFIG_UART1_SERIAL_CONSOLE is not set
# CONFIG_UART2_SERIAL_CONSOLE is not set
@ -681,8 +699,8 @@ CONFIG_UART1_BAUD=115200 @@ -681,8 +699,8 @@ CONFIG_UART1_BAUD=115200
CONFIG_UART1_BITS=8
CONFIG_UART1_PARITY=0
CONFIG_UART1_2STOP=0
CONFIG_UART1_IFLOWCONTROL=y
CONFIG_UART1_OFLOWCONTROL=y
# CONFIG_UART1_IFLOWCONTROL is not set
# CONFIG_UART1_OFLOWCONTROL is not set
# CONFIG_UART1_DMA is not set
#
@ -707,8 +725,8 @@ CONFIG_UART4_BAUD=57600 @@ -707,8 +725,8 @@ CONFIG_UART4_BAUD=57600
CONFIG_UART4_BITS=8
CONFIG_UART4_PARITY=0
CONFIG_UART4_2STOP=0
# CONFIG_UART4_IFLOWCONTROL is not set
# CONFIG_UART4_OFLOWCONTROL is not set
CONFIG_UART4_IFLOWCONTROL=y
CONFIG_UART4_OFLOWCONTROL=y
# CONFIG_UART4_DMA is not set
# CONFIG_PSEUDOTERM is not set
CONFIG_USBDEV=y

25
src/drivers/boards/nxphlite-v3/nxphlite_init.c

@ -147,7 +147,7 @@ int board_read_VBUS_state(void) @@ -147,7 +147,7 @@ int board_read_VBUS_state(void)
*
* Description:
* All boards my optionally provide this API to invert the Serial RC input.
* This is needed on SoCs that support the notion RXINV or TXINV as apposed to
* This is needed on SoCs that support the notion RXINV or TXINV as opposed to
* and external XOR controlled by a GPIO
*
************************************************************************************/
@ -275,15 +275,7 @@ kinetis_boardinitialize(void) @@ -275,15 +275,7 @@ kinetis_boardinitialize(void)
nxphlite_spidev_initialize();
}
// FIXME:STUBS
#include <termios.h>
int cfsetspeed(FAR struct termios *termiosp, speed_t speed);
int cfsetspeed(FAR struct termios *termiosp, speed_t speed)
{
return 0;
}
//FIXME: Stubs -----v
int up_rtc_getdatetime(FAR struct tm *tp);
int up_rtc_getdatetime(FAR struct tm *tp)
{
@ -308,18 +300,7 @@ static void kinetis_serial_dma_poll(void) @@ -308,18 +300,7 @@ static void kinetis_serial_dma_poll(void)
{
// todo:Stubbed
}
struct termios;
int tcgetattr(int fd, FAR struct termios *termiosp);
int tcsetattr(int fd, int options, FAR const struct termios *termiosp);
int tcgetattr(int fd, FAR struct termios *termiosp)
{
return -1;
}
int tcsetattr(int fd, int options, FAR const struct termios *termiosp)
{
return -1;
}
//FIXME: Stubs -----v
/****************************************************************************

Loading…
Cancel
Save