This is an automated email from the ASF dual-hosted git repository.

btashton pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git


The following commit(s) were added to refs/heads/master by this push:
     new 415d83c  STMPE811:  Fix name collision in 
include/nuttx/input/stmpe811.h
415d83c is described below

commit 415d83cf199a1d3a35bceb4b50282cacd31770b1
Author: Gregory Nutt <gn...@nuttx.org>
AuthorDate: Thu Sep 17 10:25:34 2020 -0600

    STMPE811:  Fix name collision in include/nuttx/input/stmpe811.h
    
    The macro name GPIO_PIN collides with naming used by many architectures:
    
        $ find . -name "*.h" | xargs grep "define GPIO_PIN[(]"
        ./arch/arm/src/am335x/hardware/am335x_gpio.h:#define GPIO_PIN(n)        
      (1 << ((n) & 0x1f)) /* Bit n: Pin n, n=0-31 */
        ./arch/arm/src/imx6/hardware/imx_gpio.h:#define GPIO_PIN(n)             
 (1 << (n)) /* Bit n: Pin n, n=0-31 */
        ./arch/arm/src/imxrt/hardware/imxrt_gpio.h:#define GPIO_PIN(n)          
    (1 << (n)) /* Bit n: Pin n, n=0-31 */
        ./arch/arm/src/lpc43xx/hardware/lpc43_gpio.h:#define GPIO_PIN(p)        
         (1 << (p)) /* Bits 0-31: Read/write pin state */
        ./arch/arm/src/nrf52/nrf52_gpio.h:#  define GPIO_PIN(n)           ((n) 
<< GPIO_PIN_SHIFT)
        ./arch/arm/src/nuc1xx/hardware/nuc_gpio.h:#define GPIO_PIN(n)           
     (1 << (n)) /* Bit n: GPIOx Pin[n] pin value */
        ./arch/avr/src/at32uc3/at32uc3_gpio.h:#define GPIO_PIN(n)              
(1 << (n))
        ./include/nuttx/input/stmpe811.h:#define GPIO_PIN(n)                  
(1 << (n))
    
    This commit changes the name used by the STMPE811 driver to STMPE11_GPIO_PIN
---
 drivers/input/stmpe811_adc.c   | 55 +++++++++++-----------------
 drivers/input/stmpe811_gpio.c  | 83 +++++++++++++++++++-----------------------
 include/nuttx/input/stmpe811.h | 73 +++++++++++++++++--------------------
 3 files changed, 93 insertions(+), 118 deletions(-)

diff --git a/drivers/input/stmpe811_adc.c b/drivers/input/stmpe811_adc.c
index 941f699..2f47575 100644
--- a/drivers/input/stmpe811_adc.c
+++ b/drivers/input/stmpe811_adc.c
@@ -1,42 +1,28 @@
 /****************************************************************************
  * drivers/input/stmpe811_adc.c
  *
- *   Copyright (C) 2012, 2017 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * 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
  *
- * References:
- *   "STMPE811 S-Touch� advanced resistive touchscreen controller with 8-bit
- *    GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics"
- *
- * 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.
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * 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.
  *
  ****************************************************************************/
 
+/* References:
+ *   "STMPE811 S-Touch advanced resistive touchscreen controller with 8-bit
+ *    GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics"
+ */
+
 /****************************************************************************
  * Included Files
  ****************************************************************************/
@@ -54,7 +40,8 @@
 
 #include "stmpe811.h"
 
-#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE811) && 
!defined(CONFIG_STMPE811_ADC_DISABLE)
+#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE811) && \
+   !defined(CONFIG_STMPE811_ADC_DISABLE)
 
 /****************************************************************************
  * Private Types
@@ -149,7 +136,7 @@ int stmpe811_adcinitialize(STMPE811_HANDLE handle)
 int stmpe811_adcconfig(STMPE811_HANDLE handle, int pin)
 {
   FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
-  uint8_t pinmask = GPIO_PIN(pin);
+  uint8_t pinmask = STMPE811_GPIO_PIN(pin);
   uint8_t regval;
   int ret;
 
@@ -207,7 +194,7 @@ int stmpe811_adcconfig(STMPE811_HANDLE handle, int pin)
 uint16_t stmpe811_adcread(STMPE811_HANDLE handle, int pin)
 {
   FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
-  uint8_t pinmask = GPIO_PIN(pin);
+  uint8_t pinmask = STMPE811_GPIO_PIN(pin);
   uint8_t regval;
   int i;
   int ret;
diff --git a/drivers/input/stmpe811_gpio.c b/drivers/input/stmpe811_gpio.c
index 55c1f92..14ea471 100644
--- a/drivers/input/stmpe811_gpio.c
+++ b/drivers/input/stmpe811_gpio.c
@@ -1,42 +1,28 @@
 /****************************************************************************
  * drivers/input/stmpe811_gpio.c
  *
- *   Copyright (C) 2012 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * 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
  *
- * References:
- *   "STMPE811 S-Touch� advanced resistive touchscreen controller with 8-bit
- *    GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics"
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * 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.
  *
  ****************************************************************************/
 
