summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-03-02 10:18:25 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-03-02 10:18:25 -0600
commitda8a477e3a03a18876f2e75afc8d505ee8c1a37d (patch)
tree95ea02317cc6607240e72248f13f8cb523b2860c /nuttx/drivers
parentb81919576cf1fba593cf339c25325bd2efff3383 (diff)
downloadpx4-nuttx-da8a477e3a03a18876f2e75afc8d505ee8c1a37d.tar.gz
px4-nuttx-da8a477e3a03a18876f2e75afc8d505ee8c1a37d.tar.bz2
px4-nuttx-da8a477e3a03a18876f2e75afc8d505ee8c1a37d.zip
Review and bring closer to nuttx coding style
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/analog/ad5410.c101
-rw-r--r--nuttx/drivers/analog/ads1255.c48
2 files changed, 79 insertions, 70 deletions
diff --git a/nuttx/drivers/analog/ad5410.c b/nuttx/drivers/analog/ad5410.c
index 0ad9fd14b..9caf675ab 100644
--- a/nuttx/drivers/analog/ad5410.c
+++ b/nuttx/drivers/analog/ad5410.c
@@ -74,10 +74,11 @@
/****************************************************************************
* ad_private Types
****************************************************************************/
+
struct up_dev_s
{
- int devno;
- FAR struct spi_dev_s *spi; /* Cached SPI device reference */
+ int devno;
+ FAR struct spi_dev_s *spi; /* Cached SPI device reference */
};
/****************************************************************************
@@ -100,19 +101,20 @@ static int dac_interrupt(int irq, void *context);
static const struct dac_ops_s g_dacops =
{
- .ao_reset =dac_reset,
- .ao_setup = dac_setup,
- .ao_shutdown = dac_shutdown,
- .ao_txint = dac_txint,
- .ao_send = dac_send,
- .ao_ioctl = dac_ioctl,
+ .ao_reset = dac_reset,
+ .ao_setup = dac_setup,
+ .ao_shutdown = dac_shutdown,
+ .ao_txint = dac_txint,
+ .ao_send = dac_send,
+ .ao_ioctl = dac_ioctl,
};
static struct up_dev_s g_dacpriv;
+
static struct dac_dev_s g_dacdev =
{
- .ad_ops = &g_dacops,
- .ad_priv= &g_dacpriv,
+ .ad_ops = &g_dacops,
+ .ad_priv = &g_dacpriv,
};
/****************************************************************************
@@ -120,60 +122,66 @@ static struct dac_dev_s g_dacdev =
****************************************************************************/
/* Reset the DAC device. Called early to initialize the hardware. This
-* is called, before ao_setup() and on error conditions.
-*/
+ * is called, before ao_setup() and on error conditions.
+ */
+
static void dac_reset(FAR struct dac_dev_s *dev)
{
-
}
/* Configure the DAC. This method is called the first time that the DAC
-* device is opened. This will occur when the port is first opened.
-* This setup includes configuring and attaching DAC interrupts. Interrupts
-* are all disabled upon return.
-*/
+ * device is opened. This will occur when the port is first opened.
+ * This setup includes configuring and attaching DAC interrupts. Interrupts
+ * are all disabled upon return.
+ */
+
static int dac_setup(FAR struct dac_dev_s *dev)
{
- FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
- FAR struct spi_dev_s *spi = priv->spi;
- SPI_SELECT(spi, priv->devno, true);
- SPI_SEND(spi,AD5410_REG_CMD);
- SPI_SEND(spi,(AD5410_CMD_OUTEN|AD5410_CMD_420MA)>>8);
- SPI_SEND(spi,AD5410_CMD_OUTEN|AD5410_CMD_420MA);
- SPI_SELECT(spi, priv->devno, false);
- return OK;
+ FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
+ FAR struct spi_dev_s *spi = priv->spi;
+
+ SPI_SELECT(spi, priv->devno, true);
+ SPI_SEND(spi,AD5410_REG_CMD);
+ SPI_SEND(spi,(AD5410_CMD_OUTEN|AD5410_CMD_420MA)>>8);
+ SPI_SEND(spi,AD5410_CMD_OUTEN|AD5410_CMD_420MA);
+ SPI_SELECT(spi, priv->devno, false);
+ return OK;
}
/* Disable the DAC. This method is called when the DAC device is closed.
-* This method reverses the operation the setup method.
-*/
+ * This method reverses the operation the setup method.
+ */
+
static void dac_shutdown(FAR struct dac_dev_s *dev)
{
}
/* Call to enable or disable TX interrupts */
+
static void dac_txint(FAR struct dac_dev_s *dev, bool enable)
{
}
static int dac_send(FAR struct dac_dev_s *dev, FAR struct dac_msg_s *msg)
{
- FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
- FAR struct spi_dev_s *spi = priv->spi;
- SPI_SELECT(spi, priv->devno, true);
- SPI_SEND(spi,AD5410_REG_WR);
- SPI_SEND(spi,(uint8_t)(msg->am_data>>24));
- SPI_SEND(spi,(uint8_t)(msg->am_data>>16));
- SPI_SELECT(spi, priv->devno, false);
- dac_txdone(&g_dacdev);
- return 0;
+ FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->ad_priv;
+ FAR struct spi_dev_s *spi = priv->spi;
+
+ SPI_SELECT(spi, priv->devno, true);
+ SPI_SEND(spi,AD5410_REG_WR);
+ SPI_SEND(spi,(uint8_t)(msg->am_data>>24));
+ SPI_SEND(spi,(uint8_t)(msg->am_data>>16));
+ SPI_SELECT(spi, priv->devno, false);
+ dac_txdone(&g_dacdev);
+ return 0;
}
/* All ioctl calls will be routed through this method */
+
static int dac_ioctl(FAR struct dac_dev_s *dev, int cmd, unsigned long arg)
{
- dbg("Fix me:Not Implemented\n");
- return 0;
+ dbg("Fix me:Not Implemented\n");
+ return 0;
}
/****************************************************************************
@@ -187,19 +195,20 @@ static int dac_ioctl(FAR struct dac_dev_s *dev, int cmd, unsigned long arg)
* Initialize the selected DAC port
*
* Input Parameter:
- * Port number (for hardware that has mutiple DAC interfaces)
+ * Port number (for hardware that has multiple DAC interfaces)
*
* Returned Value:
- * Valid ad5410 device structure reference on succcess; a NULL on failure
+ * Valid ad5410 device structure reference on success; a NULL on failure
*
****************************************************************************/
-FAR struct dac_dev_s *up_ad5410initialize(FAR struct spi_dev_s *spi, unsigned int devno)
+FAR struct dac_dev_s *up_ad5410initialize(FAR struct spi_dev_s *spi,
+ unsigned int devno)
{
- FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_dacdev.ad_priv;
- priv->spi=spi;
- priv->devno=devno;
- return &g_dacdev;
+ FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_dacdev.ad_priv;
+
+ priv->spi=spi;
+ priv->devno=devno;
+ return &g_dacdev;
}
#endif
-
diff --git a/nuttx/drivers/analog/ads1255.c b/nuttx/drivers/analog/ads1255.c
index 2d8d59774..0fbf63c19 100644
--- a/nuttx/drivers/analog/ads1255.c
+++ b/nuttx/drivers/analog/ads1255.c
@@ -67,38 +67,38 @@
#define ADS125X_PGA32 0x05
#define ADS125X_PGA64 0x06
-#define ADS125X_RDATA 0x01 //Read Data
-#define ADS125X_RDATAC 0x03 //Read Data Continuously
-#define ADS125X_SDATAC 0x0F //Stop Read Data Continuously
-#define ADS125X_RREG 0x10 //Read from REG
-#define ADS125X_WREG 0x50 //Write to REG
-#define ADS125X_SELFCAL 0xF0 //Offset and Gain Self-Calibration
-#define ADS125X_SELFOCAL 0xF1 //Offset Self-Calibration
-#define ADS125X_SELFGCAL 0xF2 //Gain Self-Calibration
-#define ADS125X_SYSOCAL 0xF3 //System Offset Calibration
-#define ADS125X_SYSGCAL 0xF4 //System Gain Calibration
-#define ADS125X_SYNC 0xFC //Synchronize the A/D Conversion
-#define ADS125X_STANDBY 0xFD //Begin Standby Mode
-#define ADS125X_RESET 0xFE //Reset to Power-Up Values
-#define ADS125X_WAKEUP 0xFF //Completes SYNC and Exits Standby Mode
+#define ADS125X_RDATA 0x01 /* Read Data */
+#define ADS125X_RDATAC 0x03 /* Read Data Continuously */
+#define ADS125X_SDATAC 0x0F /* Stop Read Data Continuously */
+#define ADS125X_RREG 0x10 /* Read from REG */
+#define ADS125X_WREG 0x50 /* Write to REG */
+#define ADS125X_SELFCAL 0xF0 /* Offset and Gain Self-Calibration */
+#define ADS125X_SELFOCAL 0xF1 /* Offset Self-Calibration */
+#define ADS125X_SELFGCAL 0xF2 /* Gain Self-Calibration */
+#define ADS125X_SYSOCAL 0xF3 /* System Offset Calibration */
+#define ADS125X_SYSGCAL 0xF4 /* System Gain Calibration */
+#define ADS125X_SYNC 0xFC /* Synchronize the A/D Conversion */
+#define ADS125X_STANDBY 0xFD /* Begin Standby Mode */
+#define ADS125X_RESET 0xFE /* Reset to Power-Up Values */
+#define ADS125X_WAKEUP 0xFF /* Completes SYNC and Exits Standby Mode */
#ifndef CONFIG_ADS1255_FREQUENCY
-#define CONFIG_ADS1255_FREQUENCY 1000000
+# define CONFIG_ADS1255_FREQUENCY 1000000
#endif
#ifndef CONFIG_ADS1255_MUX
-#define CONFIG_ADS1255_MUX 0x01
+# define CONFIG_ADS1255_MUX 0x01
#endif
#ifndef CONFIG_ADS1255_CHMODE
-#define CONFIG_ADS1255_CHMODE 0x00
+# define CONFIG_ADS1255_CHMODE 0x00
#endif
#ifndef CONFIG_ADS1255_BUFON
-#define CONFIG_ADS1255_BUFON 1
+# define CONFIG_ADS1255_BUFON 1
#endif
#ifndef CONFIG_ADS1255_PGA
-#define CONFIG_ADS1255_PGA ADS125X_PGA2
+# define CONFIG_ADS1255_PGA ADS125X_PGA2
#endif
#ifndef CONFIG_ADS1255_SPS
-#define CONFIG_ADS1255_SPS 50
+# define CONFIG_ADS1255_SPS 50
#endif
/****************************************************************************
@@ -330,14 +330,15 @@ static int adc_interrupt(int irq, void *context)
* Initialize the selected adc port
*
* Input Parameter:
- * Port number (for hardware that has mutiple adc interfaces)
+ * Port number (for hardware that has multiple adc interfaces)
*
* Returned Value:
- * Valid can device structure reference on succcess; a NULL on failure
+ * Valid can device structure reference on success; a NULL on failure
*
****************************************************************************/
-FAR struct adc_dev_s *up_ads1255initialize(FAR struct spi_dev_s *spi, unsigned int devno)
+FAR struct adc_dev_s *up_ads1255initialize(FAR struct spi_dev_s *spi,
+ unsigned int devno)
{
FAR struct up_dev_s *priv = (FAR struct up_dev_s *)g_adcdev.ad_priv;
@@ -348,4 +349,3 @@ FAR struct adc_dev_s *up_ads1255initialize(FAR struct spi_dev_s *spi, unsigned i
return &g_adcdev;
}
#endif
-