summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/input/stmpe11.h4
-rw-r--r--nuttx/drivers/input/stmpe11_base.c58
-rw-r--r--nuttx/drivers/input/stmpe11_tsc.c68
-rw-r--r--nuttx/drivers/sensors/lm75.c4
4 files changed, 84 insertions, 50 deletions
diff --git a/nuttx/drivers/input/stmpe11.h b/nuttx/drivers/input/stmpe11.h
index 6876fa141..9ca31e52a 100644
--- a/nuttx/drivers/input/stmpe11.h
+++ b/nuttx/drivers/input/stmpe11.h
@@ -148,8 +148,8 @@ struct stmpe11_dev_s
uint8_t minor; /* Touchscreen minor device number */
volatile bool penchange; /* An unreported event is buffered */
- uint32_t threshx; /* Thresholded X value */
- uint32_t threshy; /* Thresholded Y value */
+ uint16_t threshx; /* Thresholded X value */
+ uint16_t threshy; /* Thresholded Y value */
sem_t waitsem; /* Used to wait for the availability of data */
struct work_s work; /* Supports the interrupt handling "bottom half" */
diff --git a/nuttx/drivers/input/stmpe11_base.c b/nuttx/drivers/input/stmpe11_base.c
index cabd33db2..f9f52fae9 100644
--- a/nuttx/drivers/input/stmpe11_base.c
+++ b/nuttx/drivers/input/stmpe11_base.c
@@ -43,10 +43,10 @@
#include <nuttx/config.h>
+#include <unistd.h>
#include <errno.h>
#include <debug.h>
-#include <nuttx/arch.h>
#include <nuttx/kmalloc.h>
#include <nuttx/input/stmpe11.h>
@@ -92,7 +92,9 @@ static void stmpe11_worker(FAR void *arg)
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)arg;
uint8_t regval;
- /* Get the globl interrupt status */
+ DEBUGASSERT(priv && priv->config);
+
+ /* Get the global interrupt status */
regval = stmpe11_getreg8(priv, STMPE11_INT_STA);
@@ -132,16 +134,16 @@ static void stmpe11_worker(FAR void *arg)
}
#endif
- /* Clear any other residual, unhandled pending interrupt */
+ /* Clear any other residual, unhandled pending interrupt */
- if (regval != 0)
- {
- stmpe11_putreg8(priv, STMPE11_INT_STA, regval);
- }
+ if (regval != 0)
+ {
+ stmpe11_putreg8(priv, STMPE11_INT_STA, regval);
+ }
- /* Clear the STMPE11 global interrupt */
+ /* Re-enable the STMPE11 GPIO interrupt */
- priv->config->clear(priv->config);
+ priv->config->enable(priv->config, true);
}
/****************************************************************************
@@ -244,7 +246,7 @@ static void stmpe11_reset(FAR struct stmpe11_dev_s *priv)
/* Wait a bit */
- up_mdelay(20);
+ usleep(20*1000);
/* Then power on again. All registers will be in their reset state. */
@@ -285,12 +287,6 @@ STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev,
uint8_t regval;
int ret;
- /* On entry the following is assumed:
- *
- * I2C initialization ready
- * GPIO pins already configured.
- */
-
/* Allocate the device state structure */
#ifdef CONFIG_STMPE11_MULTIPLE
@@ -314,10 +310,20 @@ STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev,
/* Initialize the device state structure */
sem_init(&priv->exclsem, 0, 1);
+ priv->config = config;
+
#ifdef CONFIG_STMPE11_SPI
priv->spi = dev;
#else
priv->i2c = dev;
+
+ /* Set the I2C address and frequency. REVISIT: This logic would be
+ * insufficient if we share the I2C bus with any other devices that also
+ * modify the address and frequency.
+ */
+
+ I2C_SETADDRESS(dev, config->address, 7);
+ I2C_SETFREQUENCY(dev, config->frequency);
#endif
/* Read and verify the STMPE11 chip ID */
@@ -335,10 +341,14 @@ STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev,
stmpe11_reset(priv);
- /* Configure the interrupt output pin to generate interrupts on high level. */
+ /* Configure the interrupt output pin to generate interrupts on high or low level. */
regval = stmpe11_getreg8(priv, STMPE11_INT_CTRL);
- regval |= INT_CTRL_INT_POLARITY; /* Pin polarity: Active high */
+#ifdef CONFIG_STMPE11_ACTIVELOW
+ regval &= ~INT_CTRL_INT_POLARITY; /* Pin polarity: Active low / falling edge */
+#else
+ regval |= INT_CTRL_INT_POLARITY; /* Pin polarity: Active high / rising edge */
+#endif
regval &= ~INT_CTRL_INT_TYPE; /* Level interrupt */
stmpe11_putreg8(priv, STMPE11_INT_CTRL, regval);
@@ -409,6 +419,9 @@ uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
return 0;
}
+#ifdef CONFIG_STMPE11_REGDEBUG
+ dbg("%02x->%02x\n", regaddr, regval);
+#endif
return regval;
}
#endif
@@ -434,6 +447,10 @@ void stmpe11_putreg8(FAR struct stmpe11_dev_s *priv,
uint8_t txbuffer[2];
int ret;
+#ifdef CONFIG_STMPE11_REGDEBUG
+ dbg("%02x<-%02x\n", regaddr, regval);
+#endif
+
/* Setup to the data to be transferred. Two bytes: The STMPE11 register
* address followed by one byte of data.
*/
@@ -507,7 +524,10 @@ uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
return 0;
}
- return (uint16_t)rxbuffer[0] << 16 | (uint16_t)rxbuffer[1];
+#ifdef CONFIG_STMPE11_REGDEBUG
+ dbg("%02x->%02x%02x\n", regaddr, rxbuffer[0], rxbuffer[1]);
+#endif
+ return (uint16_t)rxbuffer[0] << 8 | (uint16_t)rxbuffer[1];
}
#endif
diff --git a/nuttx/drivers/input/stmpe11_tsc.c b/nuttx/drivers/input/stmpe11_tsc.c
index b6d9c3d62..a452d8798 100644
--- a/nuttx/drivers/input/stmpe11_tsc.c
+++ b/nuttx/drivers/input/stmpe11_tsc.c
@@ -139,7 +139,7 @@ static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv);
/* This the the vtable that supports the character driver interface */
-static const struct file_operations stmpe11_fops =
+static const struct file_operations g_stmpe11fops =
{
stmpe11_open, /* open */
stmpe11_close, /* close */
@@ -464,6 +464,7 @@ static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer, size_t len
struct stmpe11_sample_s sample;
int ret;
+ ivdbg("len=%d\n", len);
DEBUGASSERT(filep);
inode = filep->f_inode;
@@ -741,7 +742,9 @@ errout:
static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv)
{
- uint8_t regval = 0;
+ uint8_t regval;
+
+ ivdbg("Initializing touchscreen controller\n");
/* Enable TSC and ADC functions */
@@ -831,8 +834,10 @@ static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv)
int stmpe11_register(STMPE11_HANDLE handle, int minor)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle;
+ char devname[DEV_NAMELEN];
int ret;
+ ivdbg("handle=%p minor=%d\n", handle, minor);
DEBUGASSERT(priv);
/* Get exclusive access to the device structure */
@@ -854,25 +859,34 @@ int stmpe11_register(STMPE11_HANDLE handle, int minor)
return -EBUSY;
}
- /* Update the configuration structure to show that the TSC function is allocated */
+ /* Initialize the TS structure to their default values */
- priv->inuse |= TSC_PIN_SET; /* Pins 4-7 are now in-use */
- priv->flags |= STMPE11_FLAGS_TSC_INITIALIZED; /* TSC function is initialized */
- priv->minor = minor; /* Save the minor number */
+ priv->minor = minor;
+ priv->penchange = false;
+ priv->threshx = 0;
+ priv->threshy = 0;
+
+ /* Register the character driver */
+
+ snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor);
+ ret = register_driver(devname, &g_stmpe11fops, 0666, priv);
+ if (ret < 0)
+ {
+ idbg("Failed to register driver %s: %d\n", devname, ret);
+ sem_post(&priv->exclsem);
+ return ret;
+ }
/* Initialize the touchscreen controller */
stmpe11_tscinitialize(priv);
- /* Initialize the TS structure to their default values */
-
- priv->penchange = false;
- priv->threshx = 0;
- priv->threshy = 0;
+ /* Inidicate that the touchscreen controller was successfully initialized */
- priv->flags |= STMPE11_FLAGS_GPIO_INITIALIZED;
+ priv->inuse |= TSC_PIN_SET; /* Pins 4-7 are now in-use */
+ priv->flags |= STMPE11_FLAGS_TSC_INITIALIZED; /* TSC function is initialized */
sem_post(&priv->exclsem);
- return OK;
+ return ret;
}
/****************************************************************************
@@ -894,6 +908,7 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv)
uint16_t x; /* X position */
uint16_t y; /* Y position */
+ ivdbg("Sampling\n");
ASSERT(priv != NULL);
/* Get a pointer the callbacks for convenience (and so the code is not so
@@ -903,10 +918,9 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv)
config = priv->config;
DEBUGASSERT(config != NULL);
- /* Check if the Touch detect event happened */
/* Check for pen up or down from the TSC_STA ibit n the STMPE11_TSC_CTRL register. */
- pendown = (stmpe11_getreg8(priv, STMPE11_TSC_CTRL) & STMPE11_TSC_CTRL) != 0;
+ pendown = (stmpe11_getreg8(priv, STMPE11_TSC_CTRL) & TSC_CTRL_TSC_STA) != 0;
/* Handle the change from pen down to pen up */
@@ -918,17 +932,22 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv)
if (priv->sample.contact == CONTACT_NONE)
{
- goto errout;
+ return;
}
}
else
{
/* Read the next x and y positions */
+#ifdef CONFIG_STMPE11_SWAPXY
x = stmpe11_getreg16(priv, STMPE11_TSC_DATAX);
y = stmpe11_getreg16(priv, STMPE11_TSC_DATAY);
+#else
+ x = stmpe11_getreg16(priv, STMPE11_TSC_DATAY);
+ y = stmpe11_getreg16(priv, STMPE11_TSC_DATAX);
+#endif
- /* Perform a threasholding operation so that the results will be more stable */
+ /* Perform a thresholding operation so that the results will be more stable */
xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x);
ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y);
@@ -949,12 +968,12 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv)
/* Update the Z pression index */
priv->sample.z = stmpe11_getreg8(priv, STMPE11_TSC_DATAZ);
+ }
- /* Clear the interrupt pending bit and enable the FIFO again */
+ /* Clear the interrupt pending bit and enable the FIFO again */
- stmpe11_putreg8(priv, STMPE11_FIFO_STA, 0x01);
- stmpe11_putreg8(priv, STMPE11_FIFO_STA, 0x00);
- }
+ stmpe11_putreg8(priv, STMPE11_FIFO_STA, 0x01);
+ stmpe11_putreg8(priv, STMPE11_FIFO_STA, 0x00);
/* Note the availability of new measurements */
@@ -987,14 +1006,9 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv)
priv->sample.id = priv->id;
priv->penchange = true;
- /* Notify any waiters that nes STMPE11 data is available */
+ /* Notify any waiters that new STMPE11 data is available */
stmpe11_notify(priv);
-
- /* Exit, re-enabling STMPE11 interrupts */
-
-errout:
- config->enable(config, true);
}
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_TSC_DISABLE */
diff --git a/nuttx/drivers/sensors/lm75.c b/nuttx/drivers/sensors/lm75.c
index cd83f645b..8e1a0fb4b 100644
--- a/nuttx/drivers/sensors/lm75.c
+++ b/nuttx/drivers/sensors/lm75.c
@@ -108,7 +108,7 @@ static int lm75_ioctl(FAR struct file *filep,int cmd,unsigned long arg);
* Private Data
****************************************************************************/
-static const struct file_operations lm75_fops =
+static const struct file_operations g_lm75fops =
{
lm75_open,
lm75_close,
@@ -526,7 +526,7 @@ int lm75_register(FAR const char *devpath, FAR struct i2c_dev_s *i2c, uint8_t ad
/* Register the character driver */
- ret = register_driver(devpath, &lm75_fops, 0555, priv);
+ ret = register_driver(devpath, &g_lm75fops, 0666, priv);
if (ret < 0)
{
lm75dbg("Failed to register driver: %d\n", ret);