+/* References:
+ *   "STMPE811 S-Touch advanced resistive touchscreen controller with 8-bit
+ *    GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics"
+ */
+
 /****************************************************************************
  * Included Files
  ****************************************************************************/
@@ -177,14 +163,17 @@ int stmpe811_gpioconfig(STMPE811_HANDLE handle, uint8_t 
pinconfig)
       stmpe811_putreg8(priv, STMPE811_GPIO_DIR_REG, regval);
 
       /* Set its initial output value */
+
       if ((pinconfig & STMPE811_GPIO_VALUE) != STMPE811_GPIO_ZERO)
         {
           /* Set the output value(s)e by writing to the SET register */
+
           stmpe811_putreg8(priv, STMPE811_GPIO_SETPIN, (1 << pin));
         }
       else
         {
           /* Clear the output value(s) by writing to the CLR register */
+
           stmpe811_putreg8(priv, STMPE811_GPIO_CLRPIN, (1 << pin));
         }
     }
@@ -207,6 +196,7 @@ int stmpe811_gpioconfig(STMPE811_HANDLE handle, uint8_t 
pinconfig)
         {
           regval &= pinmask;
         }
+
       stmpe811_putreg8(priv, STMPE811_GPIO_FE, regval);
 
       /* Set up the rising edge detection */
@@ -220,6 +210,7 @@ int stmpe811_gpioconfig(STMPE811_HANDLE handle, uint8_t 
pinconfig)
         {
           regval &= pinmask;
         }
+
       stmpe811_putreg8(priv, STMPE811_GPIO_RE, regval);
 
       /* Disable interrupts for now */
@@ -252,7 +243,8 @@ int stmpe811_gpioconfig(STMPE811_HANDLE handle, uint8_t 
pinconfig)
  *
  ****************************************************************************/
 
-void stmpe811_gpiowrite(STMPE811_HANDLE handle, uint8_t pinconfig, bool value)
+void stmpe811_gpiowrite(STMPE811_HANDLE handle, uint8_t pinconfig,
+                        bool value)
 {
   FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
   int pin = (pinconfig & STMPE811_GPIO_PIN_MASK) >> STMPE811_GPIO_PIN_SHIFT;
@@ -323,21 +315,21 @@ int stmpe811_gpioread(STMPE811_HANDLE handle, uint8_t 
pinconfig, bool *value)
     }
 
   regval  = stmpe811_getreg8(priv, STMPE811_GPIO_MPSTA);
-  *value = ((regval & GPIO_PIN(pin)) != 0);
+  *value = ((regval & STMPE811_GPIO_PIN(pin)) != 0);
   nxsem_post(&priv->exclsem);
   return OK;
 }
 
