Squashed commit of the following:

arch/arm/src/max326xx/max32660/max32660_serial.c:  Add a mostly commented out serial driver.  With this, we can accomplish a complete build with many warnings for 'Missing logic'
    configs/max32660-evsys/src/max326_button.c:  Add support for the on-board button.
    arch/arm/src/max326xx:  Add a mostly empty max326_lowputc.c file mostly so that we can get further in the compilation.  Fixed several more compile errors revealed by this.
    arch/arm/src/max326xx:  Add peripheral clock control header file.
This commit is contained in:
Gregory Nutt 2018-11-19 10:47:28 -06:00
parent f9fc2131b0
commit 1d2a69539b
22 changed files with 1640 additions and 128 deletions

View File

@ -61,7 +61,7 @@
#define MAX326_IRQ_INTERVAL (MAX326_IRQ_EXTINT + 5) /* 5 RTC Interval Alarm */
#define MAX326_IRQ_RTCOVF (MAX326_IRQ_EXTINT + 6) /* 6 RTC Counter Overflow */
#define MAX326_IRQ_PMU (MAX326_IRQ_EXTINT + 7) /* 7 PMU */
#define MAX326_IRQ_USB (MAX326_IRQ_EXTINT + 8) /* 8-9 Reserved */
/* 8-9 Reserved */
#define MAX326_IRQ_MMA (MAX326_IRQ_EXTINT + 10) /* 10 MMA */
#define MAX326_IRQ_WDT0 (MAX326_IRQ_EXTINT + 11) /* 11 Watchdog 0 Timeout Interrupt */
/* 12-14 Watchdog 0 Pre-window Interrupt */
@ -73,10 +73,10 @@
#define MAX326_IRQ_TMR1_1 (MAX326_IRQ_EXTINT + 25) /* 25 Timer 1 Interrupt 1 */
#define MAX326_IRQ_TMR2_0 (MAX326_IRQ_EXTINT + 26) /* 26 Timer 2 Interrupt 0 */
#define MAX326_IRQ_TMR2_1 (MAX326_IRQ_EXTINT + 27) /* 27 Timer 2 Interrupt 1 */
#define MAX326_IRQ_TMR3_0 (MAX326_IRQ_EXTINT + 28) /* 28-33 Reserved */
/* 28-33 Reserved */
#define MAX326_IRQ_UART0 (MAX326_IRQ_EXTINT + 34) /* 34 UART 0 */
#define MAX326_IRQ_UART1 (MAX326_IRQ_EXTINT + 35) /* 34 UART 1 */
#define MAX326_IRQ_UART2 (MAX326_IRQ_EXTINT + 36) /* 36-38 Reserved */
#define MAX326_IRQ_UART1 (MAX326_IRQ_EXTINT + 35) /* 35 UART 1 */
/* 36-38 Reserved */
#define MAX326_IRQ_I2CM0 (MAX326_IRQ_EXTINT + 39) /* 39 I2C0 Master */
#define MAX326_IRQ_I2CM1 (MAX326_IRQ_EXTINT + 40) /* 40 I2C1 Master */
/* 41-42 Reserved */

View File

@ -118,14 +118,14 @@ void arm_timer_initialize(void)
/* Set the SysTick interrupt to the default priority */
regval = getreg32(NVIC_SYSH12_15_PRIORITY);
regval = getreg32(NVIC_SYSH12_15_PRIORITY);
regval &= ~NVIC_SYSH_PRIORITY_PR15_MASK;
regval |= (NVIC_SYSH_PRIORITY_DEFAULT << NVIC_SYSH_PRIORITY_PR15_SHIFT);
putreg32(regval, NVIC_SYSH12_15_PRIORITY);
/* Make sure that the SYSTICK clock source is set to use the LPC17xx CCLK */
regval = getreg32(NVIC_SYSTICK_CTRL);
regval = getreg32(NVIC_SYSTICK_CTRL);
regval |= NVIC_SYSTICK_CTRL_CLKSOURCE;
putreg32(regval, NVIC_SYSTICK_CTRL);

View File

