xtensa/esp32: Watchdog support (MWDTs)

This commit is contained in:
Sara Souza 2020-10-14 14:33:11 -03:00 committed by Alan Carvalho de Assis
parent b23bca5cb3
commit b9d44017cf
16 changed files with 2213 additions and 89 deletions

View File

@ -47,6 +47,10 @@ config ESP32_TIMER
bool
default n
config ESP32_WTD
bool
default n
config ESP32_BT
bool "Bluetooth"
default n
@ -205,43 +209,20 @@ config ESP32_TIMER3
Enables Timer
config ESP32_MWDT0
bool "Timer 0 Watchdog"
bool "Main System Watchdog Timer (Group 0)"
default n
depends on EXPERIMENTAL
select ESP32_TIMER0
select ESP32_WTD
---help---
No yet implemented
Includes MWDT0. This watchdog timer is part of the Group 0
timer submodule.
config ESP32_MWDT1
bool "Timer 1 Watchdog"
bool "Main System Watchdog Timer (Group 1)"
default n
depends on EXPERIMENTAL
select ESP32_TIMER1
select ESP32_WTD
---help---
No yet implemented
config ESP32_MWDT2
bool "Timer 2 Watchdog"
default n
depends on EXPERIMENTAL
select ESP32_TIMER2
---help---
No yet implemented
config ESP32_MWDT3
bool "Timer 3 Watchdog"
default n
depends on EXPERIMENTAL
select ESP32_TIMER3
---help---
No yet implemented
config ESP32_RWDT
bool "RTC Watchdog"
default n
depends on EXPERIMENTAL
---help---
No yet implemented
Includes MWDT1. This watchdog timer is part of the Group 0
timer submodule.
config ESP32_UART0
bool "UART 0"

View File

