summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-16 00:32:11 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-16 00:32:11 +0000
commitdf5aca04bdf127475b90bf6fdc246f402f039649 (patch)
treefa8d7ebc153e98273b925eb661c86da5c96e9519 /nuttx/drivers
parentfdaf3f62925632d5c98d019511acd22934653b0c (diff)
downloadpx4-nuttx-df5aca04bdf127475b90bf6fdc246f402f039649.tar.gz
px4-nuttx-df5aca04bdf127475b90bf6fdc246f402f039649.tar.bz2
px4-nuttx-df5aca04bdf127475b90bf6fdc246f402f039649.zip
Updated STM32 ADC driver
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4189 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/analog/adc.c341
1 files changed, 178 insertions, 163 deletions
diff --git a/nuttx/drivers/analog/adc.c b/nuttx/drivers/analog/adc.c
index bf3d7bdf6..ab374f973 100644
--- a/nuttx/drivers/analog/adc.c
+++ b/nuttx/drivers/analog/adc.c
@@ -77,14 +77,14 @@ static int adc_ioctl(FAR struct file *filep,int cmd,unsigned long arg);
static const struct file_operations adc_fops =
{
- adc_open, /* open */
- adc_close, /* close */
- adc_read, /* read */
- adc_write, /* write */
- 0, /* seek */
- adc_ioctl /* ioctl */
+ adc_open, /* open */
+ adc_close, /* close */
+ adc_read, /* read */
+ adc_write, /* write */
+ 0, /* seek */
+ adc_ioctl /* ioctl */
#ifndef CONFIG_DISABLE_POLL
- , 0 /* poll */
+ , 0 /* poll */
#endif
};
@@ -101,62 +101,62 @@ static const struct file_operations adc_fops =
static int adc_open(FAR struct file *filep)
{
- FAR struct inode *inode = filep->f_inode;
- FAR struct adc_dev_s *dev = inode->i_private;
- uint8_t tmp;
- int ret = OK;
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct adc_dev_s *dev = inode->i_private;
+ uint8_t tmp;
+ int ret = OK;
- /* If the port is the middle of closing, wait until the close is finished */
+ /* If the port is the middle of closing, wait until the close is finished */
- if (sem_wait(&dev->ad_closesem) != OK)
+ if (sem_wait(&dev->ad_closesem) != OK)
{
- ret = -errno;
+ ret = -errno;
}
- else
+ else
{
- /* Increment the count of references to the device. If this the first
- * time that the driver has been opened for this device, then initialize
- * the device.
- */
+ /* Increment the count of references to the device. If this the first
+ * time that the driver has been opened for this device, then initialize
+ * the device.
+ */
- tmp = dev->ad_ocount + 1;
- if (tmp == 0)
+ tmp = dev->ad_ocount + 1;
+ if (tmp == 0)
{
- /* More than 255 opens; uint8_t overflows to zero */
+ /* More than 255 opens; uint8_t overflows to zero */
- ret = -EMFILE;
+ ret = -EMFILE;
}
- else
+ else
{
- /* Check if this is the first time that the driver has been opened. */
+ /* Check if this is the first time that the driver has been opened. */
- if (tmp == 1)
+ if (tmp == 1)
{
- /* Yes.. perform one time hardware initialization. */
+ /* Yes.. perform one time hardware initialization. */
- irqstate_t flags = irqsave();
- ret = dev->ad_ops->ao_setup(dev);
- if (ret == OK)
+ irqstate_t flags = irqsave();
+ ret = dev->ad_ops->ao_setup(dev);
+ if (ret == OK)
{
- /* Mark the FIFOs empty */
+ /* Mark the FIFOs empty */
- dev->ad_recv.af_head = 0;
- dev->ad_recv.af_tail = 0;
+ dev->ad_recv.af_head = 0;
+ dev->ad_recv.af_tail = 0;
- /* Finally, Enable the CAN RX interrupt */
+ /* Finally, Enable the CAN RX interrupt */
- dev->ad_ops->ao_rxint(dev, true);
+ dev->ad_ops->ao_rxint(dev, true);
- /* Save the new open count on success */
+ /* Save the new open count on success */
- dev->ad_ocount = tmp;
+ dev->ad_ocount = tmp;
}
- irqrestore(flags);
+ irqrestore(flags);
}
}
- sem_post(&dev->ad_closesem);
+ sem_post(&dev->ad_closesem);
}
- return ret;
+ return ret;
}
/************************************************************************************
@@ -170,43 +170,42 @@ static int adc_open(FAR struct file *filep)
static int adc_close(FAR struct file *filep)
{
- FAR struct inode *inode = filep->f_inode;
- FAR struct adc_dev_s *dev = inode->i_private;
- irqstate_t flags;
- int ret = OK;
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct adc_dev_s *dev = inode->i_private;
+ irqstate_t flags;
+ int ret = OK;
- if (sem_wait(&dev->ad_closesem) != OK)
+ if (sem_wait(&dev->ad_closesem) != OK)
{
- ret = -errno;
+ ret = -errno;
}
- else
+ else
{
- /* Decrement the references to the driver. If the reference count will
- * decrement to 0, then uninitialize the driver.
- */
+ /* Decrement the references to the driver. If the reference count will
+ * decrement to 0, then uninitialize the driver.
+ */
- if (dev->ad_ocount > 1)
+ if (dev->ad_ocount > 1)
{
- dev->ad_ocount--;
- sem_post(&dev->ad_closesem);
+ dev->ad_ocount--;
+ sem_post(&dev->ad_closesem);
}
- else
+ else
{
- /* There are no more references to the port */
+ /* There are no more references to the port */
- dev->ad_ocount = 0;
+ dev->ad_ocount = 0;
+ /* Free the IRQ and disable the ADC device */
- /* Free the IRQ and disable the ADC device */
+ flags = irqsave(); /* Disable interrupts */
+ dev->ad_ops->ao_shutdown(dev); /* Disable the ADC */
+ irqrestore(flags);
- flags = irqsave(); /* Disable interrupts */
- dev->ad_ops->ao_shutdown(dev); /* Disable the ADC */
- irqrestore(flags);
-
- sem_post(&dev->ad_closesem);
+ sem_post(&dev->ad_closesem);
}
}
- return ret;
+ return ret;
}
/****************************************************************************
@@ -215,115 +214,129 @@ static int adc_close(FAR struct file *filep)
static ssize_t adc_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
{
- FAR struct inode *inode = filep->f_inode;
- FAR struct adc_dev_s *dev = inode->i_private;
- size_t nread;
- irqstate_t flags;
- int ret = 0;
- int msglen;
-
- if (buflen % 5 ==0 )
- msglen=5;
- else if (buflen % 4 ==0 )
- msglen=4;
- else if (buflen % 3 ==0 )
- msglen=3;
- else if (buflen % 2 ==0 )
- msglen=2;
- else if (buflen == 1)
- msglen=1;
- else
- msglen=5;
-
- if (buflen >= msglen)
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct adc_dev_s *dev = inode->i_private;
+ size_t nread;
+ irqstate_t flags;
+ int ret = 0;
+ int msglen;
+
+ avdbg("buflen: %d\n", (int)buflen);
+
+ if (buflen % 5 == 0)
+ msglen = 5;
+ else if (buflen % 4 == 0)
+ msglen = 4;
+ else if (buflen % 3 == 0)
+ msglen = 3;
+ else if (buflen % 2 == 0)
+ msglen = 2;
+ else if (buflen == 1)
+ msglen = 1;
+ else
+ msglen = 5;
+
+ if (buflen >= msglen)
{
- /* Interrupts must be disabled while accessing the ad_recv FIFO */
+ /* Interrupts must be disabled while accessing the ad_recv FIFO */
- flags = irqsave();
- while (dev->ad_recv.af_head == dev->ad_recv.af_tail)
+ flags = irqsave();
+ while (dev->ad_recv.af_head == dev->ad_recv.af_tail)
{
- /* The receive FIFO is empty -- was non-blocking mode selected? */
+ /* The receive FIFO is empty -- was non-blocking mode selected? */
- if (filep->f_oflags & O_NONBLOCK)
+ if (filep->f_oflags & O_NONBLOCK)
{
- ret = -EAGAIN;
- goto return_with_irqdisabled;
+ ret = -EAGAIN;
+ goto return_with_irqdisabled;
}
- /* Wait for a message to be received */
+ /* Wait for a message to be received */
- dev->ad_nrxwaiters++;
- ret = sem_wait(&dev->ad_recv.af_sem);
- dev->ad_nrxwaiters--;
- if (ret < 0)
+ dev->ad_nrxwaiters++;
+ ret = sem_wait(&dev->ad_recv.af_sem);
+ dev->ad_nrxwaiters--;
+ if (ret < 0)
{
- ret = -errno;
- goto return_with_irqdisabled;
+ ret = -errno;
+ goto return_with_irqdisabled;
}
}
- /* The ad_recv FIFO is not empty. Copy all buffered data that will fit
- * in the user buffer.
- */
+ /* The ad_recv FIFO is not empty. Copy all buffered data that will fit
+ * in the user buffer.
+ */
- nread = 0;
- do
+ nread = 0;
+ do
{
- FAR struct adc_msg_s *msg = &dev->ad_recv.af_buffer[dev->ad_recv.af_head];
+ FAR struct adc_msg_s *msg = &dev->ad_recv.af_buffer[dev->ad_recv.af_head];
- /* Will the next message in the FIFO fit into the user buffer? */
+ /* Will the next message in the FIFO fit into the user buffer? */
- if (ret + msglen > buflen)
+ if (ret + msglen > buflen)
{
- break;
+ break;
}
- /* Copy the message to the user buffer */
+ /* Copy the message to the user buffer */
- if (msglen==1)
+ if (msglen == 1)
{
- buffer[nread]=msg->am_data>>24; //Only one channel,read highest 8bits
+ /* Only one channel,read highest 8-bits */
+
+ buffer[nread] = msg->am_data >> 24;
}
- else if (msglen==2)
+ else if (msglen == 2)
{
- *(int16_t *)&buffer[nread]=msg->am_data>>16; //Only one channel,read highest 16bits
+ /* Only one channel, read highest 16-bits */
+
+ *(int16_t *)&buffer[nread] = msg->am_data >> 16;
}
- else if (msglen==3)
+ else if (msglen == 3)
{
- buffer[nread]=msg->am_channel;
- *(int16_t *)&buffer[nread+1]=msg->am_data>>16; //read channel highest 16bits
+ /* Read channel highest 16-bits */
+
+ buffer[nread] = msg->am_channel;
+ *(int16_t *)&buffer[nread + 1] = msg->am_data >> 16;
}
- else if (msglen==4)
+ else if (msglen == 4)
{
- *(int32_t *)&buffer[nread]=msg->am_data; //read channel highest 24bits
- buffer[nread]=msg->am_channel;
+ /* read channel highest 24-bits */
+
+ *(int32_t *)&buffer[nread] = msg->am_data;
+ buffer[nread] = msg->am_channel;
}
- else
+ else
{
- *(int32_t *)&buffer[nread+1]=msg->am_data; //read all
- buffer[nread]=msg->am_channel;
+ /* Read all */
+
+ *(int32_t *)&buffer[nread + 1] = msg->am_data;
+ buffer[nread] = msg->am_channel;
}
- nread += msglen;
+ nread += msglen;
- /* Increment the head of the circular message buffer */
+ /* Increment the head of the circular message buffer */
- if (++dev->ad_recv.af_head >= CONFIG_ADC_FIFOSIZE)
+ if (++dev->ad_recv.af_head >= CONFIG_ADC_FIFOSIZE)
{
- dev->ad_recv.af_head = 0;
+ dev->ad_recv.af_head = 0;
}
}
- while (dev->ad_recv.af_head != dev->ad_recv.af_tail);
+ while (dev->ad_recv.af_head != dev->ad_recv.af_tail);
- /* All on the messages have bee transferred. Return the number of bytes
- * that were read.
- */
+ /* All on the messages have bee transferred. Return the number of bytes
+ * that were read.
+ */
- ret = nread;
+ ret = nread;
return_with_irqdisabled:
- irqrestore(flags);
+ irqrestore(flags);
}
- return ret;
+
+ avdbg("Returning: %d\n", ret);
+ return ret;
}
/************************************************************************************
@@ -332,7 +345,7 @@ return_with_irqdisabled:
static ssize_t adc_write(FAR struct file *filep, FAR const char *buffer, size_t buflen)
{
- return 0;
+ return 0;
}
/************************************************************************************
@@ -341,12 +354,12 @@ static ssize_t adc_write(FAR struct file *filep, FAR const char *buffer, size_t
static int adc_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
- FAR struct inode *inode = filep->f_inode;
- FAR struct adc_dev_s *dev = inode->i_private;
- int ret = OK;
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct adc_dev_s *dev = inode->i_private;
+ int ret = OK;
- ret = dev->ad_ops->ao_ioctl(dev, cmd, arg);
- return ret;
+ ret = dev->ad_ops->ao_ioctl(dev, cmd, arg);
+ return ret;
}
/****************************************************************************
@@ -355,51 +368,53 @@ static int adc_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
int adc_receive(FAR struct adc_dev_s *dev, uint8_t ch, int32_t data)
{
- FAR struct adc_fifo_s *fifo = &dev->ad_recv;
- int nexttail;
- int err = -ENOMEM;
+ FAR struct adc_fifo_s *fifo = &dev->ad_recv;
+ int nexttail;
+ int err = -ENOMEM;
- /* Check if adding this new message would over-run the drivers ability to enqueue
- * read data.
- */
+ /* Check if adding this new message would over-run the drivers ability to enqueue
+ * read data.
+ */
- nexttail = fifo->af_tail + 1;
- if (nexttail >= CONFIG_ADC_FIFOSIZE)
+ nexttail = fifo->af_tail + 1;
+ if (nexttail >= CONFIG_ADC_FIFOSIZE)
{
- nexttail = 0;
+ nexttail = 0;
}
- /* Refuse the new data if the FIFO is full */
+ /* Refuse the new data if the FIFO is full */
- if (nexttail != fifo->af_head)
+ if (nexttail != fifo->af_head)
{
- /* Add the new, decoded CAN message at the tail of the FIFO */
+ /* Add the new, decoded CAN message at the tail of the FIFO */
- fifo->af_buffer[fifo->af_tail].am_channel = ch;
- fifo->af_buffer[fifo->af_tail].am_data=data;
+ fifo->af_buffer[fifo->af_tail].am_channel = ch;
+ fifo->af_buffer[fifo->af_tail].am_data = data;
- /* Increment the tail of the circular buffer */
+ /* Increment the tail of the circular buffer */
- fifo->af_tail = nexttail;
+ fifo->af_tail = nexttail;
- if(dev->ad_nrxwaiters>0)
- sem_post(&fifo->af_sem);
- err = OK;
+ if (dev->ad_nrxwaiters > 0)
+ {
+ sem_post(&fifo->af_sem);
+ }
+ err = OK;
}
return err;
}
int adc_register(FAR const char *path, FAR struct adc_dev_s *dev)
{
- /* Initialize the ADC device structure */
+ /* Initialize the ADC device structure */
- dev->ad_ocount = 0;
+ dev->ad_ocount = 0;
- sem_init(&dev->ad_recv.af_sem, 0, 0);
- sem_init(&dev->ad_closesem, 0, 1);
+ sem_init(&dev->ad_recv.af_sem, 0, 0);
+ sem_init(&dev->ad_closesem, 0, 1);
- dev->ad_ops->ao_reset(dev);
+ dev->ad_ops->ao_reset(dev);
- return register_driver(path, &adc_fops, 0444, dev);
+ return register_driver(path, &adc_fops, 0444, dev);
}