@ -311,7 +311,7 @@ static const struct uart_config_s g_console_config=
************************************************************************************/
/************************************************************************************
* Name: lp54_setbaud
* Name: lpc54_setbaud
*
* Description:
* Configure the USART BAUD.
@ -319,7 +319,7 @@ static const struct uart_config_s g_console_config=
************************************************************************************/
#ifdef HAVE_USART_DEVICE
static void lp54_setbaud(uintptr_t base, FAR const struct uart_config_s *config)
static void lpc54_setbaud(uintptr_t base, FAR const struct uart_config_s *config)
{
uint32_t bestdiff = (uint32_t)-1;
uint32_t bestosr = 15;
@ -693,7 +693,7 @@ void lpc54_usart_configure(uintptr_t base, FAR const struct uart_config_s *confi
/* Configure baud */
lp54_setbaud(base, config);
lpc54_setbaud(base, config);
/* Configure RX and TX FIFOs */
/* Empty and enable FIFOs */

View File

@ -550,7 +550,7 @@ static xcpt_t lpc54_capture(FAR struct watchdog_lowerhalf_s *lower,
}
/****************************************************************************
* Name: lp54_ioctl
* Name: lpc54_ioctl
*
* Description:
* Any ioctl commands that are not recognized by the "upper-half" driver

View File

@ -47,6 +47,9 @@
* Pre-processor Definitions
************************************************************************************/
#define MAX326_UART_TXFIFO_DEPTH 32 /* 32 bytes */
#define MAX326_UART_RXFIFO_DEPTH 32 /* 32 bytes */
/* Register Offsets *****************************************************************/
#define MAX326_UART_CTRL0_OFFSET 0x0000 /* UART Control 0 Register */

View File

@ -575,11 +575,8 @@ int up_prioritize_irq(int irq, int priority)
return;
}
regval = getreg32(regaddr);
shift = ((irq & 3) << 3);
regval &= ~(0xff << shift);
regval |= (priority << shift);
putreg32(regval, regaddr);
modifyreg32(regaddr, 0xff << shift, priority << shift);
max326_dumpnvic("prioritize", irq);
return OK;

View File

@ -57,6 +57,21 @@
* Pre-processor Definitions
****************************************************************************/
/* Memory Map:
*
* 0x0000:0000 - Beginning of FLASH. Address of exception vectors.
* 0x0003:ffff - End of flash (assuming 256KB of FLASH)
* 0x2000:0000 - Start of SRAM and start of .data (_sdata)
* - End of .data (_edata) abd start of .bss (_sbss)
* - End of .bss (_ebss) and bottom of idle stack
* - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack,
* start of heap
* 0x2001:7fff - End of SRAM and end of heap (assuming 96KB of SRAM)
*/
#define IDLE_STACK ((uint32_t)&_ebss + CONFIG_IDLETHREAD_STACKSIZE - 4)
#define HEAP_BASE ((uint32_t)&_ebss + CONFIG_IDLETHREAD_STACKSIZE)
/****************************************************************************
* Name: showprogress
*
@ -71,6 +86,12 @@
# define showprogress(c)
#endif
/****************************************************************************
* Public Data
****************************************************************************/
const uint32_t g_idle_topstack = IDLE_STACK;
/****************************************************************************
* Private Functions
****************************************************************************/

View File

@ -114,24 +114,6 @@ void arm_timer_initialize(void)
{
uint32_t regval;
/* May be clocked internally by the system clock or the SysTick function
* clock. Set the SysTick clock divider in the SYSCON_SYSTICK register.
* Since this function is called early after reset, it is safe to assume
* that the SysTick is disabled and so that no reset or halt actions are
* necessary.
*/
regval = (SYSCON_SYSTICKCLKDIV_DIV(BOARD_SYSTICKCLKDIV) |
SYSCON_SYSTICKCLKDIV_REQFLAG);
putreg32(regval, MAX326_SYSCON_SYSTICKCLKDIV);
/* The request flag will be cleared when the divider change is complete */
while ((getreg32(MAX326_SYSCON_SYSTICKCLKDIV) &
SYSCON_SYSTICKCLKDIV_REQFLAG) != 0)
{
}
/* Make sure that the SYSTICK clock source is set to use the CPU clock
* (CLKSOURCE==1).
*

View File

@ -39,6 +39,8 @@
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <debug.h>
#include <nuttx/irq.h>
@ -132,7 +134,7 @@ void max326_altfunc(uint32_t pinmask, bool af0, bool af1)
regval &= ~pinmask;
}
putreg32(regval, MAX326_GPIO0_AF0SEL)
putreg32(regval, MAX326_GPIO0_AF0SEL);
regval = getreg32(MAX326_GPIO0_AF1SEL);
if (af1)
@ -144,7 +146,7 @@ void max326_altfunc(uint32_t pinmask, bool af0, bool af1)
regval &= ~pinmask;
}
putreg32(regval, MAX326_GPIO0_AF1SEL)
putreg32(regval, MAX326_GPIO0_AF1SEL);
}
/****************************************************************************
@ -156,7 +158,7 @@ void max326_altfunc(uint32_t pinmask, bool af0, bool af1)
*
****************************************************************************/
void max326_default(uint32_t pinmask);
void max326_default(uint32_t pinmask)
{
uint32_t regval;
@ -164,33 +166,33 @@ void max326_default(uint32_t pinmask);
regval = getreg32(MAX326_GPIO0_INTEN); /* Pin interrupt disabled triggered */
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_INTEN)
putreg32(regval, MAX326_GPIO0_INTEN);
regval = getreg32(MAX326_GPIO0_INTMODE); /* Level triggered */
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_INTMODE)
putreg32(regval, MAX326_GPIO0_INTMODE);
regval = getreg32(MAX326_GPIO0_INTPOL); /* Input low triggers */
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_INTPOL)
putreg32(regval, MAX326_GPIO0_INTPOL);
regval = getreg32(MAX326_GPIO0_INTDUALEDGE); /* Disable dual edge */
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_INTDUALEDGE)
putreg32(regval, MAX326_GPIO0_INTDUALEDGE);
regval = getreg32(MAX326_GPIO0_WAKEEN); /* Disable wakeup */
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_WAKEEN)
putreg32(regval, MAX326_GPIO0_WAKEEN);
/* Make the pin an input */
regval = getreg32(MAX326_GPIO0_OUTEN); /* Disable output drivers */
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_OUTEN)
putreg32(regval, MAX326_GPIO0_OUTEN);
regval = getreg32(MAX326_GPIO0_OUT); /* Set the output value to zero */
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_OUT)
putreg32(regval, MAX326_GPIO0_OUT);
/* Set alternate functions to I/O */
@ -200,31 +202,31 @@ void max326_default(uint32_t pinmask);
regval = getreg32(MAX326_GPIO0_DS0SEL);
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_DS0SEL)
putreg32(regval, MAX326_GPIO0_DS0SEL);
regval = getreg32(MAX326_GPIO0_DS1SEL);
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_DS1SEL)
putreg32(regval, MAX326_GPIO0_DS1SEL);
/* Disable pull up and pull down */
regval = getreg32(MAX326_GPIO0_PULLEN);
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_PULLEN)
putreg32(regval, MAX326_GPIO0_PULLEN);
regval = getreg32(MAX326_GPIO0_PULLSEL);
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_PULLSEL)
putreg32(regval, MAX326_GPIO0_PULLSEL);
/* Disable slew and hysteresis */
regval = getreg32(MAX326_GPIO0_SRSEL);
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_SRSEL)
putreg32(regval, MAX326_GPIO0_SRSEL);
regval = getreg32(MAX326_GPIO0_INHYSEN);
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_INHYSEN)
putreg32(regval, MAX326_GPIO0_INHYSEN);
}
/****************************************************************************
@ -239,14 +241,14 @@ void max326_default(uint32_t pinmask);
*
****************************************************************************/
int max326_gpio_config(max326_pinset_t cfgset)
int max326_gpio_config(max326_pinset_t pinset)
{
irqstate_t flags;
unsigned int pin;
uint32_t pinmask;
uint32_t regval;
irqset_t flags;
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
DEBUGASSERT(pin <= GPIO_PINMAX);
pinmask = 1 << pin;
@ -266,41 +268,42 @@ int max326_gpio_config(max326_pinset_t cfgset)
/* Enable slew and hysteresis */
if ((cfgset & GPIO_SLEW) != 0)
if ((pinset & GPIO_SLEW) != 0)
{
regval = getreg32(MAX326_GPIO0_SRSEL);
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_SRSEL)
putreg32(regval, MAX326_GPIO0_SRSEL);
}
if ((cfgset & GPIO_HYSTERESIS) != 0)
if ((pinset & GPIO_HYSTERESIS) != 0)
{
regval = getreg32(MAX326_GPIO0_INHYSEN);
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_INHYSEN)
putreg32(regval, MAX326_GPIO0_INHYSEN);
}
/* Enable pull up and pull down */
if ((cfgset & GPIO_MODE_MASK) != GPIO_FLOAT)
if ((pinset & GPIO_MODE_MASK) != GPIO_FLOAT)
{
/* Enable pull-down resistor */
if ((PULLUP_SET & pinmask) != 0 ||
(cfgset & GPIO_MODE_MASK) == GPIO_PULLDOWN)
(pinset & GPIO_MODE_MASK) == GPIO_PULLDOWN)
{
regval = getreg32(AX326_GPIO_PULLEN);
regval = getreg32(MAX326_GPIO0_PULLEN);
regval |= pinmask;
putreg32(regval, AX326_GPIO_PULLEN)
putreg32(regval, MAX326_GPIO0_PULLEN);
}
if ((PULLUP_SET & pinmask) != 0 &&
(cfgset & GPIO_MODE_MASK) == GPIO_PULLUP)
(pinset & GPIO_MODE_MASK) == GPIO_PULLUP)
{
/* Enable pull-up resistor */
regval = getreg32(MAX326_GPIO0_PULLSEL);
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_PULLSEL)
putreg32(regval, MAX326_GPIO0_PULLSEL);
}
}
@ -310,12 +313,12 @@ int max326_gpio_config(max326_pinset_t cfgset)
{
/* Only two levels of drive strength */
if ((cfgset & GPIO_DRIVE_MASK) != GPIO_DRIVE_MEDHI ||
(cfgset & GPIO_DRIVE_MASK) != GPIO_DRIVE_HI)
if ((pinset & GPIO_DRIVE_MASK) != GPIO_DRIVE_MEDHI ||
(pinset & GPIO_DRIVE_MASK) != GPIO_DRIVE_HI)
{
regval = getreg32(MAX326_GPIO0_DS0SEL);
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_DS0SEL)
putreg32(regval, MAX326_GPIO0_DS0SEL);
}
}
else
@ -328,38 +331,38 @@ int max326_gpio_config(max326_pinset_t cfgset)
* HI DS0=1 DS1=1
*/
if ((cfgset & GPIO_DRIVE_MASK) != GPIO_DRIVE_MEDLO ||
(cfgset & GPIO_DRIVE_MASK) != GPIO_DRIVE_HI)
if ((pinset & GPIO_DRIVE_MASK) != GPIO_DRIVE_MEDLO ||
(pinset & GPIO_DRIVE_MASK) != GPIO_DRIVE_HI)
{
regval = getreg32(MAX326_GPIO0_DS0SEL);
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_DS0SEL)
putreg32(regval, MAX326_GPIO0_DS0SEL);
}
if ((cfgset & GPIO_DRIVE_MASK) != GPIO_DRIVE_MEDHI ||
(cfgset & GPIO_DRIVE_MASK) != GPIO_DRIVE_HI)
if ((pinset & GPIO_DRIVE_MASK) != GPIO_DRIVE_MEDHI ||
(pinset & GPIO_DRIVE_MASK) != GPIO_DRIVE_HI)
{
regval = getreg32(MAX326_GPIO0_DS1SEL);
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_DS1SEL)
putreg32(regval, MAX326_GPIO0_DS1SEL);
}
}
/* Handle the pin function */
switch (cfgset & GPIO_FUNC_MASK)
switch (pinset & GPIO_FUNC_MASK)
{
case GPIO_OUTPUT:
if ((cfgset & GPIO_VALUE) == GPIO_VALUE_ONE)
if ((pinset & GPIO_VALUE) == GPIO_VALUE_ONE)
{
regval = getreg32(MAX326_GPIO0_OUT); /* Set output high */
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_OUT)
putreg32(regval, MAX326_GPIO0_OUT);
}
regval = getreg32(MAX326_GPIO0_OUTEN); /* Enable output drivers */
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_OUTEN)
putreg32(regval, MAX326_GPIO0_OUTEN);
case GPIO_ALT1:
max326_altfunc(pinmask, AF_FUNC1);
@ -385,22 +388,22 @@ int max326_gpio_config(max326_pinset_t cfgset)
#ifdef CONFIG_MAX326_GPIOIRQ
/* Configure the interrupt */
if (GPIO_IS_INTR(cfgset))
if (GPIO_IS_INTR(pinset))
{
max326_gpio_irqconfig(cfgset);
max326_gpio_irqconfig(pinset);
}
#endif
/* Enable the wakeup event */
if ((cfgset & GPIO_WAKEUP) != 0)
if ((pinset & GPIO_WAKEUP) != 0)
{
regval = getreg32(MAX326_GPIO0_WAKEEN); /* Disable wakeup */
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_WAKEEN)
putreg32(regval, MAX326_GPIO0_WAKEEN);
}
spin_unlock_restore(flags);
spin_unlock_irqrestore(flags);
return OK;
}
@ -414,11 +417,11 @@ int max326_gpio_config(max326_pinset_t cfgset)
void max326_gpio_write(max326_pinset_t pinset, bool value)
{
irqstate_t flags;
unsigned int pin;
uint32_t regval;
irqset_t flags;
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
DEBUGASSERT(pin <= GPIO_PINMAX);
/* Modification of registers must be atomic */
@ -434,8 +437,8 @@ void max326_gpio_write(max326_pinset_t pinset, bool value)
regval &= ~(1 << pin);
}
putreg32(regval, MAX326_GPIO0_OUT)
spin_unlock_restore(flags);
putreg32(regval, MAX326_GPIO0_OUT);
spin_unlock_irqrestore(flags);
}
/****************************************************************************
@ -451,7 +454,7 @@ bool max326_gpio_read(max326_pinset_t pinset)
unsigned int pin;
uint32_t regval;
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
DEBUGASSERT(pin <= GPIO_PINMAX);
regval = getreg32(MAX326_GPIO0_IN); /* Set output high */
@ -478,7 +481,7 @@ int max326_gpio_dump(max326_pinset_t pinset, const char *msg);
unsigned int dsmode;
bool edge;
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
DEBUGASSERT(pin <= GPIO_PINMAX);
pinmask = 1 << pin;