@ -157,6 +157,14 @@ ifeq ($(CONFIG_ESP32_PARTITION),y)
CHIP_CSRCS += esp32_partition.c
endif
ifeq ($(CONFIG_WATCHDOG),y)
CHIP_CSRCS += esp32_wtd_lowerhalf.c
ifeq ($(CONFIG_ESP32_WTD),y)
CHIP_CSRCS += esp32_wtd.c
endif
endif
ifeq ($(CONFIG_ARCH_USE_MODULE_TEXT),y)
CHIP_CSRCS += esp32_modtext.c
CMN_ASRCS += xtensa_loadstore.S

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/esp32/esp32_tim_lowerhalf.h
* arch/arm/src/esp32/esp32_tim_lowerhalf.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,106 @@
/****************************************************************************
* arch/xtensa/src/esp32/esp32_wtd.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_XTENSA_SRC_ESP32_ESP32_WTD_H
#define __ARCH_XTENSA_SRC_ESP32_ESP32_WTD_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <nuttx/irq.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define FEED_DOG 0xffffffff
/* Helpers ******************************************************************/
#define ESP32_WTD_START(d) ((d)->ops->start(d))
#define ESP32_WTD_STOP(d) ((d)->ops->stop(d))
#define ESP32_WTD_LOCK(d) ((d)->ops->enablewp(d))
#define ESP32_WTD_UNLOCK(d) ((d)->ops->disablewp(d))
#define ESP32_WTD_INITCONF(d) ((d)->ops->initconf(d))
#define ESP32_WTD_PRE(d, v) ((d)->ops->pre(d, v))
#define ESP32_WTD_STO(d, v, s) ((d)->ops->settimeout(d, v, s))
#define ESP32_WTD_FEED(d) ((d)->ops->feed(d))
#define ESP32_WTD_STG_CONF(d, s, c) ((d)->ops->stg_conf(d, s, c))
#define ESP32_RWDT_CLK(d) ((d)->ops->rtc_clk(d))
#define ESP32_WTD_SETISR(d, hnd, arg) ((d)->ops->setisr(d, hnd, arg))
#define ESP32_WTD_ENABLEINT(d) ((d)->ops->enableint(d))
#define ESP32_WTD_DISABLEINT(d) ((d)->ops->disableint(d))
#define ESP32_WTD_ACKINT(d) ((d)->ops->ackint(d))
/****************************************************************************
* Public Types
****************************************************************************/
/* ESP32 WTD device */
struct esp32_wtd_dev_s
{
struct esp32_wtd_ops_s *ops;
};
/* ESP32 WTD ops */
/* This is a struct containing the pointers to the wtd operations */
struct esp32_wtd_ops_s
{
/* WTD tasks */
CODE int (*start)(FAR struct esp32_wtd_dev_s *dev);
CODE int (*stop)(FAR struct esp32_wtd_dev_s *dev);
/* WTD configuration */
CODE int (*enablewp)(FAR struct esp32_wtd_dev_s *dev);
CODE int (*disablewp)(FAR struct esp32_wtd_dev_s *dev);
CODE int (*initconf)(FAR struct esp32_wtd_dev_s *dev);
CODE int (*pre)(FAR struct esp32_wtd_dev_s *dev, uint16_t value);
CODE int (*settimeout)(FAR struct esp32_wtd_dev_s *dev,
uint32_t value, uint8_t stage);
CODE int (*feed)(FAR struct esp32_wtd_dev_s *dev);
CODE int (*stg_conf)(FAR struct esp32_wtd_dev_s *dev,
uint8_t stage, uint8_t conf);
CODE uint16_t (*rtc_clk)(FAR struct esp32_wtd_dev_s *dev);
/* WTD interrupts */
CODE int (*setisr)(FAR struct esp32_wtd_dev_s *dev, xcpt_t handler,
FAR void * arg);
CODE int (*enableint)(FAR struct esp32_wtd_dev_s *dev);
CODE int (*disableint)(FAR struct esp32_wtd_dev_s *dev);
CODE int (*ackint)(FAR struct esp32_wtd_dev_s *dev);
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
FAR struct esp32_wtd_dev_s *esp32_wtd_init(uint8_t wdt_id);
int esp32_wtd_deinit(FAR struct esp32_wtd_dev_s *dev);
#endif /* __ARCH_XTENSA_SRC_ESP32_ESP32_WTD_H */

View File

@ -0,0 +1,718 @@
/****************************************************************************
* arch/arm/src/esp32/esp32_wtd_lowerhalf.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdbool.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/timers/watchdog.h>
#include "xtensa.h"
#include "hardware/esp32_soc.h"
#include "esp32_wtd.h"
#include "esp32_wtd_lowerhalf.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define PRE_VALUE 40000 /* 40000 * 12.5 ns = 500 us */
/* Number of Cycles to have 1 ms period
* cycles = (1*10^-3 (s))*(f (Hz))
*/
#define MS_CYCLES_TIMER 2 /* 1 ms/(12.5 ns*PRE_VALUE) */
#define STAGE_0 0
#define STAGE_1 1
#define STAGE_2 2
#define STAGE_3 3
#define RESET_SYSTEM_RTC 4 /* Reset Main System + RTC */
#define RESET_SYSTEM_TIMER 3 /* Reset Main System */
#define INTERRUPT_ON_TIMEOUT 1
#define STAGES 4
#define FULL_STAGE 0xffffffff /* ((2^32)-1) */
#define MAX_MWDT_TIMEOUT_MS 0x7fffffff /* ((2^32)-1)/cycles */
/****************************************************************************
* Private Types
****************************************************************************/
/* This structure provides the private representation of the "lower-half"
* driver state structure. This structure must be cast-compatible with the
* well-known watchdog_lowerhalf_s structure.
*/
struct esp32_wtd_lowerhalf_s
{
FAR const struct watchdog_ops_s *ops; /* Lower half operations */
FAR struct esp32_wtd_dev_s *wtd; /* esp32 watchdog driver */
uint32_t timeout; /* The current timeout */
enum wdt_peripherals peripheral; /* Indicates if it is from RTC or Timer Module */
uint32_t lastreset; /* The last reset time */
bool started; /* True: Timer has been started */
xcpt_t handler; /* User Handler */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/* Interrupt handling *******************************************************/
static int esp32_wdt_handler(int irq, FAR void *context, FAR void *arg);
/* "Lower half" driver methods **********************************************/
static int esp32_wtd_start(FAR struct watchdog_lowerhalf_s *lower);
static int esp32_wtd_stop(FAR struct watchdog_lowerhalf_s *lower);
static int esp32_wtd_keepalive(FAR struct watchdog_lowerhalf_s *lower);
static int esp32_wtd_getstatus(FAR struct watchdog_lowerhalf_s *lower,
FAR struct watchdog_status_s *status);
static int esp32_wtd_settimeout(FAR struct watchdog_lowerhalf_s *lower,
uint32_t timeout);
static xcpt_t esp32_wtd_capture(FAR struct watchdog_lowerhalf_s *lower,
xcpt_t handler);
/****************************************************************************
* Private Data
****************************************************************************/
/* "Lower half" driver methods */
static const struct watchdog_ops_s g_esp32_wdg_ops =
{
.start = esp32_wtd_start,
.stop = esp32_wtd_stop,
.keepalive = esp32_wtd_keepalive,
.getstatus = esp32_wtd_getstatus,
.settimeout = esp32_wtd_settimeout,
.capture = esp32_wtd_capture,
.ioctl = NULL,
};
#ifdef CONFIG_ESP32_MWDT0
/* MWDT0 lower-half */
static struct esp32_wtd_lowerhalf_s g_esp32_mwdt0_lowerhalf =
{
.ops = &g_esp32_wdg_ops,
};
#endif
#ifdef CONFIG_ESP32_MWDT1
/* MWDT1 lower-half */
static struct esp32_wtd_lowerhalf_s g_esp32_mwdt1_lowerhalf =
{
.ops = &g_esp32_wdg_ops,
};
#endif
#ifdef CONFIG_ESP32_RWDT
/* RWDT lower-half */
static struct esp32_wtd_lowerhalf_s g_esp32_rwdt_lowerhalf =
{
.ops = &g_esp32_wdg_ops,
};
#endif
/****************************************************************************
* Name: esp32_wtd_start
*
* Description:
* Start the watchdog timer, register a callback if there is one and
* enables interrupt, otherwise, configure it to reset system on
* expiration.
*
* Input Parameters:
* lower - A pointer the publicly visible representation of the
* "lower-half" driver state structure.
*
* Returned Values:
* Zero on success; a negated errno value on failure.
*
****************************************************************************/
static int esp32_wtd_start(FAR struct watchdog_lowerhalf_s *lower)
{
FAR struct esp32_wtd_lowerhalf_s *priv =
(FAR struct esp32_wtd_lowerhalf_s *)lower;
int ret = OK;
irqstate_t flags;
wdinfo("Entry: started=%d\n");
DEBUGASSERT(priv);
if (priv->started == true)
{
/* Return EBUSY to indicate that the timer was already running */
ret = -EBUSY;
goto errout;
}
/* If WDT was not started yet */
else
{
priv->started = true;
/* Unlock WDT */
ESP32_WTD_UNLOCK(priv->wtd);
/* No User Handler */
if (priv->handler == NULL)
{
/* Then configure it to reset on wdt expiration */
if (priv->peripheral == TIMER)
{
ESP32_WTD_STG_CONF(priv->wtd, STAGE_0, RESET_SYSTEM_TIMER);
}
else
{
ESP32_WTD_STG_CONF(priv->wtd, STAGE_0, RESET_SYSTEM_RTC);
}
}
/* User handler was already provided */
else
{
/* Then configure it to call the user handler on wdt expiration */
ESP32_WTD_STG_CONF(priv->wtd, STAGE_0, INTERRUPT_ON_TIMEOUT);
/* Set the lower half handler and enable interrupt */
flags = enter_critical_section();
ESP32_WTD_SETISR(priv->wtd, esp32_wdt_handler, priv);
leave_critical_section(flags);
ESP32_WTD_ENABLEINT(priv->wtd);
}
flags = enter_critical_section();
priv->lastreset = clock_systime_ticks();
ESP32_WTD_START(priv->wtd);
leave_critical_section(flags);
/* Lock it again */
ESP32_WTD_LOCK(priv->wtd);
}
errout:
return ret;
}
/****************************************************************************
* Name: esp32_wtd_stop
*
* Description:
* Stop the watchdog timer. In case a callback was previously configured,
* unregister and deallocate it.
*
* Input Parameters:
* lower - A pointer the publicly visible representation of the
* "lower-half" driver state structure.
*
****************************************************************************/
static int esp32_wtd_stop(FAR struct watchdog_lowerhalf_s *lower)
{
FAR struct esp32_wtd_lowerhalf_s *priv =
(FAR struct esp32_wtd_lowerhalf_s *)lower;
irqstate_t flags;
/* Unlock WDT */
ESP32_WTD_UNLOCK(priv->wtd);
/* Disable the WDT */
ESP32_WTD_STOP(priv->wtd);
/* In case there is some callback registered, disable and deallocate */
if (priv->handler != NULL)
{
ESP32_WTD_DISABLEINT(priv->wtd);
flags = enter_critical_section();
ESP32_WTD_SETISR(priv->wtd, NULL, NULL);
leave_critical_section(flags);
}
/* Lock it again */
ESP32_WTD_LOCK(priv->wtd);
priv->started = false;
return OK;
}
/****************************************************************************
* Name: esp32_wtd_keepalive
*
* Description:
* Reset the watchdog timer, prevent any
* imminent watchdog timeouts. This is sometimes referred as "pinging"
* the watchdog timer or "petting the dog".
*
* Input Parameters:
* lower - A pointer the publicly visible representation of the
* "lower-half" driver state structure.
*
*
****************************************************************************/
static int esp32_wtd_keepalive(FAR struct watchdog_lowerhalf_s *lower)
{
FAR struct esp32_wtd_lowerhalf_s *priv =
(FAR struct esp32_wtd_lowerhalf_s *)lower;
irqstate_t flags;
wdinfo("Entry\n");
/* Unlock */
ESP32_WTD_UNLOCK(priv->wtd);
/* Feed the dog and updates the lastreset variable */
flags = enter_critical_section();
priv->lastreset = clock_systime_ticks();
ESP32_WTD_FEED(priv->wtd);
leave_critical_section(flags);
/* Lock */
ESP32_WTD_LOCK(priv->wtd);
return OK;
}
/****************************************************************************
* Name: esp32_wtd_getstatus
*
* Description:
* Get the current watchdog timer status
*
* Input Parameters:
* lower - A pointer the publicly visible representation of
* the "lower-half" driver state structure.
* status - The location to return the watchdog status information.
*
****************************************************************************/
static int esp32_wtd_getstatus(FAR struct watchdog_lowerhalf_s *lower,
FAR struct watchdog_status_s *status)
{
FAR struct esp32_wtd_lowerhalf_s *priv =
(FAR struct esp32_wtd_lowerhalf_s *)lower;
uint32_t ticks;
uint32_t elapsed;
DEBUGASSERT(priv);
/* Flags */
status->flags = 0;
/* If no handler was settled, then RESET on expiration.
* Otherwise, call the user handler.
*/
if (priv->handler == NULL)
{
status->flags |= WDFLAGS_RESET;
}
else
{
status->flags |= WDFLAGS_CAPTURE;
}
if (priv->started)
{
status->flags |= WDFLAGS_ACTIVE;
}
/* Return the current timeout in milliseconds */
status->timeout = priv->timeout;
/* Get the elapsed time since the last ping */
ticks = clock_systime_ticks() - priv->lastreset;
elapsed = (uint32_t)TICK2MSEC(ticks);
if (elapsed < priv->timeout)
{
/* Return the approximate time until the watchdog timer expiration */
status->timeleft = priv->timeout - elapsed;
}
else
{
status->timeleft = 0;
}
return OK;
}
/****************************************************************************
* Name: esp32_wtd_settimeout
*
* Description:
* Set a new timeout value (and reset the watchdog timer)
*
* Input Parameters:
* lower - A pointer the publicly visible representation of
* the "lower-half" driver state structure.
* timeout - The new timeout value in milliseconds.
*
* Returned Values:
* Zero on success; a negated errno value on failure.
*
****************************************************************************/
static int esp32_wtd_settimeout(FAR struct watchdog_lowerhalf_s *lower,
uint32_t timeout)
{
FAR struct esp32_wtd_lowerhalf_s *priv =
(FAR struct esp32_wtd_lowerhalf_s *)lower;
uint8_t rtc_cycles = 0;
uint32_t rtc_ms_max = 0;
wdinfo("Entry: timeout=%d\n", timeout);
DEBUGASSERT(priv);
/* Unlock WDT */
ESP32_WTD_UNLOCK(priv->wtd);
/* Write the timeout value */
priv->timeout = timeout;
/* Watchdog from Timer Module */
if (priv->peripheral == TIMER)
{
/* Is this timeout a valid value for Timer's WDT? */
if (timeout == 0 || timeout > MAX_MWDT_TIMEOUT_MS)
{
wderr("ERROR: Cannot represent timeout=%d > %d\n",
timeout, MAX_MWDT_TIMEOUT_MS);
return -ERANGE;
}
else
{
timeout = timeout*MS_CYCLES_TIMER;
ESP32_WTD_STO(priv->wtd, timeout, STAGE_0);
}
}
/* Watchdog from RTC Module */
else
{
rtc_cycles = ESP32_RWDT_CLK(priv->wtd);
rtc_ms_max = (uint32_t)(FULL_STAGE / rtc_cycles);
/* Is this timeout a valid value for RTC WDT? */
if (timeout == 0 || timeout > rtc_ms_max)
{
wderr("ERROR: Cannot represent timeout=%d > %d\n",
timeout, rtc_ms_max);
return -ERANGE;
}
else
{
timeout = timeout*rtc_cycles;
ESP32_WTD_STO(priv->wtd, timeout, STAGE_0);
}
}
/* Reset the wdt */
ESP32_WTD_FEED(priv->wtd);
/* Lock it again */
ESP32_WTD_LOCK(priv->wtd);
return OK;
}
/****************************************************************************
* Name: esp32_wtd_capture
*
* Description:
* Don't reset on watchdog timer timeout; instead, call this user provider
* timeout handler. NOTE: Providing handler==NULL will restore the reset
* behavior.
*
* Input Parameters:
* lower - A pointer the publicly visible representation of the
* "lower-half" driver state structure.
* newhandler - The new watchdog expiration function pointer. If this
* function pointer is NULL, then the reset-on-expiration
* behavior is restored,
*
* Returned Value:
* The previous watchdog expiration function pointer or NULL if there was
* no previous function pointer, i.e., if the previous behavior was
* reset-on-expiration (NULL is also returned if an error occurs).
*
****************************************************************************/
static xcpt_t esp32_wtd_capture(FAR struct watchdog_lowerhalf_s *lower,
xcpt_t handler)
{
FAR struct esp32_wtd_lowerhalf_s *priv =
(FAR struct esp32_wtd_lowerhalf_s *)lower;
irqstate_t flags;
xcpt_t oldhandler;
DEBUGASSERT(priv);
wdinfo("Entry: handler=%p\n", handler);
/* Get the old handler to return it */
oldhandler = priv->handler;
ESP32_WTD_UNLOCK(priv->wtd);
flags = enter_critical_section();
/* Save the new user handler */
priv->handler = handler;
/* There is a user callback and the timer has already been started.
* The user wants to set a callback after starting the wdt or wants to
* change the callback function once a callback has already been settled.
*/
if (priv->handler != NULL && priv->started == true)
{
/* Deallocate the previous allocated interrupt
* If there is a previous allocated interrupt.
*/
if (oldhandler != NULL)
{
ESP32_WTD_SETISR(priv->wtd, NULL, NULL);
}
else
{
/* If it was previous configured to reset on timeout
* then change to interrupt.
*/
ESP32_WTD_STG_CONF(priv->wtd, STAGE_0, INTERRUPT_ON_TIMEOUT);
}
/* Set the lower half handler and enable interrupt */
ESP32_WTD_SETISR(priv->wtd, esp32_wdt_handler, priv);
ESP32_WTD_ENABLEINT(priv->wtd);
}
/* In case the user wants to disable the callback */
else
{
ESP32_WTD_DISABLEINT(priv->wtd);
ESP32_WTD_SETISR(priv->wtd, NULL, NULL);
/* Then configure it to reset on wdt expiration */
if (priv->peripheral == TIMER)
{
ESP32_WTD_STG_CONF(priv->wtd, STAGE_0, RESET_SYSTEM_TIMER);
}
else
{
ESP32_WTD_STG_CONF(priv->wtd, STAGE_0, RESET_SYSTEM_RTC);
}
}
leave_critical_section(flags);
ESP32_WTD_LOCK(priv->wtd);
return oldhandler;
}
/* Interrupt handling *******************************************************/
static int esp32_wdt_handler(int irq, FAR void *context, FAR void *arg)
{
FAR struct esp32_wtd_lowerhalf_s *priv = arg;
ESP32_WTD_UNLOCK(priv->wtd);
/* Updates last reset var and feed the dog to reload the counter and
* to allow the application to continue executing.
*/
#ifdef CONFIG_DEBUG_WATCHDOG
priv->lastreset = clock_systime_ticks();
#endif
ESP32_WTD_FEED(priv->wtd);
/* Run the user callback */
priv->handler(irq, context, NULL);
ESP32_WTD_ACKINT(priv->wtd); /* Clear the Interrupt */
ESP32_WTD_LOCK(priv->wtd);
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: esp32_wtd_initialize
*
* Description:
* Initialize the WDT watchdog timer. The watchdog timer is initialized
* and registerd as 'devpath'.
*
* Input Parameters:
* devpath - The full path to the watchdog. This should
* be of the form/dev/watchdog0
* watchdog timer instance - A number do indicate which one is being used
*
* Returned Values:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure.
*
****************************************************************************/
int esp32_wtd_initialize(FAR const char *devpath, uint8_t wdt)
{
struct esp32_wtd_lowerhalf_s *lower = NULL;
FAR void *handle = NULL;
int ret = OK;
DEBUGASSERT(devpath);
switch (wdt)
{
#ifdef CONFIG_ESP32_MWDT0
case 0:
{
lower = &g_esp32_mwdt0_lowerhalf;
lower->peripheral = TIMER;
break;
}
#endif
#ifdef CONFIG_ESP32_MWDT1
case 1:
{
lower = &g_esp32_mwdt1_lowerhalf;
lower->peripheral = TIMER;
break;
}
#endif
#ifdef CONFIG_ESP32_RWDT
case 2:
{
lower = &g_esp32_rwdt_lowerhalf;
lower->peripheral = RTC;
break;
}
#endif
default:
{
ret = -ENODEV;
goto errout;
}
}
/* Initialize the elements of lower half state structure */
lower->started = false;
lower->handler = NULL;
lower->timeout = 0;
lower->wtd = esp32_wtd_init(wdt);
if (lower->wtd == NULL)
{
ret = -EINVAL;
goto errout;
}
ESP32_WTD_UNLOCK(lower->wtd);
/* Ensure stages are disabled and Flash boot protection was disabled */
ESP32_WTD_INITCONF(lower->wtd);
/* If it is a Main System Watchdog Timer configure the Prescale to
* have a 500us period.
*/
if (lower->peripheral == TIMER)
{
ESP32_WTD_PRE(lower->wtd, PRE_VALUE);
}
ESP32_WTD_LOCK(lower->wtd);
/* Register the watchdog driver as /dev/watchdogX. The returned value from
* watchdog_register is a handle that could be used with
* watchdog_unregister(). REVISIT: The returned handle is discarded here.
*/
handle = watchdog_register(devpath,
(FAR struct watchdog_lowerhalf_s *)lower);
if (handle == NULL)
{
/* The actual cause of the failure may have been a failure to allocate
* perhaps a failure to register the watchdog driver (such as if the
* 'devpath' were not unique). We know here but we return EEXIST to
* indicate the failure (implying the non-unique devpath).
*/
ret = -EEXIST;
goto errout;
}
errout:
return ret;
}

View File

@ -0,0 +1,52 @@
/****************************************************************************
* arch/xtensa/src/esp32/esp32_wtd_lowerhalf.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_XTENSA_SRC_ESP32_ESP32_WTD_LOWERHALF_H
#define __ARCH_XTENSA_SRC_ESP32_ESP32_WTD_LOWERHALF_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <esp32_tim.h>
/****************************************************************************
* Public Types
****************************************************************************/
enum wdt_peripherals
{
RTC,
TIMER,
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: esp32_timer_initialize
****************************************************************************/
int esp32_wtd_initialize(FAR const char *devpath, uint8_t timer);
#endif /* __ARCH_XTENSA_SRC_ESP32_ESP32_WTD_LOWERHALF_H */

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/xtensa/src/esp32/hardware/esp32_rtccnt.h
* arch/xtensa/src/esp32/hardware/esp32_rtccntl.h
*
* Adapted from use in NuttX by:
*
@ -37,6 +37,26 @@
* Pre-processor Definitions
****************************************************************************/
/* WTD defines */
/* Offset relative to each wathdog timer instance memory base */
/* RWDT */
#define RWDT_CONFIG0_OFFSET 0x008c
#define RWDT_STAGE0_TIMEOUT_OFFSET 0x0090
#define RWDT_STAGE1_TIMEOUT_OFFSET 0x0094
#define RWDT_STAGE2_TIMEOUT_OFFSET 0x0098
#define RWDT_STAGE3_TIMEOUT_OFFSET 0x009c
#define RWDT_WP_REG 0x00a4
#define RWDT_FEED_OFFSET 0x00a0
#define RCLK_CONF_REG_OFFSET 0x0070
#define RWDT_INT_ENA_REG_OFFSET 0x003c
#define RWDT_INT_CLR_REG_OFFSET 0x0048
/* CLK */
#define CK_XTAL_32K_MASK (BIT(30))
#define CK8M_D256_OUT_MASK (BIT(31))
#define RTC_CNTL_OPTIONS0_REG (DR_REG_RTCCNTL_BASE + 0x0)
/* RTC_CNTL_SW_SYS_RST : WO ;bitpos:[31] ;default: 1'd0 ; */

View File

@ -197,7 +197,7 @@
#define APB_CLK_FREQ 80 * 1000000 /* Unit: Hz */
#define REF_CLK_FREQ (1000000)
#define UART_CLK_FREQ APB_CLK_FREQ
#define WDT_CLK_FREQ APB_CLK_FREQ
#define MWDT_CLK_FREQ APB_CLK_FREQ
#define TIMER_CLK_FREQ (80000000 >> 4) /* 80MHz divided by 16 */
#define SPI_CLK_DIV 4
#define TICKS_PER_US_ROM 26 /* CPU is 80MHz */

View File

@ -46,6 +46,25 @@
#define TIM1_INT_ST_OFFSET 0x007c
#define LOW_32_MASK 0xffffffff
/* WTD defines */
#define WRITE_PROTECTION_KEY 0x050d83aa1
/* Offset relative to each watchdog timer instance memory base */
#define MWDT_CONFIG0_OFFSET 0x0000
/* MWDTs */
#define MWDT_CLK_PRESCALE_OFFSET 0x0004
#define MWDT_STAGE0_TIMEOUT_OFFSET 0x0008
#define MWDT_STAGE1_TIMEOUT_OFFSET 0x000c
#define MWDT_STAGE2_TIMEOUT_OFFSET 0x0010
#define MWDT_STAGE3_TIMEOUT_OFFSET 0x0014
#define MWDT_WP_REG 0x001c
#define MWDT_FEED_OFFSET 0x0018
#define MWDT_INT_ENA_REG_OFFSET 0x0050
#define MWDT_INT_CLR_REG_OFFSET 0x005c
/* The value that needs to be written to TIMG_WDT_WKEY to write-enable the wdt
* registers
*/

View File

@ -0,0 +1,55 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_ARCH_LEDS is not set
# CONFIG_NSH_ARGCAT is not set
# CONFIG_NSH_CMDOPT_HEXDUMP is not set
# CONFIG_NSH_CMDPARMS is not set
CONFIG_ARCH="xtensa"
CONFIG_ARCH_BOARD="esp32-core"
CONFIG_ARCH_BOARD_ESP32CORE=y
CONFIG_ARCH_CHIP="esp32"
CONFIG_ARCH_CHIP_ESP32=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_XTENSA=y
CONFIG_BOARD_LOOPSPERMSEC=16717
CONFIG_BUILTIN=y
CONFIG_DEBUG_FEATURES=y
CONFIG_DEBUG_WATCHDOG=y
CONFIG_ESP32_MWDT0=y
CONFIG_ESP32_MWDT1=y
CONFIG_ESP32_UART0=y
CONFIG_EXAMPLES_WATCHDOG=y
CONFIG_EXPERIMENTAL=y
CONFIG_FS_PROCFS=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_IDLETHREAD_STACKSIZE=3072
CONFIG_INTELHEX_BINARY=y
CONFIG_MAX_TASKS=16
CONFIG_MM_REGIONS=2
CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_LINELEN=64
CONFIG_NSH_READLINE=y
CONFIG_PREALLOC_TIMERS=4
CONFIG_RAM_SIZE=114688
CONFIG_RAM_START=0x20000000
CONFIG_RAW_BINARY=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SPI=y
CONFIG_START_DAY=6
CONFIG_START_MONTH=12
CONFIG_START_YEAR=2011
CONFIG_SYSTEM_NSH=y
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y

View File

@ -70,6 +70,12 @@ ifeq ($(CONFIG_USERLED),y)
CSRCS += esp32_userleds.c
endif
ifeq ($(CONFIG_WATCHDOG),y)
ifeq ($(CONFIG_ESP32_WTD),y)
CSRCS += esp32_wtd.c
endif
endif
SCRIPTIN = $(SCRIPTDIR)$(DELIM)esp32.template.ld
SCRIPTOUT = $(SCRIPTDIR)$(DELIM)esp32_out.ld

View File

@ -104,7 +104,18 @@ int esp32_spiflash_init(void);
****************************************************************************/
#ifdef CONFIG_TIMER
int esp32_timer_driver_setup(FAR const char *devpath, int timer);
int esp32_timer_driver_init(void);
#endif
/****************************************************************************
* Name: esp32_wdt_driver_init
*
* Description:
* Initialize WATCHDOG driver.
*
****************************************************************************/
#ifdef CONFIG_WATCHDOG
int esp32_wtd_driver_init(void);
#endif
#endif /* __ASSEMBLY__ */

View File

@ -49,6 +49,7 @@
#include <sys/mount.h>
#include <syslog.h>
#include <debug.h>
#include <stdio.h>
#ifdef CONFIG_TIMER
# include <nuttx/timers/timer.h>
@ -72,22 +73,6 @@
* Pre-processor Definitions
****************************************************************************/
#ifdef CONFIG_ESP32_TIMER0
#define ESP32_TIMER0 (0)
#endif
#ifdef CONFIG_ESP32_TIMER1
#define ESP32_TIMER1 (1)
#endif
#ifdef CONFIG_ESP32_TIMER2
#define ESP32_TIMER2 (2)
#endif
#ifdef CONFIG_ESP32_TIMER3
#define ESP32_TIMER3 (3)
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
@ -219,45 +204,15 @@ int esp32_bringup(void)
#ifdef CONFIG_TIMER
/* Configure TIMER driver */
#ifdef CONFIG_ESP32_TIMER0
ret = esp32_timer_driver_setup("/dev/timer0", ESP32_TIMER0);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize timer driver: %d\n",
ret);
}
#endif
#ifdef CONFIG_ESP32_TIMER1
ret = esp32_timer_driver_setup("/dev/timer1", ESP32_TIMER1);
ret = esp32_timer_driver_init();
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize timer driver: %d\n",
"ERROR: Failed to initialize timer drivers: %d\n",
ret);
}
#endif
#ifdef CONFIG_ESP32_TIMER2
ret = esp32_timer_driver_setup("/dev/timer2", ESP32_TIMER2);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize timer driver: %d\n",
ret);
}
#endif
#ifdef CONFIG_ESP32_TIMER3
ret = esp32_timer_driver_setup("/dev/timer3", ESP32_TIMER3);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize timer driver: %d\n",
ret);
}
#endif
#endif
#ifdef CONFIG_USERLED
@ -270,6 +225,19 @@ int esp32_bringup(void)
}
#endif
#ifdef CONFIG_WATCHDOG
/* Configure WATCHDOG driver */
ret = esp32_wtd_driver_init();
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize watchdog drivers: %d\n",
ret);
}
#endif
/* If we got here then perhaps not all initialization was successful, but
* at least enough succeeded to bring-up NSH with perhaps reduced
* capabilities.

View File

@ -24,12 +24,30 @@
#include <nuttx/config.h>
#include <nuttx/timers/timer.h>
#include <debug.h>
#include "esp32_tim_lowerhalf.h"
#include "esp32-core.h"
#include <sys/types.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifdef CONFIG_ESP32_TIMER0
#define ESP32_TIMER0 (0)
#endif
#ifdef CONFIG_ESP32_TIMER1
#define ESP32_TIMER1 (1)
#endif
#ifdef CONFIG_ESP32_TIMER2
#define ESP32_TIMER2 (2)
#endif
#ifdef CONFIG_ESP32_TIMER3
#define ESP32_TIMER3 (3)
#endif
/****************************************************************************
* Public Functions
@ -52,7 +70,53 @@
*
****************************************************************************/
int esp32_timer_driver_setup(FAR const char *devpath, int timer)
int esp32_timer_driver_init(void)
{
return esp32_timer_initialize(devpath, timer);
int ret = OK;
#ifdef CONFIG_ESP32_TIMER0
ret = esp32_timer_initialize("/dev/timer0", ESP32_TIMER0);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize timer driver: %d\n",
ret);
goto errout;
}
#endif
#ifdef CONFIG_ESP32_TIMER1
ret = esp32_timer_initialize("/dev/timer1", ESP32_TIMER1);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize timer driver: %d\n",
ret);
goto errout;
}
#endif
#ifdef CONFIG_ESP32_TIMER2
ret = esp32_timer_initialize("/dev/timer2", ESP32_TIMER2);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize timer driver: %d\n",
ret);
goto errout;
}
#endif
#ifdef CONFIG_ESP32_TIMER3
ret = esp32_timer_initialize("/dev/timer3", ESP32_TIMER3);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize timer driver: %d\n",
ret);
goto errout;
}
#endif
errout:
return ret;
}

