summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-20 13:32:49 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-20 13:32:49 +0000
commitfb0960f36c48d3dc2e21d3f5193788f23b6bfa48 (patch)
treed0e355e0baa6cdfe2bc68f770341c1e12ad68f7f /nuttx/include
parent60af61e86dfef73118ca1b21052085819df772a8 (diff)
downloadpx4-nuttx-fb0960f36c48d3dc2e21d3f5193788f23b6bfa48.tar.gz
px4-nuttx-fb0960f36c48d3dc2e21d3f5193788f23b6bfa48.tar.bz2
px4-nuttx-fb0960f36c48d3dc2e21d3f5193788f23b6bfa48.zip
Updates from Uros
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3527 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rwxr-xr-xnuttx/include/nuttx/event.h235
-rw-r--r--nuttx/include/nuttx/sensors/st_lis331dl.h35
-rwxr-xr-xnuttx/include/nuttx/wireless/chipcon_cc1101.h (renamed from nuttx/include/nuttx/ptimer.h)86
3 files changed, 297 insertions, 59 deletions
diff --git a/nuttx/include/nuttx/event.h b/nuttx/include/nuttx/event.h
new file mode 100755
index 000000000..dfa3a585c
--- /dev/null
+++ b/nuttx/include/nuttx/event.h
@@ -0,0 +1,235 @@
+/****************************************************************************
+ * include/nuttx/event.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.
+ *
+ ****************************************************************************/
+
+/** \file
+ * \author Uros Platise
+ * \brief Events
+ *
+ * Event moudle offer real-time signaling and handling of real-time
+ * events at precision of system resolution clock_t.
+ *
+ * Events are based on periodic timers, where each started event starts
+ * counting at its relative time = 0, and overflows at given period.
+ * Overflow is signalized by posted event that is handled by the
+ * event_eventhandler() called by each thread or task working with
+ * Events.
+ *
+ * Events may be used inside one thread or task only or between tasks
+ * and threads. An event can also be bind to another event i.e.:
+ * - System Clock may issue a notification about Power Failure
+ * - Other threads may connect to this event and when handled, they may
+ * inquiry for pricise time when this event has happend, using the
+ * event_gettime()
+ *
+ * Or system is about to control a process, and instead of looping and
+ * inquiring for time, system timers offer simple and effective
+ * mechanism to control timed actions:
+ * - First event is about to wait 5 seconds, then it must assert some
+ * switch, triggering another event after 2 seconds, to check the
+ * state of the system.
+ * - After 2 seconds new event is triggerred, if it is time criticial
+ * it may check for the overrun time and handle further actions,
+ * - ...
+ *
+ * Each event is denoted by a callback function event_callback_t, and
+ * an argument. Posted event with the same callback but different
+ * argument is treated as different event, while the same callback with
+ * the same argument replaces previously started event.
+ **/
+
+#ifdef CONFIG_EVENT
+
+#ifndef __INCLUDE_NUTTX_EVENT_H
+#define __INCLUDE_NUTTX_EVENT_H
+
+#include <nuttx/config.h>
+
+#include <time.h>
+#include <stdint.h>
+#include <stdbool.h>
+
+#include <nuttx/clock.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/** Event Callback
+ *
+ * \param arg an argument as posted by the event_post(),
+ * event_signal() or event_start() methods.
+ *
+ * \return Optional time to increment to retrigger. This time is added
+ * to present actual time, so an event returning with constant value
+ * as return PERIOD would be periodic with long-term absolute precision.
+ *
+ * \retval >0 Time to increment to second post of the event.
+ * \retval 0 Acknowledge event.
+ */
+typedef clock_t (*event_callback_t)(FAR void *arg);
+
+typedef struct event_s event_t;
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/** Create new instance of Events (typically per thread)
+ *
+ * \param base Future extension to support multiple base timers. Pass NULL at
+ * the moment.
+ *
+ * \return Valid structure or NULL on error with errno set.
+ */
+event_t * event_create( void * base );
+
+/** Delete unused instance of Events. A call to this function also destroys
+ * all bindings.
+ *
+ * \param events Pointer to a structure as returned by event_create()
+ * \return 0 On success or -1 on error.
+ */
+int event_delete( event_t *events );
+
+/** Post an event, equal to period = 0
+ *
+ * \param events Pointer to a structure as returned by event_create()
+ * \param event Callback to be called
+ * \param arg Optional argument to be passed to the event.
+ * \return 0 On success or -1 on error.
+ */
+int event_post( event_t *events, event_callback_t event, void *arg );
+
+/** Trigger an event without calling it but may trigger connected events
+ *
+ * \param events Pointer to a structure as returned by event_create()
+ * \param event Callback to be called
+ * \param arg Optional argument to be passed to the event.
+ * \return 0 On success or -1 on error.
+ */
+int event_signal( event_t *events, event_callback_t event, void *arg );
+
+/** Start timer with given period
+ *
+ * \param events Pointer to a structure as returned by event_create()
+ * \param event Callback to be called
+ * \param arg Optional argument to be passed to the event.
+ * \param period Time to first occurence.
+ * \return 0 On success or -1 on error.
+ */
+int event_start( event_t *events, event_callback_t event, void *arg, clock_t period );
+
+/** Stop timer, matches only those with equal event and arg.
+ *
+ * \param events Pointer to a structure as returned by event_create()
+ * \param event Callback to be called
+ * \param arg Optional argument to be passed to the event.
+ * \return 0 On success or -1 on error.
+ */
+int event_stop( event_t *events, event_callback_t event, void *arg );
+
+/** Stop all timers related to the same event callback
+ *
+ * \param events Pointer to a structure as returned by event_create()
+ * \param event Callback to be called
+ * \return 0 On success or -1 on error.
+ */
+int event_stopall( event_t *events, event_callback_t event );
+
+/** Get present time of given timer
+ *
+ * \param events Pointer to a structure as returned by event_create()
+ * \param event Callback to be called
+ * \param arg Optional argument to be passed to the event.
+ * \return 0 On success or -1 on error.
+ */
+clock_t event_gettime( event_t *events, event_callback_t event, void *arg );
+
+/** Bind two events
+ *
+ * \param source_events Pointer to source event structure.
+ * \param source_event Source event
+ * \param dest_events Pointer to destination event structure
+ * \param dest_event Destination event to be called, when source fires
+ * \return 0 On success or -1 on error.
+ */
+int event_connect(event_t *source_events, event_callback_t source_event,
+ event_t *dest_events, event_callback_t dest_event);
+
+/** Unbind two events
+ *
+ * \param source_events Pointer to source event structure.
+ * \param source_event Source event
+ * \param dest_events Pointer to destination event structure
+ * \param dest_event Destination event to be called, when source fires
+ * \return 0 On success or -1 on error.
+ */
+int event_disconnect(event_t *source_events, event_callback_t source_event,
+ event_t *dest_events, event_callback_t dest_event);
+
+/** Unbind all events related to given destination
+ *
+ * \param dest_events Pointer to destination event structure
+ * \param dest_event Destination event to be called, when source fires
+ * \return 0 On success or -1 on error.
+ */
+int event_disconnectall(event_t *dest_events, event_callback_t dest_event);
+
+/** Handle callbacks
+ *
+ * \param events Pointer to a structure as returned by event_create()
+ * \param timeout Time to wait for a callback to be served.
+ * \return Remaining time.
+ * */
+clock_t event_handle( event_t *events, clock_t timeout );
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __INCLUDE_NUTTX_EVENT_H */
+#endif /* CONFIG_EVENT */
diff --git a/nuttx/include/nuttx/sensors/st_lis331dl.h b/nuttx/include/nuttx/sensors/st_lis331dl.h
index 679ba81ec..404d4a480 100644
--- a/nuttx/include/nuttx/sensors/st_lis331dl.h
+++ b/nuttx/include/nuttx/sensors/st_lis331dl.h
@@ -59,41 +59,6 @@ extern "C" {
#define EXTERN extern
#endif
-/************************************************************************************
- * LIS331DL Internal Registers
- ************************************************************************************/
-
-#define ST_LIS331DL_WHOAMI 0x0F /* who am I register */
-#define ST_LIS331DL_WHOAMI_VALUE 0x3B /* Valid result is 0x3B */
-
-#define ST_LIS331DL_CTRL_REG1 0x20
-#define ST_LIS331DL_CR1_DR 0x80 /* Data-rate selection 0: 100 Hz, 1: 400 Hz */
-#define ST_LIS331DL_CR1_PD 0x40 /* Active Mode (1) / Power-down (0) */
-#define ST_LIS331DL_CR1_FS 0x20 /* Full Scale (1) +-9g or Normal Scale (0) +-2g */
-#define ST_LIS331DL_CR1_ST 0x18 /* Self test enable */
-#define ST_LIS331DL_CR1_ZEN 0x04 /* Z-Axis Enable */
-#define ST_LIS331DL_CR1_YEN 0x02 /* Y-Axis Enable */
-#define ST_LIS331DL_CR1_XEN 0x01 /* X-Axis Enable */
-
-#define ST_LIS331DL_CTRL_REG2 0x21
-#define ST_LIS331DL_CTRL_REG3 0x22
-
-#define ST_LIS331DL_HP_FILTER_RESET 0x23
-
-#define ST_LIS331DL_STATUS_REG 0x27 /* Status Register */
-#define ST_LIS331DL_SR_ZYXOR 0x80 /* OR'ed X,Y and Z data over-run */
-#define ST_LIS331DL_SR_ZOR 0x40 /* individual data over-run ... */
-#define ST_LIS331DL_SR_YOR 0x20
-#define ST_LIS331DL_SR_XOR 0x10
-#define ST_LIS331DL_SR_ZYXDA 0x08 /* OR'ed X,Y and Z data available */
-#define ST_LIS331DL_SR_ZDA 0x04 /* individual data available ... */
-#define ST_LIS331DL_SR_YDA 0x02
-#define ST_LIS331DL_SR_XDA 0x01
-
-#define ST_LIS331DL_OUT_X 0x29
-#define ST_LIS331DL_OUT_Y 0x2B
-#define ST_LIS331DL_OUT_Z 0x2D
-
/************************************************************************************
* Public Data Types
diff --git a/nuttx/include/nuttx/ptimer.h b/nuttx/include/nuttx/wireless/chipcon_cc1101.h
index a8bac82fe..0daadada1 100755
--- a/nuttx/include/nuttx/ptimer.h
+++ b/nuttx/include/nuttx/wireless/chipcon_cc1101.h
@@ -1,8 +1,9 @@
/****************************************************************************
- * include/nuttx/ptimer.h
+ * include/nuttx/wireless/chipcon_cc1101.h
*
- * Copyright(C) 2011 Uros Platise. All rights reserved.
- * Author: Uros Platise <uros.platise@isotel.eu>
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ *
+ * Authors: 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
@@ -23,40 +24,35 @@
* 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,
+ * 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
+ * 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
+/** \file
+ * \author Uros Platise
+ * \brief Chipcon CC1101 Device Driver
+ **/
-/****************************************************************************
- * Included Files
- ****************************************************************************/
+#ifndef __INCLUDE_NUTTX_WIRELESS_CHIPCON_CC1101_H
+#define __INCLUDE_NUTTX_WIRELESS_CHIPCON_CC1101_H
#include <nuttx/config.h>
+#include <nuttx/spi.h>
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
+#include <stdint.h>
+#include <stdbool.h>
-/****************************************************************************
- * Public Types
- ****************************************************************************/
+/************************************************************************************
+ * Pre-Processor Declarations
+ ************************************************************************************/
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
+#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
@@ -67,9 +63,51 @@ extern "C" {
#endif
+/************************************************************************************
+ * Public Data Types
+ ************************************************************************************/
+
+struct chipcon_cc1101_dev_s;
+
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/** Initialize Chipcon CC1101 Chip
+ *
+ * \param spi SPI Device Structure
+ * \return Pointer to newly allocated CC1101 structure or NULL on error with errno set.
+ *
+ * Possible errno as set by this function on error:
+ * - ENODEV: When device addressed is not compatible or it is not a CC1101
+ * - EFAULT: When there is no device
+ * - EBUSY: When device is already addressed by other device driver (not yet supported by low-level driver)
+ **/
+EXTERN struct chipcon_cc1101_dev_s * chipcon_cc1101_init(struct spi_dev_s * spi);
+
+/** Deinitialize Chipcon CC1101 Chip
+ *
+ * \param dev Device to CC1101 device structure, as returned by the chipcon_cc1101_init()
+ * \return OK On success
+ *
+ **/
+EXTERN int chipcon_cc1101_deinit(struct chipcon_cc1101_dev_s * dev);
+
+/** Power up device, start conversion */
+EXTERN int chipcon_cc1101_powerup(struct chipcon_cc1101_dev_s * dev);
+
+/** Power down device, stop conversion */
+EXTERN int chipcon_cc1101_powerdown(struct chipcon_cc1101_dev_s * dev);
+
+/** Set Multi Purpose Output Function */
+EXTERN int chipcon_cc1101_setgdo(struct chipcon_cc1101_dev_s * dev, uint8_t pin, uint8_t function);
+
+
#undef EXTERN
#if defined(__cplusplus)
}
#endif
+#endif /* __ASSEMBLY__ */
+#endif /* __INCLUDE_NUTTX_WIRELESS_CHIPCON_CC1101_H */
-#endif /* __INCLUDE_NUTTX_PTIMER_H */