View File

@ -174,21 +174,17 @@ void max326_gpio_irqconfig(max326_pinset_t cfgset)
void max326_gpio_irqdisable(int irq)
{
unsigned int pin;
uint32_t pinmask;
uint32_t regval;
irqset_t flags;
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
DEBUGASSERT(pin <= GPIO_PINMAX);
pinmask = 1 << pin;
DEBUGASSERT(irq >= MAX326_IRQ_GPIO1ST && irq <= MAX326_IRQ_GPIOLAST)
/* Modification of registers must be atomic */
if (irq >= MAX326_IRQ_GPIO1ST && irq <= MAX326_IRQ_GPIOLAST)
{
pin = irq - MAX326_IRQ_GPIO1ST
flags = spin_lock_irqsave();
regval = getreg32(MAX326_GPIO0_INTEN);
regval &= ~pinmask;
putreg32(regval, MAX326_GPIO0_INTEN)
spin_unlock_restore(flags);
/* Modification of registers must be atomic */
modifyreg32(MAX326_GPIO0_INTEN, 1 << pin, 0);
}
}
/************************************************************************************
@ -206,21 +202,17 @@ void max326_gpio_irqdisable(int irq)
void max326_gpio_irqenable(int irq)
{
unsigned int pin;
uint32_t pinmask;
uint32_t regval;
irqset_t flags;
pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
DEBUGASSERT(pin <= GPIO_PINMAX);
pinmask = 1 << pin;
DEBUGASSERT(irq >= MAX326_IRQ_GPIO1ST && irq <= MAX326_IRQ_GPIOLAST)
/* Modification of registers must be atomic */
if (irq >= MAX326_IRQ_GPIO1ST && irq <= MAX326_IRQ_GPIOLAST)
{
pin = irq - MAX326_IRQ_GPIO1ST
flags = spin_lock_irqsave();
regval = getreg32(MAX326_GPIO0_INTEN);
regval |= pinmask;
putreg32(regval, MAX326_GPIO0_INTEN)
spin_unlock_restore(flags);
/* Modification of registers must be atomic */
modifyreg32(MAX326_GPIO0_INTEN, 0, 1 << pin);
}
}
#endif /* CONFIG_MAX326_GPIOIRQ */

View File