View File

@ -0,0 +1,110 @@
/****************************************************************************
* boards/xtensa/esp32/esp32-core/src/esp32_wtd.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <debug.h>
#include "esp32_wtd_lowerhalf.h"
#include "esp32-core.h"
#include <sys/types.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifdef CONFIG_ESP32_MWDT0
#define ESP32_MWDT0 (0)
#endif
#ifdef CONFIG_ESP32_MWDT1
#define ESP32_MWDT1 (1)
#endif
#ifdef CONFIG_ESP32_RWDT
#define ESP32_RWDT (2)
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: esp32_wtd_driver_init
*
* Description:
* Configure the timer driver.
*
* Input Parameters:
* devpath - The full path to the timer device. This should be of the
* form /dev/watchdogX
* wdt timer - The wdt timer's number.
*
* Returned Value:
* Zero (OK) is returned on success; A negated errno value is returned
* to indicate the nature of any failure.
*
****************************************************************************/
int esp32_wtd_driver_init(void)
{
int ret = OK;
#ifdef CONFIG_ESP32_MWDT0
ret = esp32_wtd_initialize("/dev/watchdog0", ESP32_MWDT0);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize watchdog driver: %d\n",
ret);
goto errout;
}
#endif
#ifdef CONFIG_ESP32_MWDT1
ret = esp32_wtd_initialize("/dev/watchdog1", ESP32_MWDT1);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize watchdog driver: %d\n",
ret);
goto errout;
}
#endif
#ifdef CONFIG_ESP32_RWDT
ret = esp32_wtd_initialize("/dev/watchdog2", ESP32_RWDT);
if (ret < 0)
{
syslog(LOG_ERR,
"ERROR: Failed to initialize watchdog driver: %d\n",
ret);
goto errout;
}
#endif
errout:
return ret;
}