-/***********************************************************************************
+/****************************************************************************
  * Name: stmpe811_gpioattach
  *
  * Description:
- *  Attach to a GPIO interrupt input pin and enable interrupts on the pin.  
Using
- *  the value NULL for the handler address will disable interrupts from the 
pin and
- *  detach the handler.
+ *  Attach to a GPIO interrupt input pin and enable interrupts on the pin.
+ *  Using the value NULL for the handler address will disable interrupts
+ *  from the pin anddetach the handler.
  *
- *  NOTE:  Callbacks do not occur from an interrupt handler but rather from the
- *  context of the worker thread.
+ *  NOTE:  Callbacks do not occur from an interrupt handler but rather
+ *  from the context of the worker thread.
  *
  * Input Parameters:
  *   handle    - The handle previously returned by stmpe811_instantiate
@@ -345,10 +337,10 @@ int stmpe811_gpioread(STMPE811_HANDLE handle, uint8_t 
pinconfig, bool *value)
  *   handler   - The handler that will be called when the interrupt occurs.
  *
  * Returned Value:
- *   Zero is returned on success.  Otherwise, a negated errno value is returned
- *   to indicate the nature of the failure.
+ *   Zero is returned on success.  Otherwise, a negated errno value is
+ *   returned to indicate the nature of the failure.
  *
- 
************************************************************************************/
+ ****************************************************************************/
 
 #ifndef CONFIG_STMPE811_GPIOINT_DISABLE
 int stmpe811_gpioattach(STMPE811_HANDLE handle, uint8_t pinconfig,
@@ -385,13 +377,13 @@ int stmpe811_gpioattach(STMPE811_HANDLE handle, uint8_t 
pinconfig,
     {
       /* Enable interrupts for this GPIO */
 
-      regval |= GPIO_PIN(pin);
+      regval |= STMPE811_GPIO_PIN(pin);
     }
   else
     {
       /* Disable interrupts for this GPIO */
 
-      regval &= ~GPIO_PIN(pin);
+      regval &= ~STMPE811_GPIO_PIN(pin);
     }
 
   stmpe811_putreg8(priv, STMPE811_GPIO_EN, regval);
@@ -442,7 +434,8 @@ void stmpe811_gpioworker(FAR struct stmpe811_dev_s *priv)
             }
           else
             {
-              ierr("ERROR: No handler for PIN%d, GPIO_INTSTA: %02x\n", pin, 
regval);
+              ierr("ERROR: No handler for PIN%d, GPIO_INTSTA: %02x\n",
+                   pin, regval);
             }
 
           /* Clear the pending GPIO interrupt by writing a '1' to the
diff --git a/include/nuttx/input/stmpe811.h b/include/nuttx/input/stmpe811.h
index 60b2fbb..387b756 100644
--- a/include/nuttx/input/stmpe811.h
+++ b/include/nuttx/input/stmpe811.h
@@ -1,42 +1,28 @@
 
/********************************************************************************************
  * include/nuttx/input/stmpe811.h
  *
- *   Copyright (C) 2012, 2015, 2017 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * 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
  *
- * References:
- *   "STMPE811 S-Touch� advanced resistive touchscreen controller with 8-bit
- *    GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics"
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * 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.
  *
  
********************************************************************************************/
 
+/* References:
+ *   "STMPE811 S-Touch advanced resistive touchscreen controller with 8-bit
+ *    GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics"
+ */
+
 #ifndef __INCLUDE_NUTTX_INPUT_STMPE811_H
 #define __INCLUDE_NUTTX_INPUT_STMPE811_H
 
@@ -56,7 +42,9 @@
 
/********************************************************************************************
  * Pre-processor Definitions
  
********************************************************************************************/
+
 /* Configuration 
****************************************************************************/
+
 /* Prerequisites:  CONFIG_INPUT=y
  *
  * CONFIG_INPUT_STMPE811
@@ -142,6 +130,7 @@
 #endif
 
 /* I2C 
**************************************************************************************/
+
 /* STMPE811 Address:  The STMPE811 may have 7-bit address 0x41 or 0x44, 
depending upon the
  * state of the ADDR0 pin.
  */
@@ -158,6 +147,7 @@
 #define STMPE811_I2C_MAXFREQUENCY    400000       /* 400KHz */
 
 /* SPI 
**************************************************************************************/
+
 /* The device always operates in mode 0 */
 
 #define STMPE811_SPI_MODE            SPIDEV_MODE0 /* Mode 0 */
@@ -166,7 +156,8 @@
 
 #define STMPE811_SPI_MAXFREQUENCY    1000000      /* 1MHz */
 
-/* STMPE811 Registers 
************************************************************************/
+/* STMPE811 Registers 
***********************************************************************/
+
 /* Register Addresses */
 
 #define STMPE811_CHIP_ID             0x00  /* Device identification (16-bit) */
@@ -192,7 +183,8 @@
 #define STMPE811_ADC_CTRL1           0x20  /* ADC control */
 #define STMPE811_ADC_CTRL2           0x21  /* ADC control */
 #define STMPE811_ADC_CAPT            0x22  /* To initiate ADC data acquisition 
*/
-#define STMPE811_ADC_DATACH(n)       (0x30 + ((n) << 1))  /* ADC channel n 
(16-bit) */
+#define STMPE811_ADC_DATACH(n)       (0x30 + ((n) << 1))
+                                           /* ADC channel n (16-bit) */
 #define STMPE811_ADC_DATACH0         0x30  /* ADC channel 0 (16-bit) */
 #define STMPE811_ADC_DATACH1         0x32  /* ADC channel 1 (16_bit) */
 #define STMPE811_ADC_DATACH2         0x34  /* ADC channel 2 (16-bit) */
@@ -279,7 +271,7 @@
 
 /* GPIO set/clear/sta/dir/edge/rising/falling/af registers */
 
-#define GPIO_PIN(n)                  (1 << (n))
+#define STMPE811_GPIO_PIN(n)         (1 << (n))
 #define TSC_PIN_SET                  (0xf0)   /* Pins 4-7:  Used by 
touchscreen */
 
 /* ADC control */
@@ -310,15 +302,15 @@
 
 /* 4-wire touchscreen controller setup */
 
-#define TSC_CTRL_EN                  (1 << 0)  /* Bit 0: Enable TSC */
-#define TSC_CTRL_OP_MOD_SHIFT        (1)       /* Bits 1-3: TSC operating mode 
*/
+#define TSC_CTRL_EN                  (1 << 0)                     /* Bit 0: 
Enable TSC */
+#define TSC_CTRL_OP_MOD_SHIFT        (1)                          /* Bits 1-3: 
TSC operating mode */
 #define TSC_CTRL_OP_MOD_MASK         (7 << TSC_CTRL_OP_MOD_SHIFT)
 #  define TSC_CTRL_OP_MOD_XYZ        (0 << TSC_CTRL_OP_MOD_SHIFT) /* 000: X, 
Y, Z acquisition */
 #  define TSC_CTRL_OP_MOD_XY         (1 << TSC_CTRL_OP_MOD_SHIFT) /* 001: X, Y 
only */
 #  define TSC_CTRL_OP_MOD_X          (2 << TSC_CTRL_OP_MOD_SHIFT) /* 010: X 
only */
 #  define TSC_CTRL_OP_MOD_Y          (3 << TSC_CTRL_OP_MOD_SHIFT) /* 011: Y 
only */
 #  define TSC_CTRL_OP_MOD_Z          (4 << TSC_CTRL_OP_MOD_SHIFT) /* 100: Z 
only */
-#define TSC_CTRL_TRACK_SHIFT         (4)       /* Bits 4-6: Tracking index */
+#define TSC_CTRL_TRACK_SHIFT         (4)                          /* Bits 4-6: 
Tracking index */
 #define TSC_CTRL_TRACK_MASK          (7 << TSC_CTRL_TRACK_SHIFT)
 #define TSC_CTRL_TRACK_NONE          (0 << TSC_CTRL_TRACK_SHIFT)
 #define TSC_CTRL_TRACK_4             (1 << TSC_CTRL_TRACK_SHIFT)
@@ -328,7 +320,7 @@
 #define TSC_CTRL_TRACK_64            (5 << TSC_CTRL_TRACK_SHIFT)
 #define TSC_CTRL_TRACK_92            (6 << TSC_CTRL_TRACK_SHIFT)
 #define TSC_CTRL_TRACK_127           (7 << TSC_CTRL_TRACK_SHIFT)
-#define TSC_CTRL_TSC_STA             (1 << 7)  /* Bit 7: TSC status. 1=touch 
detected */
+#define TSC_CTRL_TSC_STA             (1 << 7)                     /* Bit 7: 
TSC status. 1=touch detected */
 
 /* Touchscreen controller configuration */
 
@@ -393,6 +385,7 @@
 #define TEMP_CTRL_THRES_RANGE        (1 << 4)  /* Bit 4: temperature threshold 
enable, 0='>=' 1='<' */
 
 /* GPIO Configuration 
***********************************************************************/
+
 /* The STMPE811 GPIO interfaces take an 8-bit bit-encoded parameter to 
describe the GPIO pin.
  * The following definitions describe the bit-encoding of that parameter.
  *
@@ -648,7 +641,8 @@ int stmpe811_gpioread(STMPE811_HANDLE handle, uint8_t 
pinconfig, bool *value);
  
********************************************************************************************/
 
 #if !defined(CONFIG_STMPE811_GPIO_DISABLE) && 
!defined(CONFIG_STMPE811_GPIOINT_DISABLE)
-int stmpe811_gpioattach(STMPE811_HANDLE handle, uint8_t pinconfig, 
stmpe811_handler_t handler);
+int stmpe811_gpioattach(STMPE811_HANDLE handle, uint8_t pinconfig,
+                        stmpe811_handler_t handler);
 #endif
 
 
/********************************************************************************************
@@ -765,6 +759,7 @@ uint16_t stmpe811_tempread(STMPE811_HANDLE handle);
  *   the nature of the failure.
  *
  
********************************************************************************************/
+
 /* Not implemented */
 
 #undef EXTERN

Reply via email to