@ -0,0 +1,333 @@
/************************************************************************************
* arch/arm/src/max326xx/max32660_lowputc.c
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 "up_arch.h"
#include "up_internal.h"
#include "chip/max326_memorymap.h"
#include "chip/max326_pinmux.h"
#include "chip/max326_uart.h"
#include "max326_config.h"
#include "max326_periphclks.h"
#include "max326_clockconfig.h"
#include "max326_gpio.h"
#include "max326_lowputc.h"
#include <arch/board/board.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
# define CONSOLE_BASE MAX326_UART0_BASE
# define CONSOLE_BAUD CONFIG_UART0_BAUD
# define CONSOLE_PARITY CONFIG_UART0_PARITY
# define CONSOLE_BITS CONFIG_UART0_BITS
# ifdef CONFIG_UART0_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_UART0_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_UART0_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
# define CONSOLE_BASE MAX326_UART1_BASE
# define CONSOLE_BAUD CONFIG_UART1_BAUD
# define CONSOLE_PARITY CONFIG_UART1_PARITY
# define CONSOLE_BITS CONFIG_UART1_BITS
# ifdef CONFIG_UART1_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_UART1_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_UART1_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#endif
/************************************************************************************
* Private Data
************************************************************************************/
#ifdef HAVE_UART_CONSOLE
/* UART console configuration */
static const struct uart_config_s g_console_config=
{
.baud = CONSOLE_BAUD,
.parity = CONSOLE_PARITY,
.bits = CONSOLE_BITS,
.txlevel = MAX326_UART_TXFIFO_DEPTH / 2,
.rxlevel = MAX326_UART_RXFIFO_DEPTH / 4,
.stopbits2 = CONSOLE_STOPBITS2,
#ifdef CONFIG_SERIAL_IFLOWCONTROL
.iflow = CONSOLE_IFLOW,
#endif
#ifdef CONFIG_SERIAL_OFLOWCONTROL
.oflow = CONSOLE_OFLOW,
#endif
};
#endif /* HAVE_UART_CONSOLE */
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Name: max326_setbaud
*
* Description:
* Configure the UART BAUD.
*
************************************************************************************/
#ifdef HAVE_UART_DEVICE
static void max326_setbaud(uintptr_t base, FAR const struct uart_config_s *config)
{
#warning Missing logic
}
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: max326_lowsetup
*
* Description:
* Called at the very beginning of _start. Performs low level initialization
* including setup of the console UART. This UART initialization is done
* early so that the serial console is available for debugging very early in
* the boot sequence.
*
************************************************************************************/
void max326_lowsetup(void)
{
/* Enable clocking to GPIO0 */
max326_gpio0_enableclk();
#ifdef HAVE_UART_DEVICE
#ifdef CONFIG_MAX326XX_UART0
/* Enable clocking to UART0 */
max326_uart0_enableclk();
/* Configure UART0 pins */
max326_gpio_config(GPIO_UART0_RX);
max326_gpio_config(GPIO_UART0_TX);
#ifdef CONFIG_UART0_OFLOWCONTROL
max326_gpio_config(GPIO_UART0_CTS);
#endif
#ifdef CONFIG_UART0_IFLOWCONTROL
max326_gpio_config(GPIO_UART0_RTS);
#endif
#endif /* CONFIG_MAX326XX_UART0 */
#ifdef CONFIG_MAX326XX_UART1
/* Enable clocking to UART1 */
max326_uart1_enableclk();
/* Configure UART1 pins */
max326_gpio_config(GPIO_UART1_RX);
max326_gpio_config(GPIO_UART1_TX);
#ifdef CONFIG_UART1_OFLOWCONTROL
max326_gpio_config(GPIO_UART1_CTS);
#endif
#ifdef CONFIG_UART1_IFLOWCONTROL
max326_gpio_config(GPIO_UART1_RTS);
#endif
#endif /* CONFIG_MAX326XX_UART1 */
#ifdef HAVE_UART_CONSOLE
/* Configure the console UART (if any) */
max326_uart_configure(CONSOLE_BASE, &g_console_config);
#endif /* HAVE_UART_CONSOLE */
#endif /* HAVE_UART_DEVICE */
}
/************************************************************************************
* Name: max326_uart_configure
*
* Description:
* Configure a UART for non-interrupt driven operation
*
************************************************************************************/
#ifdef HAVE_UART_DEVICE
void max326_uart_configure(uintptr_t base, FAR const struct uart_config_s *config)
{
uint32_t regval;
/* Configure baud */
max326_setbaud(CONSOLE_BASE, config);
/* Configure RX and TX FIFOs */
/* Empty and enable FIFOs */
/* Setup trigger level */
/* Enable trigger events */
/* Setup configuration and enable UART */
switch (config->bits)
{
case 7:
break;
default:
case 8:
break;
case 9:
break;
}
switch (config->parity)
{
default:
case 0:
break;
case 1:
break;
case 2:
break;
}
if (config->stopbits2)
{
}
#warning Missing logic
}
#endif
/****************************************************************************
* Name: max326_uart_disable
*
* Description:
* Disable a UART. it will be necessary to again call
* max326_uart_configure() in order to use this UART channel again.
*
****************************************************************************/
#ifdef HAVE_UART_DEVICE
void max326_uart_disable(uintptr_t base)
{
/* Disable interrupts */
/* Disable the UART */
/* Disable the FIFOs */
}
#endif
/****************************************************************************
* Name: up_lowputc
*
* Description:
* Output one byte on the serial console
*
****************************************************************************/
void up_lowputc(char ch)
{
#ifdef HAVE_UART_CONSOLE
irqstate_t flags;
for (; ; )
{
/* Wait for the transmit FIFO to be not full */
#warning Missing logic
/* Disable interrupts so that the test and the transmission are
* atomic.
*/
flags = spin_lock_irqsave();
#warning Missing logic
{
/* Send the character */
spin_unlock_irqrestore(flags);
return;
}
spin_unlock_irqrestore(flags);
}
#endif
}

View File

