summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-15 16:20:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-15 16:20:25 +0000
commit3a3fe9efb1e3f0fe6a756b8e4d2fa48d5564137b (patch)
tree13d2c82c982b760b250741f7167faf0d509ecbc4 /nuttx/include
parentf1893cbaf513c7f0fbca77240fc59707ad039734 (diff)
downloadpx4-nuttx-3a3fe9efb1e3f0fe6a756b8e4d2fa48d5564137b.tar.gz
px4-nuttx-3a3fe9efb1e3f0fe6a756b8e4d2fa48d5564137b.tar.bz2
px4-nuttx-3a3fe9efb1e3f0fe6a756b8e4d2fa48d5564137b.zip
Add code changes from Uros
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3507 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/clock.h56
-rwxr-xr-xnuttx/include/nuttx/ptimer.h245
2 files changed, 157 insertions, 144 deletions
diff --git a/nuttx/include/nuttx/clock.h b/nuttx/include/nuttx/clock.h
index e06d2c0dd..4d641696f 100644
--- a/nuttx/include/nuttx/clock.h
+++ b/nuttx/include/nuttx/clock.h
@@ -49,19 +49,6 @@
* Pro-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
-/* Access to raw system clock ***********************************************/
-/* The system timer/counter is supported only if (1) the system clock is not
- * disabled and (2) we are not configured to use a hardware periodic timer
- * for system time.
- */
-
-#undef __HAVE_SYSTEM_COUNTER
-#if !defined(CONFIG_DISABLE_CLOCK) && !defined(CONFIG_PTIMER)
-# define __HAVE_SYSTEM_COUNTER 1
-#else
-# define __HAVE_SYSTEM_COUNTER 0
-#endif
-
/* Efficient, direct access to OS global timer variables will be supported
* if the execution environment has direct access to kernel global data.
* The code in this execution context can access the kernel global data
@@ -157,10 +144,6 @@ extern volatile uint32_t g_uptime;
* Global Function Prototypes
****************************************************************************/
-/****************************************************************************
- * Global Function Prototypes
- ****************************************************************************/
-
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C" {
@@ -168,15 +151,46 @@ extern "C" {
#define EXTERN extern
#endif
-/* Indirect access to the system time is required if (1) we are using a
- * hardware periodic timer, OR (2) the execution environment does not have
- * direct access to kernel global data
- */
+/****************************************************************************
+ * Function: clock_systimer
+ *
+ * Description:
+ * Return the current value of the system timer counter. Indirect access
+ * to the system timer counter is required through this function if (1) we
+ * are using a hardware periodic timer, OR (2) the execution environment
+ * does not have direct access to kernel global data
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * The current value of the system timer counter
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
#if defined(CONFIG_PTIMER) || !__HAVE_KERNEL_GLOBALS
EXTERN uint32_t clock_systimer(void);
#endif
+/****************************************************************************
+ * Function: clock_uptime
+ *
+ * Description:
+ * Return the current value of the system timer counter, which is only
+ * enabled when system is in active mode.
+ *
+ * Parameters:
+ * None
+ *
+ * Return Value:
+ * The current value of the system time counter
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
#if defined(CONFIG_UPTIME) && !__HAVE_KERNEL_GLOBALS
EXTERN time_t clock_uptime(void);
#endif
diff --git a/nuttx/include/nuttx/ptimer.h b/nuttx/include/nuttx/ptimer.h
index b5b5d65ae..19d493bf7 100755
--- a/nuttx/include/nuttx/ptimer.h
+++ b/nuttx/include/nuttx/ptimer.h
@@ -1,123 +1,122 @@
-/****************************************************************************
- * include/nuttx/ptimer.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_PTIMER_H
-#define __INCLUDE_NUTTX_PTIMER_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-
-#include <time.h>
-#include <stdint.h>
-#include <stdbool.h>
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* Configuration ************************************************************/
-
-/* Access macros ************************************************************/
-
-/* Clock manipulation macros ************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/* The type of the periodic timer callback function */
-
-typedef void (*ptimer_handler_t)(FAR void *arg);
-
-/* The periodic timer vtable */
-
-struct ptimer_dev_s;
-struct ptimer_ops_s
-{
- int (*trigger)(FAR struct ptimer_dev_s *dev, FAR void *arg);
- int (*add)(FAR struct ptimer_dev_s *dev, FAR void *arg, clock_t period);
- int (*set)(FAR struct ptimer_dev_s *dev, FAR void *arg, clock_t period);
- int (*clear)(FAR struct ptimer_dev_s *dev, FAR void *arg);
- clock_t (*remainder)(FAR struct ptimer_dev_s *dev, FAR void *arg);
- clock_t (*overrun)(FAR struct ptimer_dev_s *dev, FAR void *arg);
- int (*exec)(FAR struct ptimer_dev_s *dev, clock_t timeout);
-};
-
-/* PTIMER private data. This structure only defines the initial fields of the
- * structure visible to the SPI client. The specific implementation may
- * add additional, device specific fields
- */
-
-struct ptimer_dev_s
-{
- FAR const struct ptimer_ops_s *ops;
-};
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/****************************************************************************
- * Name: up_ptimerinitialize
- *
- * Description:
- * Initialize the periodic timer interface. This function may be called to
- * obtian multiple instances of the interface
- *
- * Returned Value:
- * Valid peridic timer device structre reference on succcess; a NULL on failure
- *
- ****************************************************************************/
-
-EXTERN FAR struct ptimer_dev_s *up_ptimerinitialize(void);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-#endif /* __INCLUDE_NUTTX_PTIMER_H */
+/****************************************************************************
+ * include/nuttx/ptimer.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_PTIMER_H
+#define __INCLUDE_NUTTX_PTIMER_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#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
+ ****************************************************************************/
+
+/****************************************************************************
+ * 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 /* CONFIG_PTIMER */
+#endif /* __INCLUDE_NUTTX_PTIMER_H */