From ca700d2e3c06a80de37c5ef8383ca550fe20c750 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 7 May 2011 19:22:15 +0000 Subject: Mostly cosmetic changes from Uros git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3575 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/include/nuttx/progmem.h | 1 + nuttx/include/nuttx/sensors/lis331dl.h | 142 +++++++++++++++++++++++++ nuttx/include/nuttx/sensors/st_lis331dl.h | 144 -------------------------- nuttx/include/nuttx/wireless/cc1101.h | 112 ++++++++++++++++++++ nuttx/include/nuttx/wireless/chipcon_cc1101.h | 113 -------------------- 5 files changed, 255 insertions(+), 257 deletions(-) create mode 100644 nuttx/include/nuttx/sensors/lis331dl.h delete mode 100644 nuttx/include/nuttx/sensors/st_lis331dl.h create mode 100755 nuttx/include/nuttx/wireless/cc1101.h delete mode 100755 nuttx/include/nuttx/wireless/chipcon_cc1101.h (limited to 'nuttx/include') diff --git a/nuttx/include/nuttx/progmem.h b/nuttx/include/nuttx/progmem.h index e9e05ed2c..021eb035e 100644 --- a/nuttx/include/nuttx/progmem.h +++ b/nuttx/include/nuttx/progmem.h @@ -41,6 +41,7 @@ ****************************************************************************/ #include +#include #include #include diff --git a/nuttx/include/nuttx/sensors/lis331dl.h b/nuttx/include/nuttx/sensors/lis331dl.h new file mode 100644 index 000000000..2e83dbe1f --- /dev/null +++ b/nuttx/include/nuttx/sensors/lis331dl.h @@ -0,0 +1,142 @@ +/**************************************************************************** + * include/nuttx/sensors/lis331dl.h + * + * Copyright (C) 2011 Uros Platise. All rights reserved. + * + * Authors: Uros Platise + * + * 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 ST LIS331DL I2C Device Driver + **/ + +#ifndef __INCLUDE_NUTTX_SENSORS_LIS331DL_H +#define __INCLUDE_NUTTX_SENSORS_LIS331DL_H + +#include +#include + +/************************************************************************************ + * Pre-Processor Declarations + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + + +/************************************************************************************ + * Public Data Types + ************************************************************************************/ + +struct lis331dl_dev_s; + +struct lis331dl_vector_s { + int8_t x, y, z; +}; + + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/** Initialize ST LIS331DL Chip + * + * \param i2c I2C Device Structure + * \param address I2C Address of the proposed device + * \return Pointer to newly allocated ST LIS331DL structure or NULL on error with errno set. + * + * Possible errno as set by this function on error: + * - ENODEV: When device addressed on given address is not compatible or it is not a LIS331DL + * - EFAULT: When there is no device at given address. + * - EBUSY: When device is already addressed by other device driver (not yet supported by low-level driver) + **/ +EXTERN struct lis331dl_dev_s * lis331dl_init(struct i2c_dev_s * i2c, uint16_t address); + +/** Deinitialize ST LIS331DL Chip + * + * \param dev Device to LIS331DL device structure, as returned by the lis331dl_init() + * \return OK On success + * + **/ +EXTERN int lis331dl_deinit(struct lis331dl_dev_s * dev); + +/** Power up device, start conversion */ +EXTERN int lis331dl_powerup(struct lis331dl_dev_s * dev); + +/** Power down device, stop conversion */ +EXTERN int lis331dl_powerdown(struct lis331dl_dev_s * dev); + +/** Configure conversion + * + * \param dev Device to LIS331DL device structure + * \param full When set, range of [-9g, 9g] is selected, otherwise [-2g, +2g] + * \param fast When set, conversion operates at 400 Hz, otherwise at 100 Hz + * \return OK on success or errno is set + **/ +EXTERN int lis331dl_setconversion(struct lis331dl_dev_s * dev, bool full, bool fast); + +/** Get precision + * + * \return Precision of 1 LSB in terms of unit [mg] + **/ +EXTERN int lis331dl_getprecision(struct lis331dl_dev_s * dev); + +/** Get sample rate + * + * \return Sample rate in unit of [Hz] + **/ +EXTERN int lis331dl_getsamplerate(struct lis331dl_dev_s * dev); + +/** Get readings, updates internal data structure + * + * \param dev Device to LIS331DL device structure + * \return Ptr to vector acceleration [x,y,z] on success, or NULL on error with errno set. + * If data is not yet ready to be read from the LIS331 then errno is set to EAGAIN otherwise + * errno is set by I2C_TRANSFER(). + */ +EXTERN const struct lis331dl_vector_s * lis331dl_getreadings(struct lis331dl_dev_s * dev); + + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __INCLUDE_NUTTX_SENSORS_LIS331DL_H */ diff --git a/nuttx/include/nuttx/sensors/st_lis331dl.h b/nuttx/include/nuttx/sensors/st_lis331dl.h deleted file mode 100644 index 404d4a480..000000000 --- a/nuttx/include/nuttx/sensors/st_lis331dl.h +++ /dev/null @@ -1,144 +0,0 @@ -/**************************************************************************** - * include/nuttx/sensors/st_lis331dl.h - * - * Copyright (C) 2011 Uros Platise. All rights reserved. - * - * Authors: Uros Platise - * - * 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 ST LIS331DL I2C Device Driver - **/ - -#ifndef __INCLUDE_NUTTX_SENSORS_ST_LIS331DL_H -#define __INCLUDE_NUTTX_SENSORS_ST_LIS331DL_H - -#include -#include - -/************************************************************************************ - * Pre-Processor Declarations - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - - -/************************************************************************************ - * Public Data Types - ************************************************************************************/ - -struct st_lis331dl_dev_s; - -struct st_lis331dl_vector_s { - int8_t x, y, z; -}; - - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ - -/** Initialize ST LIS331DL Chip - * - * \param i2c I2C Device Structure - * \param address I2C Address of the proposed device - * \return Pointer to newly allocated ST LIS331DL structure or NULL on error with errno set. - * - * Possible errno as set by this function on error: - * - ENODEV: When device addressed on given address is not compatible or it is not a LIS331DL - * - EFAULT: When there is no device at given address. - * - EBUSY: When device is already addressed by other device driver (not yet supported by low-level driver) - **/ -EXTERN struct st_lis331dl_dev_s * st_lis331dl_init(struct i2c_dev_s * i2c, uint16_t address); - -/** Deinitialize ST LIS331DL Chip - * - * \param dev Device to LIS331DL device structure, as returned by the st_lis331dl_init() - * \return OK On success - * - **/ -EXTERN int st_lis331dl_deinit(struct st_lis331dl_dev_s * dev); - -/** Power up device, start conversion */ -EXTERN int st_lis331dl_powerup(struct st_lis331dl_dev_s * dev); - -/** Power down device, stop conversion */ -EXTERN int st_lis331dl_powerdown(struct st_lis331dl_dev_s * dev); - -/** Configure conversion - * - * \param dev Device to LIS331DL device structure - * \param full When set, range of [-9g, 9g] is selected, otherwise [-2g, +2g] - * \param fast When set, conversion operates at 400 Hz, otherwise at 100 Hz - * \return OK on success or errno is set - **/ -EXTERN int st_lis331dl_setconversion(struct st_lis331dl_dev_s * dev, bool full, bool fast); - -/** Get precision - * - * \return Precision of 1 LSB in terms of unit [mg] - **/ -EXTERN int st_lis331dl_getprecision(struct st_lis331dl_dev_s * dev); - -/** Get sample rate - * - * \return Sample rate in unit of [Hz] - **/ -EXTERN int st_lis331dl_getsamplerate(struct st_lis331dl_dev_s * dev); - -/** Get readings, updates internal data structure - * - * \param dev Device to LIS331DL device structure - * \return Ptr to vector acceleration [x,y,z] on success, or NULL on error with errno set. - * If data is not yet ready to be read from the LIS331 then errno is set to EAGAIN otherwise - * errno is set by I2C_TRANSFER(). - */ -EXTERN const struct st_lis331dl_vector_s * st_lis331dl_getreadings(struct st_lis331dl_dev_s * dev); - - - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __INCLUDE_NUTTX_SENSORS_ST_LIS331DL_H */ - diff --git a/nuttx/include/nuttx/wireless/cc1101.h b/nuttx/include/nuttx/wireless/cc1101.h new file mode 100755 index 000000000..c0d756e72 --- /dev/null +++ b/nuttx/include/nuttx/wireless/cc1101.h @@ -0,0 +1,112 @@ +/**************************************************************************** + * include/nuttx/wireless/cc1101.h + * + * Copyright (C) 2011 Uros Platise. All rights reserved. + * + * Authors: Uros Platise + * + * 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 Chipcon CC1101 Device Driver + **/ + +#ifndef __INCLUDE_NUTTX_WIRELESS_CC1101_H +#define __INCLUDE_NUTTX_WIRELESS_CC1101_H + +#include +#include + +#include +#include + +/************************************************************************************ + * Pre-Processor Declarations + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + + +/************************************************************************************ + * Public Data Types + ************************************************************************************/ + +struct 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 cc1101_dev_s * cc1101_init(struct spi_dev_s * spi); + +/** Deinitialize Chipcon CC1101 Chip + * + * \param dev Device to CC1101 device structure, as returned by the cc1101_init() + * \return OK On success + * + **/ +EXTERN int cc1101_deinit(struct cc1101_dev_s * dev); + +/** Power up device, start conversion */ +EXTERN int cc1101_powerup(struct cc1101_dev_s * dev); + +/** Power down device, stop conversion */ +EXTERN int cc1101_powerdown(struct cc1101_dev_s * dev); + +/** Set Multi Purpose Output Function */ +EXTERN int cc1101_setgdo(struct cc1101_dev_s * dev, uint8_t pin, uint8_t function); + + +#undef EXTERN +#if defined(__cplusplus) +} +#endif +#endif /* __ASSEMBLY__ */ +#endif /* __INCLUDE_NUTTX_WIRELESS_CC1101_H */ diff --git a/nuttx/include/nuttx/wireless/chipcon_cc1101.h b/nuttx/include/nuttx/wireless/chipcon_cc1101.h deleted file mode 100755 index 0daadada1..000000000 --- a/nuttx/include/nuttx/wireless/chipcon_cc1101.h +++ /dev/null @@ -1,113 +0,0 @@ -/**************************************************************************** - * include/nuttx/wireless/chipcon_cc1101.h - * - * Copyright (C) 2011 Uros Platise. All rights reserved. - * - * Authors: Uros Platise - * - * 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 Chipcon CC1101 Device Driver - **/ - -#ifndef __INCLUDE_NUTTX_WIRELESS_CHIPCON_CC1101_H -#define __INCLUDE_NUTTX_WIRELESS_CHIPCON_CC1101_H - -#include -#include - -#include -#include - -/************************************************************************************ - * Pre-Processor Declarations - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#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 */ - -- cgit v1.2.3