@ -0,0 +1,92 @@
/************************************************************************************
* arch/arm/src/max326xx/max32600/max326_periphclks.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_MAX326XX_MAX32660_MAX32660_PERIPHCLKS_H
#define __ARCH_ARM_SRC_MAX326XX_MAX32660_MAX32660_PERIPHCLKS_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include "up_arch.h"
#include "chip/max326_gcr.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#define MAX32660_PERIPH_ENABLE_0(n) modifyreg32(MAX326_GCR_PCLKDIS0, (n), 0)
#define MAX32660_PERIPH_ENABLE_1(n) modifyreg32(MAX326_GCR_PCLKDIS1, (n), 0)
#define MAX32660_PERIPH_DISABLE_0(n) modifyreg32(MAX326_GCR_PCLKDIS0, 0, (n))
#define MAX32660_PERIPH_DISABLE_1(n) modifyreg32(MAX326_GCR_PCLKDIS1, 0, (n))
/* Enable peripheral clocks */
#define max326_gpio0_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_GPIO0D)
#define max326_dma_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_DMAD)
#define max326_spi0_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_SPI0D)
#define max326_spi1_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_SPI1D)
#define max326_uart0_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_UART0D)
#define max326_uart1_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_UART1D)
#define max326_i2c0_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_I2C0D)
#define max326_tmr0_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_TMR0D)
#define max326_tmr1_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_TMR1D)
#define max326_tmr2_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_TMR2D)
#define max326_i2c1_enableclk() MAX32660_PERIPH_ENABLE_0(GCR_PCLKDIS0_I2C1D)
#define max326_flc_enableclk() MAX32660_PERIPH_ENABLE_1(GCR_PCLKDIS1_FLCD)
#define max326_icc_enableclk() MAX32660_PERIPH_ENABLE_1(GCR_PCLKDIS1_ICCD)
/* Disable peripheral clocks */
#define max326_gpio0_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_GPIO0D)
#define max326_dma_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_DMAD)
#define max326_spi0_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_SPI0D)
#define max326_spi1_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_SPI1D)
#define max326_uart0_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_UART0D)
#define max326_uart1_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_UART1D)
#define max326_i2c0_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_I2C0D)
#define max326_tmr0_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_TMR0D)
#define max326_tmr1_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_TMR1D)
#define max326_tmr2_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_TMR2D)
#define max326_i2c1_disableclk() MAX32660_PERIPH_DISABLE_0(GCR_PCLKDIS0_I2C1D)
#define max326_flc_disableclk() MAX32660_PERIPH_DISABLE_1(GCR_PCLKDIS1_FLCD)
#define max326_icc_disableclk() MAX32660_PERIPH_DISABLE_1(GCR_PCLKDIS1_ICCD)
#endif /* __ARCH_ARM_SRC_MAX326XX_MAX32660_MAX32660_PERIPHCLKS_H */

View File

