summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rtc.c2
-rw-r--r--nuttx/configs/vsn/src/sif.c4
-rw-r--r--nuttx/include/nuttx/clock.h15
-rwxr-xr-xnuttx/include/nuttx/ptimer.h47
-rwxr-xr-xnuttx/include/nuttx/rtc.h118
-rw-r--r--nuttx/lib/time/Make.defs2
-rw-r--r--nuttx/sched/Makefile5
-rw-r--r--nuttx/sched/clock_initialize.c15
-rw-r--r--nuttx/sched/clock_systimer.c8
-rw-r--r--nuttx/sched/clock_uptime.c3
10 files changed, 140 insertions, 79 deletions
diff --git a/nuttx/arch/arm/src/stm32/stm32_rtc.c b/nuttx/arch/arm/src/stm32/stm32_rtc.c
index ec0afdc35..17b611008 100644
--- a/nuttx/arch/arm/src/stm32/stm32_rtc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_rtc.c
@@ -59,7 +59,7 @@
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
-#include <nuttx/ptimer.h>
+#include <nuttx/rtc.h>
#include <arch/board/board.h>
#include <stdlib.h>
diff --git a/nuttx/configs/vsn/src/sif.c b/nuttx/configs/vsn/src/sif.c
index 555c43f63..7a510da24 100644
--- a/nuttx/configs/vsn/src/sif.c
+++ b/nuttx/configs/vsn/src/sif.c
@@ -514,9 +514,9 @@ int sif_main(int argc, char *argv[])
else if (!strcmp(argv[1], "i2c") && argc == 3) {
int val = atoi(argv[2]);
- I2C_SETFREQUENCY(vsn_sif.i2c2, 100000);
+ I2C_SETFREQUENCY(vsn_sif.i2c1, 100000);
- struct st_lis331dl_dev_s * lis = st_lis331dl_init(vsn_sif.i2c2, val);
+ struct st_lis331dl_dev_s * lis = st_lis331dl_init(vsn_sif.i2c1, val);
if (lis) {
struct st_lis331dl_vector_s * a;
diff --git a/nuttx/include/nuttx/clock.h b/nuttx/include/nuttx/clock.h
index 4d641696f..62bc29910 100644
--- a/nuttx/include/nuttx/clock.h
+++ b/nuttx/include/nuttx/clock.h
@@ -125,19 +125,18 @@
* access to kernel global data
*/
-#if !defined(CONFIG_PTIMER) && __HAVE_KERNEL_GLOBALS
+#if __HAVE_KERNEL_GLOBALS
extern volatile uint32_t g_system_timer;
-#define clock_systimer() g_system_timer
+extern volatile uint32_t g_uptime;
#endif
-/* System uptime (in seconds) is only supported by periodic timer hardware */
+#if !defined(CONFIG_RTC) && __HAVE_KERNEL_GLOBALS
+#define clock_systimer() g_system_timer
#if defined(CONFIG_UPTIME)
-extern volatile uint32_t g_uptime;
-
-#if __HAVE_KERNEL_GLOBALS
-# define clock_uptime() g_uptime
+#define clock_uptime() g_uptime
#endif
+
#endif
/****************************************************************************
@@ -170,7 +169,7 @@ extern "C" {
*
****************************************************************************/
-#if defined(CONFIG_PTIMER) || !__HAVE_KERNEL_GLOBALS
+#if defined(CONFIG_RTC) || !__HAVE_KERNEL_GLOBALS
EXTERN uint32_t clock_systimer(void);
#endif
diff --git a/nuttx/include/nuttx/ptimer.h b/nuttx/include/nuttx/ptimer.h
index 19d493bf7..a8bac82fe 100755
--- a/nuttx/include/nuttx/ptimer.h
+++ b/nuttx/include/nuttx/ptimer.h
@@ -42,21 +42,10 @@
#include <nuttx/config.h>
-#include <time.h>
-#include <stdint.h>
-#include <stdbool.h>
-
-#include <nuttx/clock.h>
-
-#ifdef CONFIG_PTIMER
-
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-#define RTC_CLOCKS_PER_SEC 16384
-#define RTC_CLOCKS_SHIFT 14
-
/****************************************************************************
* Public Types
****************************************************************************/
@@ -65,15 +54,6 @@
* Public Variables
****************************************************************************/
-/* Variable determines the state of the RTC module.
- *
- * After initialization value is set to 'true' if RTC starts successfully.
- * The value can be changed to false also during operation if RTC for
- * some reason fails.
- */
-
-extern volatile bool g_rtc_enabled;
-
/****************************************************************************
* Public Functions
****************************************************************************/
@@ -86,37 +66,10 @@ extern "C" {
#define EXTERN extern
#endif
-/****************************************************************************
- * Name: up_rtcinitialize
- *
- * Description:
- * Initialize the periodic timer interface. This function is called once
- * from the clock_initialize() function.
- *
- * Returned Value:
- * Returns OK if RTC has successfully started, otherwise ERROR.
- *
- ****************************************************************************/
-
-EXTERN int up_rtcinitialize(void);
-EXTERN int up_rtcinitialize(void);
-
-EXTERN clock_t up_rtc_getclock(void);
-EXTERN void up_rtc_setclock(clock_t clock);
-
-EXTERN time_t up_rtc_gettime(void);
-EXTERN void up_rtc_settime(time_t time);
-
-EXTERN clock_t up_rtc_setalarm(clock_t atclock);
-
-/* This callback is provided by the clock module and called by the RTC ISR */
-
-EXTERN void clock_rtcalarmcb(clock_t clock);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
-#endif /* CONFIG_PTIMER */
#endif /* __INCLUDE_NUTTX_PTIMER_H */
diff --git a/nuttx/include/nuttx/rtc.h b/nuttx/include/nuttx/rtc.h
new file mode 100755
index 000000000..5d9ae6341
--- /dev/null
+++ b/nuttx/include/nuttx/rtc.h
@@ -0,0 +1,118 @@
+/****************************************************************************
+ * include/nuttx/rtc.h
+ *
+ * Copyright(C) 2011 Uros Platise. All rights reserved.
+ * Author: Uros Platise <uros.platise@isotel.eu>
+ *
+ * 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 __INCLUDE_NUTTX_RTC_H
+#define __INCLUDE_NUTTX_RTC_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#include <nuttx/clock.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define RTC_CLOCKS_PER_SEC 16384
+#define RTC_CLOCKS_SHIFT 14
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/* Variable determines the state of the RTC module.
+ *
+ * After initialization value is set to 'true' if RTC starts successfully.
+ * The value can be changed to false also during operation if RTC for
+ * some reason fails.
+ */
+
+extern volatile bool g_rtc_enabled;
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Name: up_rtcinitialize
+ *
+ * Description:
+ * Initialize the periodic timer interface. This function is called once
+ * from the clock_initialize() function.
+ *
+ * Returned Value:
+ * Returns OK if RTC has successfully started, otherwise ERROR.
+ *
+ ****************************************************************************/
+
+EXTERN int up_rtcinitialize(void);
+EXTERN int up_rtcinitialize(void);
+
+EXTERN clock_t up_rtc_getclock(void);
+EXTERN void up_rtc_setclock(clock_t clock);
+
+EXTERN time_t up_rtc_gettime(void);
+EXTERN void up_rtc_settime(time_t time);
+
+EXTERN clock_t up_rtc_setalarm(clock_t atclock);
+
+/* This callback is provided by the clock module and called by the RTC ISR */
+
+EXTERN void clock_rtcalarmcb(clock_t clock);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_RTC_H */
diff --git a/nuttx/lib/time/Make.defs b/nuttx/lib/time/Make.defs
index 652019f5b..d65ba50f6 100644
--- a/nuttx/lib/time/Make.defs
+++ b/nuttx/lib/time/Make.defs
@@ -34,4 +34,4 @@
############################################################################
TIME_SRCS = lib_mktime.c lib_gmtime.c lib_gmtimer.c lib_strftime.c \
- lib_calendar2utc.c lib_daysbeforemonth.c lib_isleapyear.c
+ lib_calendar2utc.c lib_daysbeforemonth.c lib_isleapyear.c lib_time.c
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 20e3522d0..bc2852c54 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -78,14 +78,11 @@ endif
CLOCK_SRCS = clock_initialize.c clock_settime.c clock_gettime.c clock_getres.c \
clock_time2ticks.c clock_abstime2ticks.c clock_ticks2time.c \
- clock_gettimeofday.c
+ clock_gettimeofday.c clock_systimer.c
-ifeq ($(CONFIG_NUTTX_KERNEL),y)
-CLOCK_SRCS += clock_systimer.c
ifeq ($(CONFIG_UPTIME),y)
CLOCK_SRCS += clock_uptime.c
endif
-endif
SIGNAL_SRCS = sig_initialize.c \
sig_action.c sig_procmask.c sig_pending.c sig_suspend.c \
diff --git a/nuttx/sched/clock_initialize.c b/nuttx/sched/clock_initialize.c
index 0079e9f57..2bb4d87a8 100644
--- a/nuttx/sched/clock_initialize.c
+++ b/nuttx/sched/clock_initialize.c
@@ -46,6 +46,7 @@
#include <nuttx/clock.h>
#include <nuttx/time.h>
+#include <nuttx/rtc.h>
#include "clock_internal.h"
@@ -152,10 +153,7 @@ static inline void incr_uptime(void)
void clock_initialize(void)
{
- time_t jdn;
-#ifdef CONFIG_PTIMER
- bool rtc_enabled = false;
-#endif
+ time_t jdn = 0;
/* Initialize the real time close (this should be un-nesssary except on a
* restart).
@@ -169,18 +167,13 @@ void clock_initialize(void)
/* Do we have hardware periodic timer support? */
#ifdef CONFIG_RTC
- if (up_rtcinitialize() == OK)
- {
- rtc_enabled = true;
- }
-#endif
+ up_rtcinitialize();
/* Get the EPOCH-relative julian date from the calendar year,
* month, and date
*/
-#ifdef CONFIG_PTIMER
- if (!rtc_enabled)
+ if (g_rtc_enabled==false)
#endif
{
jdn = clock_calendar2utc(CONFIG_START_YEAR, CONFIG_START_MONTH,
diff --git a/nuttx/sched/clock_systimer.c b/nuttx/sched/clock_systimer.c
index fde303be6..c4560a8a1 100644
--- a/nuttx/sched/clock_systimer.c
+++ b/nuttx/sched/clock_systimer.c
@@ -42,7 +42,7 @@
#include <stdint.h>
#include <nuttx/clock.h>
-#include <nuttx/ptimer.h>
+#include <nuttx/rtc.h>
#include <nuttx/time.h>
#if !defined(clock_systimer) /* See nuttx/clock.h */
@@ -79,17 +79,17 @@ uint32_t clock_systimer(void)
{
/* Fetch the g_system_timer value from timer hardware, if available */
-#ifdef CONFIG_PTIMER
+#ifdef CONFIG_RTC
/* Check if the periodic timer is initialized
*
* Note that the unit of the g_system_timer and and up_rtc_getclock() must
- * be the same in order.
+ * be the same in order (must have same [unit]) to allow smooth transitions.
*/
if (g_rtc_enabled)
{
- up_rtc_getclock();
+// return up_rtc_getclock();
}
#endif
diff --git a/nuttx/sched/clock_uptime.c b/nuttx/sched/clock_uptime.c
index cea3262c8..203d056fd 100644
--- a/nuttx/sched/clock_uptime.c
+++ b/nuttx/sched/clock_uptime.c
@@ -42,6 +42,7 @@
#include <stdint.h>
#include <nuttx/clock.h>
#include <nuttx/time.h>
+#include <nuttx/rtc.h>
#if !defined(CONFIG_DISABLE_CLOCK) && defined(CONFIG_UPTIME) && !defined(clock_uptime)
@@ -76,7 +77,7 @@
time_t clock_uptime(void)
{
-#ifdef CONFIG_PTIMER
+#ifdef CONFIG_RTC
if (g_rtc_enabled)
{
return up_rtc_gettime();