@ -0,0 +1,867 @@
/****************************************************************************
* arch/arm/src/max326xx/max326_serial.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <unistd.h>
#include <semaphore.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/serial/serial.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "chip.h"
#include "max326_config.h"
#include "chip/max326_uart.h"
#include "max326_clockconfig.h"
#include "max326_lowputc.h"
#include "max326_serial.h"
#include <arch/board/board.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Some sanity checks *******************************************************/
/* Is there at least one UART enabled and configured as a RS-232 device? */
#ifndef HAVE_UART_DEVICE
# warning "No UARTs enabled"
#endif
/* If we are not using the serial driver for the console, then we still must
* provide some minimal implementation of up_putc.
*/
#if defined(HAVE_UART_DEVICE) && defined(USE_SERIALDRIVER)
/* Which UART with be tty0/console and which tty1-4? The console will
* always be ttyS0. If there is no console then will use the lowest
* numbered UART.
*/
/* First pick the console and ttys0. This could be any of UART0-5 */
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart0port /* UART0 is console */
# define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */
# define UART0_ASSIGNED 1
#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart1port /* UART1 is console */
# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
# define UART1_ASSIGNED 1
#else
# undef CONSOLE_DEV /* No console */
# if defined(CONFIG_MAX326XX_UART0)
# define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */
# define UART0_ASSIGNED 1
# elif defined(CONFIG_MAX326XX_UART1)
# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
# define UART1_ASSIGNED 1
# endif
#endif
/* Pick ttys1. This could be any of UART0-1 excluding the console UART. */
#if defined(CONFIG_MAX326XX_UART0) && !defined(UART0_ASSIGNED)
# define TTYS1_DEV g_uart0port /* UART0 is ttyS1 */
# define UART0_ASSIGNED 1
#elif defined(CONFIG_MAX326XX_UART1) && !defined(UART1_ASSIGNED)
# define TTYS1_DEV g_uart1port /* UART1 is ttyS1 */
# define UART1_ASSIGNED 1
#endif
/****************************************************************************
* Private Types
****************************************************************************/
/* This structure provides the state of one UART device */
struct max326_dev_s
{
uintptr_t uartbase; /* Base address of UART registers */
uint8_t irq; /* IRQ associated with this UART */
/* UART configuration */
struct uart_config_s config;
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int max326_setup(struct uart_dev_s *dev);
static void max326_shutdown(struct uart_dev_s *dev);
static int max326_attach(struct uart_dev_s *dev);
static void max326_detach(struct uart_dev_s *dev);
static int max326_interrupt(int irq, void *context, FAR void *arg);
static int max326_ioctl(struct file *filep, int cmd, unsigned long arg);
static int max326_receive(struct uart_dev_s *dev, uint32_t *status);
static void max326_rxint(struct uart_dev_s *dev, bool enable);
static bool max326_rxavailable(struct uart_dev_s *dev);
static void max326_send(struct uart_dev_s *dev, int ch);
static void max326_txint(struct uart_dev_s *dev, bool enable);
static bool max326_txready(struct uart_dev_s *dev);
static bool max326_txempty(struct uart_dev_s *dev);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct uart_ops_s g_uart_ops =
{
.setup = max326_setup,
.shutdown = max326_shutdown,
.attach = max326_attach,
.detach = max326_detach,
.ioctl = max326_ioctl,
.receive = max326_receive,
.rxint = max326_rxint,
.rxavailable = max326_rxavailable,
#ifdef CONFIG_SERIAL_IFLOWCONTROL
.rxflowcontrol = NULL,
#endif
.send = max326_send,
.txint = max326_txint,
.txready = max326_txready,
.txempty = max326_txempty,
};
/* I/O buffers */
#ifdef CONFIG_MAX326XX_UART0
static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE];
static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE];
#endif
#ifdef CONFIG_MAX326XX_UART1
static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE];
static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
#endif
/* This describes the state of the MAX326xx UART0 port. */
#ifdef CONFIG_MAX326XX_UART0
static struct max326_dev_s g_uart0priv =
{
.uartbase = MAX326_UART0_BASE,
.irq = MAX326_IRQ_UART0,
.config =
{
.baud = CONFIG_UART0_BAUD,
.parity = CONFIG_UART0_PARITY,
.bits = CONFIG_UART0_BITS,
.txlevel = MAX326_UART_TXFIFO_DEPTH / 2,
.rxlevel = MAX326_UART_RXFIFO_DEPTH / 4,
.stopbits2 = CONFIG_UART0_2STOP,
#ifdef CONFIG_UART0_IFLOWCONTROL
.iflow = true,
#endif
#ifdef CONFIG_UART0_OFLOWCONTROL
.oflow = true,
#endif
}
};
static uart_dev_t g_uart0port =
{
.recv =
{
.size = CONFIG_UART0_RXBUFSIZE,
.buffer = g_uart0rxbuffer,
},
.xmit =
{
.size = CONFIG_UART0_TXBUFSIZE,
.buffer = g_uart0txbuffer,
},
.ops = &g_uart_ops,
.priv = &g_uart0priv,
};
#endif
/* This describes the state of the MAX326xx UART1 port. */
#ifdef CONFIG_MAX326XX_UART1
static struct max326_dev_s g_uart1priv =
{
.uartbase = MAX326_UART1_BASE,
.irq = MAX326_IRQ_UART1,
.config =
{
.baud = CONFIG_UART1_BAUD,
.parity = CONFIG_UART1_PARITY,
.bits = CONFIG_UART1_BITS,
.txlevel = MAX326_UART_TXFIFO_DEPTH / 2,
.rxlevel = MAX326_UART_RXFIFO_DEPTH / 4,
.stopbits2 = CONFIG_UART1_2STOP,
#ifdef CONFIG_UART1_IFLOWCONTROL
.iflow = true,
#endif
#ifdef CONFIG_UART1_OFLOWCONTROL
.oflow = true,
#endif
}
};
static uart_dev_t g_uart1port =
{
.recv =
{
.size = CONFIG_UART1_RXBUFSIZE,
.buffer = g_uart1rxbuffer,
},
.xmit =
{
.size = CONFIG_UART1_TXBUFSIZE,
.buffer = g_uart1txbuffer,
},
.ops = &g_uart_ops,
.priv = &g_uart1priv,
};
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: max326_serialin
****************************************************************************/
static inline uint32_t max326_serialin(struct max326_dev_s *priv,
unsigned int offset)
{
return getreg32(priv->uartbase + offset);
}
/****************************************************************************
* Name: max326_serialout
****************************************************************************/
static inline void max326_serialout(struct max326_dev_s *priv,
unsigned int offset, uint32_t value)
{
putreg32(value, priv->uartbase + offset);
}
/****************************************************************************
* Name: max326_modifyreg
****************************************************************************/
static inline void max326_modifyreg(struct max326_dev_s *priv, unsigned int offset,
uint32_t setbits, uint32_t clrbits)
{
irqstate_t flags;
uintptr_t regaddr = priv->uartbase + offset;
uint32_t regval;
flags = enter_critical_section();
regval = getreg32(regaddr);
regval &= ~clrbits;
regval |= setbits;
putreg32(regval, regaddr);
leave_critical_section(flags);
}
/****************************************************************************
* Name: max326_fifoint_enable
****************************************************************************/
static inline void max326_fifoint_enable(struct max326_dev_s *priv, uint32_t intset)
{
#warning Missing logic
}
/****************************************************************************
* Name: max326_fifoint_disable
****************************************************************************/
static inline void max326_fifoint_disable(struct max326_dev_s *priv, uint32_t intset)
{
#warning Missing logic
}
/****************************************************************************
* Name: max326_fifoint_disableall
****************************************************************************/
static void max326_fifoint_disableall(struct max326_dev_s *priv, uint32_t *intset)
{
irqstate_t flags;
flags = enter_critical_section();
if (intset)
{
#warning Missing logic
}
#warning Missing logic
leave_critical_section(flags);
}
/****************************************************************************
* Name: max326_setup
*
* Description:
* Configure the UART baud, bits, parity, etc. This method is called the
* first time that the serial port is opened.
*
****************************************************************************/
static int max326_setup(struct uart_dev_s *dev)
{
#ifndef CONFIG_SUPPRESS_UART_CONFIG
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
/* Configure the UART as an RS-232 UART */
max326_uart_configure(priv->uartbase, &priv->config);
#endif
/* Make sure that all interrupts are disabled */
max326_fifoint_disableall(priv, NULL);
return OK;
}
/****************************************************************************
* Name: max326_shutdown
*
* Description:
* Disable the UART. This method is called when the serial
* port is closed
*
****************************************************************************/
static void max326_shutdown(struct uart_dev_s *dev)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
/* Disable interrupts */
max326_fifoint_disableall(priv, NULL);
/* Reset hardware and disable Rx and Tx */
max326_uart_disable(priv->uartbase);
}
/****************************************************************************
* Name: max326_attach
*
* Description:
* Configure the UART to operation in interrupt driven mode. This method is
* called when the serial port is opened. Normally, this is just after the
* the setup() method is called, however, the serial console may operate in
* a non-interrupt driven mode during the boot phase.
*
* RX and TX interrupts are not enabled when by the attach method (unless the
* hardware supports multiple levels of interrupt enabling). The RX and TX
* interrupts are not enabled until the txint() and rxint() methods are called.
*
****************************************************************************/
static int max326_attach(struct uart_dev_s *dev)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
int ret;
/* Attach and enable the IRQ(s). The interrupts are (probably) still
* disabled in the C2 register.
*/
ret = irq_attach(priv->irq, max326_interrupt, dev);
if (ret == OK)
{
up_enable_irq(priv->irq);
}
return ret;
}
/****************************************************************************
* Name: max326_detach
*
* Description:
* Detach UART interrupts. This method is called when the serial port is
* closed normally just before the shutdown method is called. The exception
* is the serial console which is never shutdown.
*
****************************************************************************/
static void max326_detach(struct uart_dev_s *dev)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
/* Disable interrupts */
max326_fifoint_disableall(priv, NULL);
up_disable_irq(priv->irq);
/* Detach from the interrupt(s) */
irq_detach(priv->irq);
}
/****************************************************************************
* Name: max326_interrupt
*
* Description:
* This is the UART status interrupt handler. It will be invoked when an
* interrupt received on the 'irq' It should call uart_transmitchars or
* uart_receivechar to perform the appropriate data transfers. The
* interrupt handling logic must be able to map the 'irq' number into the
* approprite uart_dev_s structure in order to call these functions.
*
****************************************************************************/
static int max326_interrupt(int irq, void *context, FAR void *arg)
{
struct uart_dev_s *dev = (struct uart_dev_s *)arg;
struct max326_dev_s *priv;
int passes;
uint32_t regval;
bool handled;
DEBUGASSERT(dev != NULL && dev->priv != NULL);
priv = (struct max326_dev_s *)dev->priv;
/* Loop until there are no characters to be transferred or,
* until we have been looping for a long time.
*/
handled = true;
for (passes = 0; passes < 256 && handled; passes++)
{
handled = false;
/* Read and clear FIFO interrupt status */
#warning Missing logic
/* Handle incoming, receive bytes.
* Check if the received FIFO is not empty.
*/
#warning Missing logic
{
/* Process incoming bytes */
uart_recvchars(dev);
handled = true;
}
/* Handle outgoing, transmit bytes.
* Check if the received FIFO is not full.
*/
#warning Missing logic
{
/* Process outgoing bytes */
uart_xmitchars(dev);
handled = true;
}
#ifdef CONFIG_DEBUG_FEATURES
/* Check for error conditions */
#warning Missing logic
{
/* And now do... what? Should we reset FIFOs on a FIFO error? */
#warning Misssing logic
}
#endif
}
return OK;
}
/****************************************************************************
* Name: max326_ioctl
*
* Description:
* All ioctl calls will be routed through this method
*
****************************************************************************/
static int max326_ioctl(struct file *filep, int cmd, unsigned long arg)
{
#if 0 /* Reserved for future growth */
struct inode *inode;
struct uart_dev_s *dev;
struct max326_dev_s *priv;
int ret = OK;
DEBUGASSERT(filep, filep->f_inode);
inode = filep->f_inode;
dev = inode->i_private;
DEBUGASSERT(dev, dev->priv);
priv = (struct max326_dev_s *)dev->priv;
switch (cmd)
{
case xxx: /* Add commands here */
break;
default:
ret = -ENOTTY;
break;
}
return ret;
#else
return -ENOTTY;
#endif
}
/****************************************************************************
* Name: max326_receive
*
* Description:
* Called (usually) from the interrupt level to receive one
* character from the UART. Error bits associated with the
* receipt are provided in the return 'status'.
*
****************************************************************************/
static int max326_receive(struct uart_dev_s *dev, uint32_t *status)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
uint32_t fiford;
/* Get input data along with receiver control information */
#warning Missing logic
/* Return receiver control information */
if (status)
{
#warning Missing logic
//*status = fiford && ~UART_FIFORD_RXDATA_MASK;
}
/* Then return the actual received data. */
#warning Missing logic
return fiford /* & UART_FIFORD_RXDATA_MASK */;
}
/****************************************************************************
* Name: max326_rxint
*
* Description:
* Call to enable or disable RX interrupts
*
****************************************************************************/
static void max326_rxint(struct uart_dev_s *dev, bool enable)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
if (enable)
{
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
/* Receive an interrupt when their is anything in the Rx data register (or an Rx
* timeout occurs).
*/
#warning Missing logic
//max326_fifoint_enable(priv, CCR_RX_EVENTS);
#endif
}
else
{
#warning Missing logic
//max326_fifoint_disable(priv, CCR_RX_EVENTS);
}
}
/****************************************************************************
* Name: max326_rxavailable
*
* Description:
* Return true if the receive register is not empty
*
****************************************************************************/
static bool max326_rxavailable(struct uart_dev_s *dev)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
uint32_t regval;
/* Return true if the receive buffer/fifo is not "empty." */
#warning Missing logic
return false;
}
/****************************************************************************
* Name: max326_send
*
* Description:
* This method will send one byte on the UART.
*
****************************************************************************/
static void max326_send(struct uart_dev_s *dev, int ch)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
#warning Missing logic
}
/****************************************************************************
* Name: max326_txint
*
* Description:
* Call to enable or disable TX interrupts
*
****************************************************************************/
static void max326_txint(struct uart_dev_s *dev, bool enable)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
if (enable)
{
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
irqstate_t flags;
/* Enable the TX interrupt */
flags = enter_critical_section();
#warning Missing logic
//max326_fifoint_enable(priv, CCR_TX_EVENTS);
/* Fake a TX interrupt here by just calling uart_xmitchars() with
* interrupts disabled (note this may recurse).
*/
uart_xmitchars(dev);
leave_critical_section(flags);
#endif
}
else
{
/* Disable the TX interrupt */
#warning Missing logic
//max326_fifoint_disable(priv, CCR_TX_EVENTS);
}
}
/****************************************************************************
* Name: max326_txready
*
* Description:
* Return true if the tranmsit data register is empty
*
****************************************************************************/
static bool max326_txready(struct uart_dev_s *dev)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
uint32_t regval;
/* Return true if the transmit FIFO is "not full." */
#warning Missing logic
return false;
}
/****************************************************************************
* Name: max326_txempty
*
* Description:
* Return true if the transmit data register is empty
*
****************************************************************************/
static bool max326_txempty(struct uart_dev_s *dev)
{
struct max326_dev_s *priv = (struct max326_dev_s *)dev->priv;
uint32_t regval;
/* Return true if the transmit FIFO is "empty." */
#warning Missing logic
return false;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: max326_earlyserialinit
*
* Description:
* Performs the low level UART initialization early in debug so that the
* serial console will be available during bootup. This must be called
* before max326_serialinit. NOTE: This function depends on GPIO pin
* configuration performed in xmc_lowsetup() and main clock iniialization
* performed in xmc_clock_configure().
*
****************************************************************************/
#ifdef USE_EARLYSERIALINIT
void max326_earlyserialinit(void)
{
/* Disable interrupts from all UARTS. The console is enabled in
* pic32mx_consoleinit()
*/
max326_fifoint_disableall(TTYS0_DEV.priv, NULL);
#ifdef TTYS1_DEV
max326_fifoint_disableall(TTYS1_DEV.priv, NULL);
#endif
/* Configuration whichever one is the console */
#ifdef HAVE_UART_CONSOLE
CONSOLE_DEV.isconsole = true;
max326_setup(&CONSOLE_DEV);
#endif
}
#endif
/****************************************************************************
* Name: up_serialinit
*
* Description:
* Register serial console and serial ports. This assumes
* that max326_earlyserialinit was called previously.
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
****************************************************************************/
void up_serialinit(void)
{
#ifdef HAVE_UART_CONSOLE
/* Register the serial console */
(void)uart_register("/dev/console", &CONSOLE_DEV);
#endif
/* Register all UARTs */
(void)uart_register("/dev/ttyS0", &TTYS0_DEV);
#ifdef TTYS1_DEV
(void)uart_register("/dev/ttyS1", &TTYS1_DEV);
#endif
}
/****************************************************************************
* Name: up_putc
*
* Description:
* Provide priority, low-level access to support OS debug writes
*
****************************************************************************/
int up_putc(int ch)
{
#ifdef HAVE_UART_CONSOLE
struct max326_dev_s *priv = (struct max326_dev_s *)CONSOLE_DEV.priv;
uint32_t intset;
max326_fifoint_disableall(priv, &intset);
/* Check for LF */
if (ch == '\n')
{
/* Add CR */
up_lowputc('\r');
}
up_lowputc(ch);
max326_fifoint_enable(priv, intset);
#endif
return ch;
}
#else /* USE_SERIALDRIVER */
/****************************************************************************
* Name: up_putc
*
* Description:
* Provide priority, low-level access to support OS debug writes
*
****************************************************************************/
int up_putc(int ch)
{
#ifdef HAVE_UART_CONSOLE
/* Check for LF */
if (ch == '\n')
{
/* Add CR */
up_lowputc('\r');
}
up_lowputc(ch);
return ch;
}
#endif
#endif /* HAVE_UART_DEVICE && USE_SERIALDRIVER */

View File

@ -108,7 +108,7 @@ void max326_gpio_irqinitialize(void);
*
************************************************************************************/
int max326_gpio_config(max326_pinset_t cfgset);
int max326_gpio_config(max326_pinset_t pinset);
/************************************************************************************
* Name: max326_gpio_irqconfig
@ -120,7 +120,7 @@ int max326_gpio_config(max326_pinset_t cfgset);
************************************************************************************/
#ifdef CONFIG_MAX326_GPIOIRQ
void max326_gpio_irqconfig(max326_pinset_t cfgset);
void max326_gpio_irqconfig(max326_pinset_t pinset);
#endif
/************************************************************************************
@ -150,9 +150,6 @@ bool max326_gpio_read(max326_pinset_t pinset);
* Disable a GPIO pin interrupt. This function should not be called directly but,
* rather through up_disable_irq();
*
* Assumptions:
* We are in a critical section.
*
************************************************************************************/
#ifdef CONFIG_MAX326_GPIOIRQ
@ -166,9 +163,6 @@ void max326_gpio_irqdisable(int irq);
* Enable a GPIO pin interrupt. This function should not be called directly but,
* rather through up_enable_irq();
*
* Assumptions:
* We are in a critical section.
*
************************************************************************************/
#ifdef CONFIG_MAX326_GPIOIRQ

View File

@ -57,7 +57,6 @@
struct uart_config_s
{
uint32_t baud; /* Configured baud */
uint32_t fclk; /* Input UART function clock frequency */
uint8_t parity; /* 0=none, 1=odd, 2=even */
uint8_t bits; /* Number of bits (5-9) */
uint8_t txlevel; /* TX level for event generation */
@ -90,7 +89,7 @@ struct uart_config_s
void max326_lowsetup(void);
/****************************************************************************
* Name: max326_usart_configure
* Name: max326_uart_configure
*
* Description:
* Configure a UART for non-interrupt driven operation
@ -98,21 +97,21 @@ void max326_lowsetup(void);
****************************************************************************/
#ifdef HAVE_UART_DEVICE
void max326_usart_configure(uintptr_t base,
FAR const struct uart_config_s *config);
void max326_uart_configure(uintptr_t base,
FAR const struct uart_config_s *config);
#endif
/****************************************************************************
* Name: max326_usart_disable
* Name: max326_uart_disable
*
* Description:
* Disable a UART. it will be necessary to again call
* max326_usart_configure() in order to use this UART channel again.
* max326_uart_configure() in order to use this UART channel again.
*
****************************************************************************/
#ifdef HAVE_UART_DEVICE
void max326_usart_disable(uintptr_t base);
void max326_uart_disable(uintptr_t base);
#endif
#endif /* __ARCH_ARM_SRC_MAX326XX_MAX326_LOWPUTC_H */

View File

@ -0,0 +1,53 @@
/************************************************************************************
* arch/arm/src/max326xx/max326_periphclks.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_MAX326XX_MAX326_PERIPHCLKS_H
#define __ARCH_ARM_SRC_MAX326XX_MAX326_PERIPHCLKS_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#if defined(CONFIG_ARCH_FAMILY_MAX32620) || defined(CONFIG_ARCH_FAMILY_MAX32630)
# include "max32620_30/max32620_30_periphclks.h"
#elif defined(CONFIG_ARCH_FAMILY_MAX32660)
# include "max32660/max32660_periphclks.h"
#else
# error "Unsupported MAX326XX family"
#endif
#endif /* __ARCH_ARM_SRC_MAX326XX_MAX326_PERIPHCLKS_H */

View File

@ -32,8 +32,12 @@ Contents
Serial Console
==============
A VCOM serial console is available. This is provided by UART1 via pins
P0.10 and P0.11.
UART1 Tx and Rx signals at port P0.10 and P0.11 are connected to the
programming and debug header JH2 pins 2 and 3 through 1kΩ resistors.
This provides a convenient way to communicate with a PC though the
virtual serial port available in Maxims CMSIS-DAP debug adapter. The
series resistors allow for these signals to be overdriven by other
circuits without modifying the board.
LEDs and Buttons
================

View File

@ -109,7 +109,20 @@
#define BUTTON_SW2_BIT (1 << BUTTON_SW2)
/* Alternate function pin selections ****************************************/
/* Pin Disambiguation *******************************************************/
/* UART1
*
* UART1 Tx and Rx signals at port P0.10 and P0.11 are connected to the
* programming and debug header JH2 pins 2 and 3 through 1 resistors.
* This provides a convenient way to communicate with a PC though the
* virtual serial port available in Maxims CMSIS-DAP debug adapter. The
* series resistors allow for these signals to be overdriven by other
* circuits without modifying the board.
*/
#define GPIO_UART1_RX GPIO_UART1_RX_3 /* P0.11 */
#define GPIO_UART1_TX GPIO_UART1_TX_3 /* P0.10 */
/* DMA **********************************************************************/

View File

@ -51,7 +51,7 @@ CSRCS += max326_userleds.c
endif
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += max326_buttons.c
CSRCS += max326_button.c
endif
ifeq ($(CONFIG_MAX326XX_HAVE_I2CM),y)

View File

@ -46,6 +46,15 @@
* Pre-processor Definitions
****************************************************************************/
/* A single red LED is available driven by GPIO P0.13. */
#define GPIO_LED (GPIO_OUTPUT | GPIO_PORT0 | GPIO_PIN13)
/* An single button is available on GPIO P0.12 for use by software. */
#define GPIO_BUTTON (GPIO_INPUT | GPIO_PORT0 | GPIO_PIN12)
#define BUTTON_IRQ MAX326_IRQ_P0_12
/****************************************************************************
* Public Function Prototypes
****************************************************************************/

View File

@ -39,6 +39,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
#include <sys/mount.h>
#include <syslog.h>

View File

@ -0,0 +1,149 @@
/****************************************************************************
* configs/sama5d2-xult/src/sam_buttons.c
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 <stdint.h>
#include <errno.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <nuttx/irq.h>
#include <nuttx/irq.h>
#include "max326_gpio.h"
#include "max32660-evsys.h"
#include <arch/board/board.h>
#ifdef CONFIG_ARCH_BUTTONS
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_button_initialize
*
* Description:
* board_button_initialize() must be called to initialize button resources.
* After that, board_buttons() may be called to collect the current state
* of all buttons or board_button_irq() may be called to register button
* interrupt handlers.
*
****************************************************************************/
void board_button_initialize(void)
{
(void)max326_gpio_config(GPIO_BUTTON);
}
/****************************************************************************
* Name: board_buttons
*
* Description:
* After board_button_initialize() has been called, board_buttons() may be
* called to collect the state of all buttons. board_buttons() returns an
* 32-bit bit set with each bit associated with a button. See the BUTTON*
* definitions above for the meaning of each bit in the returned value.
*
****************************************************************************/
uint32_t board_buttons(void)
{
return !max326_gpio_read(GPIO_BUTTON) ? 0 : BUTTON_SW2_BIT;
}
/****************************************************************************
* Name: board_button_irq
*
* Description:
* This function may be called to register an interrupt handler that will
* be called when a button is depressed or released. The ID value is one
* of the BUTTON* definitions provided above.
*
* Configuration Notes:
* Configuration CONFIG_SAMA5_PIO_IRQ must be selected to enable the
* overall PIO IRQ feature and CONFIG_SAMA5_PIOB_IRQ must be enabled to
* select PIOs to support interrupts on PIOE.
*
****************************************************************************/
#if defined(CONFIG_SAMA5_PIOB_IRQ) && defined(CONFIG_ARCH_IRQBUTTONS)
int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg)
{
int ret = -EINVAL;
if (id == BUTTON_SW2)
{
irqstate_t flags;
/* Disable interrupts until we are done. This guarantees that the
* following operations are atomic.
*/
flags = spin_lock_irqsave();
/* Are we attaching or detaching? */
if (irqhandler != NULL)
{
/* Configure the interrupt */
(void)irq_attach(BUTTON_IRQ, irqhandler, arg);
up_enable_irq(BUTTON_IRQ);
}
else
{
/* Disable and detach the interrupt */
up_disable_irq(BUTTON_IRQ);
(void)irq_detach(BUTTON_IRQ);
}
spin_unlock_irqrestore(flags);
ret = OK;
}
return ret;
}
#endif
#endif /* CONFIG_ARCH_BUTTONS */