summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-04-13 13:18:06 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-04-13 13:18:06 -0600
commit3900ca5789a408413a6e590683b4babe76ac7fad (patch)
tree228f5246dcea113238b5925775b9b9ccf8585238 /nuttx
parent74a4eb6d1612d63958e14a240cc526c9be8041e0 (diff)
downloadpx4-nuttx-3900ca5789a408413a6e590683b4babe76ac7fad.tar.gz
px4-nuttx-3900ca5789a408413a6e590683b4babe76ac7fad.tar.bz2
px4-nuttx-3900ca5789a408413a6e590683b4babe76ac7fad.zip
Cosmetic changes for coding style; removal of dangling spaces at the end of lines
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_sdhc.c71
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c48
-rw-r--r--nuttx/configs/cloudctrl/src/up_usb.c18
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_usb.c18
-rw-r--r--nuttx/configs/shenzhou/src/up_usb.c18
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_usb.c18
-rw-r--r--nuttx/configs/stm3240g-eval/src/up_usb.c18
-rw-r--r--nuttx/configs/stm32f429i-disco/src/stm32_usb.c18
-rw-r--r--nuttx/drivers/sensors/lis331dl.c399
-rw-r--r--nuttx/fs/fs_closeblockdriver.c2
-rw-r--r--nuttx/fs/fs_findblockdriver.c2
-rw-r--r--nuttx/fs/fs_umount.c4
-rw-r--r--nuttx/libc/sched/sched_getprioritymin.c2
-rw-r--r--nuttx/libnx/nxtk/nxtk_drawlinetoolbar.c2
-rw-r--r--nuttx/libnx/nxtk/nxtk_drawlinewindow.c2
-rwxr-xr-xnuttx/tools/mkfsdata.pl8
16 files changed, 353 insertions, 295 deletions
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_sdhc.c b/nuttx/arch/arm/src/kinetis/kinetis_sdhc.c
index 4c392cbf8..cf2109130 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_sdhc.c
+++ b/nuttx/arch/arm/src/kinetis/kinetis_sdhc.c
@@ -164,7 +164,7 @@
struct kinetis_dev_s
{
struct sdio_dev_s dev; /* Standard, base SDIO interface */
-
+
/* Kinetis-specific extensions */
/* Event support */
@@ -733,7 +733,8 @@ static void kinetis_dataconfig(struct kinetis_dev_s *priv, bool bwrite,
{
watermark = (SDHC_MAX_WATERMARK / 2);
}
- putreg32(watermark << SDHC_WML_RD_SHIFT, KINETIS_SDHC_WML);
+
+ putreg32(watermark << SDHC_WML_RD_SHIFT, KINETIS_SDHC_WML);
}
#endif
}
@@ -825,7 +826,7 @@ static void kinetis_transmit(struct kinetis_dev_s *priv)
{
data.b[i] = *ptr++;
}
-
+
/* Now the transfer is finished */
priv->remaining = 0;
@@ -870,7 +871,7 @@ static void kinetis_receive(struct kinetis_dev_s *priv)
* queued words is greater than or equal to 1.
*/
- putreg32(1 << SDHC_WML_RD_SHIFT, KINETIS_SDHC_WML);
+ putreg32(1 << SDHC_WML_RD_SHIFT, KINETIS_SDHC_WML);
/* Loop while there is space to store the data, waiting for buffer read
* ready (BRR)
@@ -925,7 +926,8 @@ static void kinetis_receive(struct kinetis_dev_s *priv)
{
watermark = (SDHC_MAX_WATERMARK / 2);
}
- putreg32(watermark << SDHC_WML_RD_SHIFT, KINETIS_SDHC_WML);
+
+ putreg32(watermark << SDHC_WML_RD_SHIFT, KINETIS_SDHC_WML);
fllvdbg("Exit: remaining: %d IRQSTAT: %08x WML: %08x\n",
priv->remaining, getreg32(KINETIS_SDHC_IRQSTAT),
@@ -1039,7 +1041,7 @@ static void kinetis_endtransfer(struct kinetis_dev_s *priv, sdio_eventset_t wkup
kinetis_configxfrints(priv, 0);
/* Clearing pending interrupt status on all transfer related interrupts */
-
+
putreg32(SDHC_XFRDONE_INTS, KINETIS_SDHC_IRQSTAT);
/* If this was a DMA transfer, make sure that DMA is stopped */
@@ -1071,7 +1073,7 @@ static void kinetis_endtransfer(struct kinetis_dev_s *priv, sdio_eventset_t wkup
}
/****************************************************************************
- * Interrrupt Handling
+ * Interrupt Handling
****************************************************************************/
/****************************************************************************
@@ -1103,9 +1105,9 @@ static int kinetis_interrupt(int irq, void *context)
regval = getreg32(KINETIS_SDHC_IRQSIGEN);
enabled = getreg32(KINETIS_SDHC_IRQSTAT) & regval;
- fllvdbg("IRQSTAT: %08x IRQSIGEN %08x enabled: %08x\n",
+ fllvdbg("IRQSTAT: %08x IRQSIGEN %08x enabled: %08x\n",
getreg32(KINETIS_SDHC_IRQSTAT), regval, enabled);
-
+
/* Disable card interrupts to clear the card interrupt to the host system. */
regval &= ~SDHC_INT_CINT;
@@ -1217,7 +1219,7 @@ static int kinetis_interrupt(int irq, void *context)
*
* Description:
* Locks the bus. Function calls low-level multiplexed bus routines to
- * resolve bus requests and acknowledgment issues.
+ * resolve bus requests and acknowledgement issues.
*
* Input Parameters:
* dev - An instance of the SDIO device interface
@@ -1230,7 +1232,7 @@ static int kinetis_interrupt(int irq, void *context)
#ifdef CONFIG_SDIO_MUXBUS
static int kinetis_lock(FAR struct sdio_dev_s *dev, bool lock)
-{
+{
/* Single SDIO instance so there is only one possibility. The multiplex
* bus is part of board support package.
*/
@@ -1247,7 +1249,7 @@ static int kinetis_lock(FAR struct sdio_dev_s *dev, bool lock)
* Reset the SDIO controller. Undo all setup and initialization.
*
* Input Parameters:
- * dev - An instance of the SDIO device interface
+ * dev - An instance of the SDIO device interface
*
* Returned Value:
* None
@@ -1406,12 +1408,12 @@ static void kinetis_frequency(FAR struct sdio_dev_s *dev, uint32_t frequency)
*
* For example, if the base clock frequency is 96 MHz, and the target
* frequency is 25 MHz, the following logic will select prescaler.
- *
+ *
* 96MHz / 2 <= 25MHz <= 96MHz / 2 /16 -- YES, prescaler == 2
*
* If the target frequency is 400 kHz, the following logic will select
* prescaler:
- *
+ *
* 96MHz / 2 <= 400KHz <= 96MHz / 2 / 16 -- NO
* 96MHz / 4 <= 400KHz <= 96MHz / 4 / 16 -- NO
* 96MHz / 8 <= 400KHz <= 96MHz / 8 / 16 -- NO
@@ -1479,7 +1481,7 @@ static void kinetis_frequency(FAR struct sdio_dev_s *dev, uint32_t frequency)
*
* Or, for example, if the target frequency is 400 kHz and the selected
* prescaler is 16, the following* logic will select prescaler:
- *
+ *
* prescaled = 96MHz / 16 = 6MHz
* divisor = (6MHz + 200KHz) / 400KHz = 15
*
@@ -1686,7 +1688,7 @@ static int kinetis_attach(FAR struct sdio_dev_s *dev)
putreg32(0, KINETIS_SDHC_IRQSIGEN);
putreg32(SDHC_INT_ALL, KINETIS_SDHC_IRQSTAT);
- /* Set the interrrupt priority */
+ /* Set the interrupt priority */
up_prioritize_irq(KINETIS_IRQ_SDHC, CONFIG_KINETIS_SDHC_PRIO);
@@ -1778,7 +1780,7 @@ static int kinetis_sendcmd(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t ar
}
}
}
-
+
/* Configure response type bits */
switch (cmd & MMCSD_RESPONSE_MASK)
@@ -1790,7 +1792,7 @@ static int kinetis_sendcmd(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t ar
case MMCSD_R1B_RESPONSE: /* Response length 48, check busy & cmdindex*/
regval |= (SDHC_XFERTYP_RSPTYP_LEN48BSY|SDHC_XFERTYP_CICEN|SDHC_XFERTYP_CCCEN);
break;
-
+
case MMCSD_R1_RESPONSE: /* Response length 48, check cmdindex */
case MMCSD_R5_RESPONSE:
case MMCSD_R6_RESPONSE:
@@ -1988,7 +1990,7 @@ static int kinetis_cancel(FAR struct sdio_dev_s *dev)
/* Clearing pending interrupt status on all transfer- and event- related
* interrupts
*/
-
+
putreg32(SDHC_WAITALL_INTS, KINETIS_SDHC_IRQSTAT);
/* Cancel any watchdog timeout */
@@ -2066,7 +2068,7 @@ static int kinetis_waitresponse(FAR struct sdio_dev_s *dev, uint32_t cmd)
/* Then wait for the Command Complete (CC) indication (or timeout). The
* CC bit is set when the end bit of the command response is received
- * (except Auto CMD12).
+ * (except Auto CMD12).
*/
while ((getreg32(KINETIS_SDHC_IRQSTAT) & SDHC_INT_CC) == 0)
@@ -2117,7 +2119,8 @@ static int kinetis_waitresponse(FAR struct sdio_dev_s *dev, uint32_t cmd)
*
****************************************************************************/
-static int kinetis_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t *rshort)
+static int kinetis_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd,
+ uint32_t *rshort)
{
uint32_t regval;
int ret = OK;
@@ -2130,7 +2133,7 @@ static int kinetis_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32
* 7:1 bit6 - bit0 CRC7
* 0 1 End bit
*
- * R1b Identical to R1 with the additional busy signaling via the data
+ * R1b Identical to R1 with the additional busy signalling via the data
* line.
*
* R6 Published RCA Response (48-bit, SD card only)
@@ -2227,7 +2230,7 @@ static int kinetis_recvlong(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t r
ret = -EIO;
}
}
-
+
/* Return the long response in CMDRSP3..0*/
if (rlong)
@@ -2326,7 +2329,7 @@ static void kinetis_waitenable(FAR struct sdio_dev_s *dev,
{
struct kinetis_dev_s *priv = (struct kinetis_dev_s*)dev;
uint32_t waitints;
-
+
DEBUGASSERT(priv != NULL);
/* Disable event-related interrupts */
@@ -2395,7 +2398,7 @@ static sdio_eventset_t kinetis_eventwait(FAR struct sdio_dev_s *dev,
{
int delay;
- /* Yes.. Handle a cornercase */
+ /* Yes.. Handle a corner case */
if (!timeout)
{
@@ -2428,9 +2431,9 @@ static sdio_eventset_t kinetis_eventwait(FAR struct sdio_dev_s *dev,
kinetis_takesem(priv);
wkupevent = priv->wkupevent;
-
+
/* Check if the event has occurred. When the event has occurred, then
- * evenset will be set to 0 and wkupevent will be set to a nonzero value.
+ * evenset will be set to 0 and wkupevent will be set to a non-zero value.
*/
if (wkupevent != 0)
@@ -2462,7 +2465,7 @@ static sdio_eventset_t kinetis_eventwait(FAR struct sdio_dev_s *dev,
*
* Events are automatically disabled once the callback is performed and no
* further callback events will occur until they are again enabled by
- * calling this methos.
+ * calling this method.
*
* Input Parameters:
* dev - An instance of the SDIO device interface
@@ -2500,7 +2503,7 @@ static void kinetis_callbackenable(FAR struct sdio_dev_s *dev,
*
* Input Parameters:
* dev - Device-specific state data
- * callback - The funtion to call on the media change
+ * callback - The function to call on the media change
* arg - A caller provided value to return with the callback
*
* Returned Value:
@@ -2595,7 +2598,7 @@ static int kinetis_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer,
kinetis_configxfrints(priv, SDHC_DMADONE_INTS);
putreg32((uint32_t)buffer, KINETIS_SDHC_DSADDR);
-
+
/* Sample the register state */
kinetis_sample(priv, SAMPLENDX_AFTER_SETUP);
@@ -2805,7 +2808,7 @@ FAR struct sdio_dev_s *sdhc_initialize(int slotno)
/* Configure pins for 1 or 4-bit, wide-bus operation (the chip is capable
* of 8-bit wide bus operation but D4-D7 are not configured).
- *
+ *
* If bus is multiplexed then there is a custom bus configuration utility
* in the scope of the board support package.
*/
@@ -2851,13 +2854,13 @@ FAR struct sdio_dev_s *sdhc_initialize(int slotno)
* Name: sdhc_mediachange
*
* Description:
- * Called by board-specific logic -- posssible from an interrupt handler --
+ * Called by board-specific logic -- possible from an interrupt handler --
* in order to signal to the driver that a card has been inserted or
* removed from the slot
*
* Input Parameters:
* dev - An instance of the SDIO driver device state structure.
- * cardinslot - true is a card has been detected in the slot; false if a
+ * cardinslot - true is a card has been detected in the slot; false if a
* card has been removed from the slot. Only transitions
* (inserted->removed or removed->inserted should be reported)
*
@@ -2884,6 +2887,7 @@ void sdhc_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot)
{
priv->cdstatus &= ~SDIO_STATUS_PRESENT;
}
+
fvdbg("cdstatus OLD: %02x NEW: %02x\n", cdstatus, priv->cdstatus);
/* Perform any requested callback if the status has changed */
@@ -2892,6 +2896,7 @@ void sdhc_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot)
{
kinetis_callback(priv);
}
+
irqrestore(flags);
}
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
index 2d927db50..2b7c157a0 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
@@ -291,7 +291,7 @@ struct lpc17_driver_s
uint32_t lp_inten; /* Shadow copy of INTEN register */
WDOG_ID lp_txpoll; /* TX poll timer */
WDOG_ID lp_txtimeout; /* TX timeout timer */
-
+
#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
struct lpc17_statistics_s lp_stat;
#endif
@@ -638,7 +638,7 @@ static int lpc17_transmit(struct lpc17_driver_s *priv)
memcpy(txbuffer, priv->lp_dev.d_buf, priv->lp_dev.d_len);
/* Bump the producer index, making the packet available for transmission. */
-
+
if (++prodidx >= CONFIG_NET_NTXDESC)
{
/* Wrap back to index zero */
@@ -723,10 +723,10 @@ static int lpc17_uiptxpoll(struct uip_driver_s *dev)
* possibly a response to the incoming packet (but probably not, in reality).
* However, since the Rx and Tx operations are decoupled, there is no
* guarantee that there will be a Tx descriptor available at that time.
- * This function will perform that check and, if no Tx descriptor is
+ * This function will perform that check and, if no Tx descriptor is
* available, this function will (1) stop incoming Rx processing (bad), and
* (2) hold the outgoing packet in a pending state until the next Tx
- * interrupt occurs.
+ * interrupt occurs.
*
* Parameters:
* priv - Reference to the driver state structure
@@ -757,7 +757,7 @@ static void lpc17_response(struct lpc17_driver_s *priv)
/* No.. mark the Tx as pending and halt further Tx interrupts */
DEBUGASSERT((priv->lp_inten & ETH_INT_TXDONE) != 0);
-
+
priv->lp_txpending = true;
priv->lp_inten &= ~ETH_RXINTS;
lpc17_putreg(priv->lp_inten, LPC17_ETH_INTEN);
@@ -807,7 +807,7 @@ static void lpc17_rxdone(struct lpc17_driver_s *priv)
EMAC_STAT(priv, rx_packets);
/* Get the Rx status and packet length (-4+1) */
-
+
rxstat = (uint32_t*)(LPC17_RXSTAT_BASE + (considx << 3));
pktlen = (*rxstat & RXSTAT_INFO_RXSIZE_MASK) - 3;
@@ -827,7 +827,7 @@ static void lpc17_rxdone(struct lpc17_driver_s *priv)
* be the same size as our max packet size, any fragments also
* imply that the packet is too big.
*/
-
+
/* else */ if (pktlen > CONFIG_NET_BUFSIZE + CONFIG_NET_GUARDSIZE)
{
nlldbg("Too big. considx: %08x prodidx: %08x pktlen: %d rxstat: %08x\n",
@@ -854,11 +854,11 @@ static void lpc17_rxdone(struct lpc17_driver_s *priv)
void *rxbuffer;
/* Get the Rx buffer address from the Rx descriptor */
-
+
rxdesc = (uint32_t*)(LPC17_RXDESC_BASE + (considx << 3));
rxbuffer = (void*)*rxdesc;
- /* Copy the data data from the EMAC DMA RAM to priv->lp_dev.d_buf.
+ /* Copy the data data from the EMAC DMA RAM to priv->lp_dev.d_buf.
* Set amount of data in priv->lp_dev.d_len
*
* Here would be a great performance improvement: Remove the
@@ -1034,7 +1034,7 @@ static int lpc17_interrupt(int irq, void *context)
/* Clear all pending interrupts */
lpc17_putreg(status, LPC17_ETH_INTCLR);
-
+
/* Handle each pending interrupt **************************************/
/* Check for Wake-Up on Lan *******************************************/
@@ -1076,7 +1076,7 @@ static int lpc17_interrupt(int irq, void *context)
(void)lpc17_ifup(&priv->lp_dev);
}
else
- {
+ {
/* Check for receive events ***************************************/
/* RX ERROR -- Triggered on receive errors: AlignmentError,
* RangeError, LengthError, SymbolError, CRCError or NoDescriptor
@@ -1116,7 +1116,7 @@ static int lpc17_interrupt(int irq, void *context)
lpc17_rxdone(priv);
}
-
+
/* Check for Tx events ********************************************/
/* TX ERROR -- Triggered on transmit errors: LateCollision,
* ExcessiveCollision and ExcessiveDefer, NoDescriptor or Underrun.
@@ -1255,7 +1255,7 @@ static void lpc17_polltimer(int argc, uint32_t arg, ...)
*
* Description:
* NuttX Callback: Bring up the Ethernet interface when an IP address is
- * provided
+ * provided
*
* Parameters:
* dev - Reference to the NuttX driver state structure
@@ -1463,7 +1463,7 @@ static int lpc17_ifdown(struct uip_driver_s *dev)
* Function: lpc17_txavail
*
* Description:
- * Driver callback invoked when new TX data is available. This is a
+ * Driver callback invoked when new TX data is available. This is a
* stimulus perform an out-of-cycle poll and, thereby, reduce the TX
* latency.
*
@@ -1516,7 +1516,7 @@ static int lpc17_txavail(struct uip_driver_s *dev)
*
* Parameters:
* dev - Reference to the NuttX driver state structure
- * mac - The MAC address to be added
+ * mac - The MAC address to be added
*
* Returned Value:
* None
@@ -1546,7 +1546,7 @@ static int lpc17_addmac(struct uip_driver_s *dev, const uint8_t *mac)
*
* Parameters:
* dev - Reference to the NuttX driver state structure
- * mac - The MAC address to be removed
+ * mac - The MAC address to be removed
*
* Returned Value:
* None
@@ -1574,7 +1574,7 @@ static int lpc17_rmmac(struct uip_driver_s *dev, const uint8_t *mac)
* Dump GPIO registers
*
* Parameters:
- * None
+ * None
*
* Returned Value:
* None
@@ -1631,7 +1631,7 @@ static void lpc17_showmii(uint8_t phyaddr, const char *msg)
* Parameters:
* phyaddr - The device address where the PHY was discovered
* regaddr - The address of the PHY register to be written
- * phydata - The data to write to the PHY register
+ * phydata - The data to write to the PHY register
*
* Returned Value:
* None
@@ -1891,7 +1891,7 @@ static int lpc17_phymode(uint8_t phyaddr, uint8_t mode)
* Initialize the PHY
*
* Parameters:
- * priv - Pointer to EMAC device driver structure
+ * priv - Pointer to EMAC device driver structure
*
* Returned Value:
* None directly. As a side-effect, it will initialize priv->lp_phyaddr
@@ -1988,7 +1988,7 @@ static inline int lpc17_phyinit(struct lpc17_driver_s *priv)
#ifdef CONFIG_PHY_AUTONEG
/* Setup the Auto-negotiation advertisement: 100 or 10, and HD or FD */
- lpc17_phywrite(phyaddr, MII_ADVERTISE,
+ lpc17_phywrite(phyaddr, MII_ADVERTISE,
(MII_ADVERTISE_100BASETXFULL | MII_ADVERTISE_100BASETXHALF |
MII_ADVERTISE_10BASETXFULL | MII_ADVERTISE_10BASETXHALF |
MII_ADVERTISE_CSMA));
@@ -2146,7 +2146,7 @@ static inline int lpc17_phyinit(struct lpc17_driver_s *priv)
* Initialize the EMAC Tx descriptor table
*
* Parameters:
- * priv - Pointer to EMAC device driver structure
+ * priv - Pointer to EMAC device driver structure
*
* Returned Value:
* None directory.
@@ -2202,7 +2202,7 @@ static inline void lpc17_txdescinit(struct lpc17_driver_s *priv)
* Initialize the EMAC Rx descriptor table
*
* Parameters:
- * priv - Pointer to EMAC device driver structure
+ * priv - Pointer to EMAC device driver structure
*
* Returned Value:
* None directory.
@@ -2278,7 +2278,7 @@ static void lpc17_macmode(uint8_t mode)
if ((mode & LPC17_DUPLEX_MASK) == LPC17_DUPLEX_FULL)
{
/* Set the back-to-back inter-packet gap */
-
+
lpc17_putreg(21, LPC17_ETH_IPGT);
/* Set MAC to operate in full duplex mode with CRC and Pad enabled */
@@ -2296,7 +2296,7 @@ static void lpc17_macmode(uint8_t mode)
else
{
/* Set the back-to-back inter-packet gap */
-
+
lpc17_putreg(18, LPC17_ETH_IPGT);
/* Set MAC to operate in half duplex mode with CRC and Pad enabled */
diff --git a/nuttx/configs/cloudctrl/src/up_usb.c b/nuttx/configs/cloudctrl/src/up_usb.c
index 2ef928c14..f38689b5c 100644
--- a/nuttx/configs/cloudctrl/src/up_usb.c
+++ b/nuttx/configs/cloudctrl/src/up_usb.c
@@ -211,14 +211,14 @@ int stm32_usbhost_initialize(void)
* Enable/disable driving of VBUS 5V output. This function must be provided be
* each platform that implements the STM32 OTG FS host interface
*
- * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
- * or, if 5 V are available on the application board, a basic power switch, must
- * be added externally to drive the 5 V VBUS line. The external charge pump can
- * be driven by any GPIO output. When the application decides to power on VBUS
- * using the chosen GPIO, it must also set the port power bit in the host port
+ * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
+ * or, if 5 V are available on the application board, a basic power switch, must
+ * be added externally to drive the 5 V VBUS line. The external charge pump can
+ * be driven by any GPIO output. When the application decides to power on VBUS
+ * using the chosen GPIO, it must also set the port power bit in the host port
* control and status register (PPWR bit in OTG_FS_HPRT).
*
- * "The application uses this field to control power to this port, and the core
+ * "The application uses this field to control power to this port, and the core
* clears this bit on an overcurrent condition."
*
* Input Parameters:
@@ -234,7 +234,7 @@ int stm32_usbhost_initialize(void)
void stm32_usbhost_vbusdrive(int iface, bool enable)
{
DEBUGASSERT(iface == 0);
-
+
if (enable)
{
/* Enable the Power Switch by driving the enable pin low */
@@ -242,9 +242,9 @@ void stm32_usbhost_vbusdrive(int iface, bool enable)
stm32_gpiowrite(GPIO_OTGFS_PWRON, false);
}
else
- {
+ {
/* Disable the Power Switch by driving the enable pin high */
-
+
stm32_gpiowrite(GPIO_OTGFS_PWRON, true);
}
}
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_usb.c b/nuttx/configs/mikroe-stm32f4/src/up_usb.c
index 967da72fb..9a45c1a9b 100644
--- a/nuttx/configs/mikroe-stm32f4/src/up_usb.c
+++ b/nuttx/configs/mikroe-stm32f4/src/up_usb.c
@@ -210,14 +210,14 @@ int stm32_usbhost_initialize(void)
* Enable/disable driving of VBUS 5V output. This function must be provided be
* each platform that implements the STM32 OTG FS host interface
*
- * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
- * or, if 5 V are available on the application board, a basic power switch, must
- * be added externally to drive the 5 V VBUS line. The external charge pump can
- * be driven by any GPIO output. When the application decides to power on VBUS
- * using the chosen GPIO, it must also set the port power bit in the host port
+ * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
+ * or, if 5 V are available on the application board, a basic power switch, must
+ * be added externally to drive the 5 V VBUS line. The external charge pump can
+ * be driven by any GPIO output. When the application decides to power on VBUS
+ * using the chosen GPIO, it must also set the port power bit in the host port
* control and status register (PPWR bit in OTG_FS_HPRT).
*
- * "The application uses this field to control power to this port, and the core
+ * "The application uses this field to control power to this port, and the core
* clears this bit on an overcurrent condition."
*
* Input Parameters:
@@ -233,7 +233,7 @@ int stm32_usbhost_initialize(void)
void stm32_usbhost_vbusdrive(int iface, bool enable)
{
DEBUGASSERT(iface == 0);
-
+
if (enable)
{
/* Enable the Power Switch by driving the enable pin low */
@@ -241,9 +241,9 @@ void stm32_usbhost_vbusdrive(int iface, bool enable)
stm32_gpiowrite(GPIO_OTGFS_PWRON, false);
}
else
- {
+ {
/* Disable the Power Switch by driving the enable pin high */
-
+
stm32_gpiowrite(GPIO_OTGFS_PWRON, true);
}
}
diff --git a/nuttx/configs/shenzhou/src/up_usb.c b/nuttx/configs/shenzhou/src/up_usb.c
index 95e3a3c39..e3416d86e 100644
--- a/nuttx/configs/shenzhou/src/up_usb.c
+++ b/nuttx/configs/shenzhou/src/up_usb.c
@@ -210,14 +210,14 @@ int stm32_usbhost_initialize(void)
* Enable/disable driving of VBUS 5V output. This function must be provided be
* each platform that implements the STM32 OTG FS host interface
*
- * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
- * or, if 5 V are available on the application board, a basic power switch, must
- * be added externally to drive the 5 V VBUS line. The external charge pump can
- * be driven by any GPIO output. When the application decides to power on VBUS
- * using the chosen GPIO, it must also set the port power bit in the host port
+ * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
+ * or, if 5 V are available on the application board, a basic power switch, must
+ * be added externally to drive the 5 V VBUS line. The external charge pump can
+ * be driven by any GPIO output. When the application decides to power on VBUS
+ * using the chosen GPIO, it must also set the port power bit in the host port
* control and status register (PPWR bit in OTG_FS_HPRT).
*
- * "The application uses this field to control power to this port, and the core
+ * "The application uses this field to control power to this port, and the core
* clears this bit on an overcurrent condition."
*
* Input Parameters:
@@ -233,7 +233,7 @@ int stm32_usbhost_initialize(void)
void stm32_usbhost_vbusdrive(int iface, bool enable)
{
DEBUGASSERT(iface == 0);
-
+
if (enable)
{
/* Enable the Power Switch by driving the enable pin low */
@@ -241,9 +241,9 @@ void stm32_usbhost_vbusdrive(int iface, bool enable)
stm32_gpiowrite(GPIO_OTGFS_PWRON, false);
}
else
- {
+ {
/* Disable the Power Switch by driving the enable pin high */
-
+
stm32_gpiowrite(GPIO_OTGFS_PWRON, true);
}
}
diff --git a/nuttx/configs/stm3220g-eval/src/up_usb.c b/nuttx/configs/stm3220g-eval/src/up_usb.c
index 72187d009..d1638b210 100644
--- a/nuttx/configs/stm3220g-eval/src/up_usb.c
+++ b/nuttx/configs/stm3220g-eval/src/up_usb.c
@@ -210,14 +210,14 @@ int stm32_usbhost_initialize(void)
* Enable/disable driving of VBUS 5V output. This function must be provided be
* each platform that implements the STM32 OTG FS host interface
*
- * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
- * or, if 5 V are available on the application board, a basic power switch, must
- * be added externally to drive the 5 V VBUS line. The external charge pump can
- * be driven by any GPIO output. When the application decides to power on VBUS
- * using the chosen GPIO, it must also set the port power bit in the host port
+ * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
+ * or, if 5 V are available on the application board, a basic power switch, must
+ * be added externally to drive the 5 V VBUS line. The external charge pump can
+ * be driven by any GPIO output. When the application decides to power on VBUS
+ * using the chosen GPIO, it must also set the port power bit in the host port
* control and status register (PPWR bit in OTG_FS_HPRT).
*
- * "The application uses this field to control power to this port, and the core
+ * "The application uses this field to control power to this port, and the core
* clears this bit on an overcurrent condition."
*
* Input Parameters:
@@ -233,7 +233,7 @@ int stm32_usbhost_initialize(void)
void stm32_usbhost_vbusdrive(int iface, bool enable)
{
DEBUGASSERT(iface == 0);
-
+
if (enable)
{
/* Enable the Power Switch by driving the enable pin low */
@@ -241,9 +241,9 @@ void stm32_usbhost_vbusdrive(int iface, bool enable)
stm32_gpiowrite(GPIO_OTGFS_PWRON, false);
}
else
- {
+ {
/* Disable the Power Switch by driving the enable pin high */
-
+
stm32_gpiowrite(GPIO_OTGFS_PWRON, true);
}
}
diff --git a/nuttx/configs/stm3240g-eval/src/up_usb.c b/nuttx/configs/stm3240g-eval/src/up_usb.c
index d27ac3735..e12e65e43 100644
--- a/nuttx/configs/stm3240g-eval/src/up_usb.c
+++ b/nuttx/configs/stm3240g-eval/src/up_usb.c
@@ -210,14 +210,14 @@ int stm32_usbhost_initialize(void)
* Enable/disable driving of VBUS 5V output. This function must be provided be
* each platform that implements the STM32 OTG FS host interface
*
- * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
- * or, if 5 V are available on the application board, a basic power switch, must
- * be added externally to drive the 5 V VBUS line. The external charge pump can
- * be driven by any GPIO output. When the application decides to power on VBUS
- * using the chosen GPIO, it must also set the port power bit in the host port
+ * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
+ * or, if 5 V are available on the application board, a basic power switch, must
+ * be added externally to drive the 5 V VBUS line. The external charge pump can
+ * be driven by any GPIO output. When the application decides to power on VBUS
+ * using the chosen GPIO, it must also set the port power bit in the host port
* control and status register (PPWR bit in OTG_FS_HPRT).
*
- * "The application uses this field to control power to this port, and the core
+ * "The application uses this field to control power to this port, and the core
* clears this bit on an overcurrent condition."
*
* Input Parameters:
@@ -233,7 +233,7 @@ int stm32_usbhost_initialize(void)
void stm32_usbhost_vbusdrive(int iface, bool enable)
{
DEBUGASSERT(iface == 0);
-
+
if (enable)
{
/* Enable the Power Switch by driving the enable pin low */
@@ -241,9 +241,9 @@ void stm32_usbhost_vbusdrive(int iface, bool enable)
stm32_gpiowrite(GPIO_OTGFS_PWRON, false);
}
else
- {
+ {
/* Disable the Power Switch by driving the enable pin high */
-
+
stm32_gpiowrite(GPIO_OTGFS_PWRON, true);
}
}
diff --git a/nuttx/configs/stm32f429i-disco/src/stm32_usb.c b/nuttx/configs/stm32f429i-disco/src/stm32_usb.c
index 11369638e..433ceaccd 100644
--- a/nuttx/configs/stm32f429i-disco/src/stm32_usb.c
+++ b/nuttx/configs/stm32f429i-disco/src/stm32_usb.c
@@ -209,14 +209,14 @@ int stm32_usbhost_initialize(void)
* Enable/disable driving of VBUS 5V output. This function must be provided be
* each platform that implements the STM32 OTG HS host interface
*
- * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
- * or, if 5 V are available on the application board, a basic power switch, must
- * be added externally to drive the 5 V VBUS line. The external charge pump can
- * be driven by any GPIO output. When the application decides to power on VBUS
- * using the chosen GPIO, it must also set the port power bit in the host port
+ * "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
+ * or, if 5 V are available on the application board, a basic power switch, must
+ * be added externally to drive the 5 V VBUS line. The external charge pump can
+ * be driven by any GPIO output. When the application decides to power on VBUS
+ * using the chosen GPIO, it must also set the port power bit in the host port
* control and status register (PPWR bit in OTG_HS_HPRT).
*
- * "The application uses this field to control power to this port, and the core
+ * "The application uses this field to control power to this port, and the core
* clears this bit on an overcurrent condition."
*
* Input Parameters:
@@ -232,7 +232,7 @@ int stm32_usbhost_initialize(void)
void stm32_usbhost_vbusdrive(int iface, bool enable)
{
DEBUGASSERT(iface == 0);
-
+
if (enable)
{
/* Enable the Power Switch by driving the enable pin low */
@@ -240,9 +240,9 @@ void stm32_usbhost_vbusdrive(int iface, bool enable)
stm32_gpiowrite(GPIO_OTGHS_PWRON, false);
}
else
- {
+ {
/* Disable the Power Switch by driving the enable pin high */
-
+
stm32_gpiowrite(GPIO_OTGHS_PWRON, true);
}
}
diff --git a/nuttx/drivers/sensors/lis331dl.c b/nuttx/drivers/sensors/lis331dl.c
index 346bc03f7..0760a59cd 100644
--- a/nuttx/drivers/sensors/lis331dl.c
+++ b/nuttx/drivers/sensors/lis331dl.c
@@ -34,11 +34,10 @@
*
****************************************************************************/
-/** \file
- * \author Uros Platise
- * \brief ST LIS331DL I2C Device Driver
- **/
-
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
#include <nuttx/config.h>
#include <assert.h>
#include <stdlib.h>
@@ -49,9 +48,10 @@
#include <nuttx/kmalloc.h>
#include <nuttx/sensors/lis331dl.h>
-/************************************************************************************
- * LIS331DL Internal Registers
- ************************************************************************************/
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* LIS331DL Internal Registers **********************************************/
#define ST_LIS331DL_WHOAMI 0x0F /* who am I register */
#define ST_LIS331DL_WHOAMI_VALUE 0x3B /* Valid result is 0x3B */
@@ -84,73 +84,100 @@
#define ST_LIS331DL_OUT_Y 0x2B
#define ST_LIS331DL_OUT_Z 0x2D
-
-/************************************************************************************
+/****************************************************************************
* Private Data Types
- ************************************************************************************/
-
-struct lis331dl_dev_s {
- struct i2c_dev_s * i2c;
-
- uint8_t address;
- struct lis331dl_vector_s a;
- uint8_t cr1;
- uint8_t cr2;
- uint8_t cr3;
+ ****************************************************************************/
+
+struct lis331dl_dev_s
+{
+ struct i2c_dev_s *i2c;
+ uint8_t address;
+ struct lis331dl_vector_s a;
+ uint8_t cr1;
+ uint8_t cr2;
+ uint8_t cr3;
};
-
/****************************************************************************
* Private Functions
****************************************************************************/
-/** LIS331DL Access with range check
- *
- * \param dev LIS331 DL Private Structure
- * \param subaddr LIS331 Sub Address
- * \param buf Pointer to buffer, either for read or write access
- * \param length when >0 it denotes read access, when <0 it denotes write access of -length
- * \return OK on success or errno is set.
- **/
-
-static int lis331dl_access(struct lis331dl_dev_s * dev, uint8_t subaddr,
- uint8_t *buf, int length)
+/****************************************************************************
+ * LIS331DL Access with range check
+ *
+ * Input Parameters:
+ * dev LIS331 DL Private Structure
+ * subaddr LIS331 Sub Address
+ * buf Pointer to buffer, either for read or write access
+ * length When >0 it denotes read access, when <0 it denotes write access
+ * of -length
+ *
+ * Returned Value:
+ * Returns OK on success or errno is set.
+ *
+ ****************************************************************************/
+
+static int lis331dl_access(FAR struct lis331dl_dev_s *dev, uint8_t subaddr,
+ FAR uint8_t *buf, int length)
{
- uint16_t flags = 0;
- int retval;
-
- if (length > 0) {
- flags = I2C_M_READ;
+ uint16_t flags = 0;
+ int retval;
+
+ if (length > 0)
+ {
+ flags = I2C_M_READ;
}
- else {
- flags = I2C_M_NORESTART;
- length = -length;
+ else
+ {
+ flags = I2C_M_NORESTART;
+ length = -length;
}
- /* Check valid address ranges and set auto address increment flag */
-
- if (subaddr == 0x0F) {
- if (length > 1) length = 1;
+ /* Check valid address ranges and set auto address increment flag */
+
+ if (subaddr == 0x0f)
+ {
+ if (length > 1)
+ {
+ length = 1;
+ }
}
- else if (subaddr >= 0x20 && subaddr < 0x24) {
- if (length > (0x24 - subaddr) ) length = 0x24 - subaddr;
+ else if (subaddr >= 0x20 && subaddr < 0x24)
+ {
+ if (length > (0x24 - subaddr))
+ {
+ length = 0x24 - subaddr;
+ }
}
- else if (subaddr >= 0x27 && subaddr < 0x2E) {
- if (length > (0x2E - subaddr) ) length = 0x2E - subaddr;
+ else if (subaddr >= 0x27 && subaddr < 0x2e)
+ {
+ if (length > (0x2e - subaddr))
+ {
+ length = 0x2e - subaddr;
+ }
}
- else if (subaddr >= 0x30 && subaddr < 0x40) {
- if (length > (0x40 - subaddr) ) length = 0x40 - subaddr;
+ else if (subaddr >= 0x30 && subaddr < 0x40)
+ {
+ if (length > (0x40 - subaddr))
+ {
+ length = 0x40 - subaddr;
+ }
}
- else {
- errno = EFAULT;
- return ERROR;
+ else
+ {
+ errno = EFAULT;
+ return ERROR;
+ }
+
+ if (length > 1)
+ {
+ subaddr |= 0x80;
}
- if (length > 1) subaddr |= 0x80;
-
/* Create message and send */
-
- struct i2c_msg_s msgv[2] = {
+
+ struct i2c_msg_s msgv[2] =
+ {
{
.addr = dev->address,
.flags = 0,
@@ -164,159 +191,185 @@ static int lis331dl_access(struct lis331dl_dev_s * dev, uint8_t subaddr,
.length = length
}
};
-
- if ( (retval = I2C_TRANSFER(dev->i2c, msgv, 2)) == OK )
- return length;
-
- return retval;
-}
+ if ((retval = I2C_TRANSFER(dev->i2c, msgv, 2)) == OK)
+ {
+ return length;
+ }
-static int lis331dl_readregs(struct lis331dl_dev_s * dev)
-{
- if (lis331dl_access(dev, ST_LIS331DL_CTRL_REG1, &dev->cr1, 3) != 3) return ERROR;
- return OK;
+ return retval;
}
+static int lis331dl_readregs(FAR struct lis331dl_dev_s *dev)
+{
+ if (lis331dl_access(dev, ST_LIS331DL_CTRL_REG1, &dev->cr1, 3) != 3)
+ {
+ return ERROR;
+ }
+
+ return OK;
+}
/****************************************************************************
* Public Functions
****************************************************************************/
-struct lis331dl_dev_s * lis331dl_init(struct i2c_dev_s * i2c, uint16_t address)
+FAR struct lis331dl_dev_s *lis331dl_init(FAR struct i2c_dev_s *i2c,
+ uint16_t address)
{
- struct lis331dl_dev_s * dev;
- uint8_t retval;
-
- ASSERT(i2c);
- ASSERT(address);
-
- if ( (dev = kmalloc( sizeof(struct lis331dl_dev_s) )) == NULL ) {
- errno = ENOMEM;
- return NULL;
+ FAR struct lis331dl_dev_s * dev;
+ uint8_t retval;
+
+ ASSERT(i2c);
+ ASSERT(address);
+
+ dev = kmalloc(sizeof(struct lis331dl_dev_s));
+ if (dev == NULL)
+ {
+ errno = ENOMEM;
+ return NULL;
}
-
- memset(dev, 0, sizeof(struct lis331dl_dev_s));
- dev->i2c = i2c;
- dev->address = address;
-
- /* Probe device */
-
- if (lis331dl_access(dev, ST_LIS331DL_WHOAMI, &retval, 1) > 0) {
-
- /* Check chip identification, in the future several more compatible parts
- * may be added here.
- */
-
- if (retval == ST_LIS331DL_WHOAMI_VALUE) {
-
- /* Copy LIS331DL registers to our private structure and power-up device */
-
- if (lis331dl_readregs(dev)==OK && lis331dl_powerup(dev)==OK) {
-
- /* Normal exit point */
- errno = 0;
- return dev;
+
+ memset(dev, 0, sizeof(struct lis331dl_dev_s));
+ dev->i2c = i2c;
+ dev->address = address;
+
+ /* Probe device */
+
+ if (lis331dl_access(dev, ST_LIS331DL_WHOAMI, &retval, 1) > 0)
+ {
+ /* Check chip identification, in the future several more compatible parts
+ * may be added here.
+ */
+
+ if (retval == ST_LIS331DL_WHOAMI_VALUE)
+ {
+ /* Copy LIS331DL registers to our private structure and power-up device */
+
+ if (lis331dl_readregs(dev)==OK && lis331dl_powerup(dev) == OK)
+ {
+ /* Normal exit point */
+
+ errno = 0;
+ return dev;
}
- retval = errno;
+
+ retval = errno;
}
-
- /* Otherwise, we mark an invalid device found at given address */
- retval = ENODEV;
+
+ /* Otherwise, we mark an invalid device found at given address */
+
+ retval = ENODEV;
}
- else {
- /* No response at given address is marked as */
- retval = EFAULT;
+ else
+ {
+ /* No response at given address is marked as */
+
+ retval = EFAULT;
}
- /* Error exit */
- kfree(dev);
- errno = retval;
- return NULL;
-}
+ /* Error exit */
+ kfree(dev);
+ errno = retval;
+ return NULL;
+}
-int lis331dl_deinit(struct lis331dl_dev_s * dev)
+int lis331dl_deinit(FAR struct lis331dl_dev_s * dev)
{
- ASSERT(dev);
-
- lis331dl_powerdown(dev);
- kfree(dev);
-
- return OK;
-}
+ ASSERT(dev);
+ lis331dl_powerdown(dev);
+ kfree(dev);
-int lis331dl_powerup(struct lis331dl_dev_s * dev)
-{
- dev->cr1 = ST_LIS331DL_CR1_PD |
- ST_LIS331DL_CR1_ZEN | ST_LIS331DL_CR1_YEN | ST_LIS331DL_CR1_XEN;
- dev->cr2 = 0;
- dev->cr3 = 0;
-
- if (lis331dl_access(dev, ST_LIS331DL_CTRL_REG1, &dev->cr1, -3) == 3) return OK;
- return ERROR;
+ return OK;
}
-
-int lis331dl_powerdown(struct lis331dl_dev_s * dev)
+int lis331dl_powerup(FAR struct lis331dl_dev_s * dev)
{
- dev->cr1 = ST_LIS331DL_CR1_ZEN | ST_LIS331DL_CR1_YEN | ST_LIS331DL_CR1_XEN;
- dev->cr2 = 0;
- dev->cr3 = 0;
-
- if (lis331dl_access(dev, ST_LIS331DL_CTRL_REG1, &dev->cr1, -3) == 3) return OK;
- return ERROR;
-}
+ dev->cr1 = ST_LIS331DL_CR1_PD |
+ ST_LIS331DL_CR1_ZEN | ST_LIS331DL_CR1_YEN | ST_LIS331DL_CR1_XEN;
+ dev->cr2 = 0;
+ dev->cr3 = 0;
+
+ if (lis331dl_access(dev, ST_LIS331DL_CTRL_REG1, &dev->cr1, -3) == 3)
+ {
+ return OK;
+ }
+ return ERROR;
+}
-int lis331dl_setconversion(struct lis331dl_dev_s * dev, bool full, bool fast)
+int lis331dl_powerdown(FAR struct lis331dl_dev_s * dev)
{
- dev->cr1 = ST_LIS331DL_CR1_PD |
- (full ? ST_LIS331DL_CR1_FS : 0) | (fast ? ST_LIS331DL_CR1_DR : 0) |
- ST_LIS331DL_CR1_ZEN | ST_LIS331DL_CR1_YEN | ST_LIS331DL_CR1_XEN;
-
- if (lis331dl_access(dev, ST_LIS331DL_CTRL_REG1, &dev->cr1, -1) == 1) return OK;
- return ERROR;
-}
+ dev->cr1 = ST_LIS331DL_CR1_ZEN | ST_LIS331DL_CR1_YEN | ST_LIS331DL_CR1_XEN;
+ dev->cr2 = 0;
+ dev->cr3 = 0;
+
+ if (lis331dl_access(dev, ST_LIS331DL_CTRL_REG1, &dev->cr1, -3) == 3)
+ {
+ return OK;
+ }
+ return ERROR;
+}
-int lis331dl_getprecision(struct lis331dl_dev_s * dev)
+int lis331dl_setconversion(FAR struct lis331dl_dev_s * dev, bool full, bool fast)
{
- if (dev->cr1 & ST_LIS331DL_CR1_FS)
- return 9200/127; /* typ. 9.2g full scale */
- return 2300/127; /* typ. 2.3g full scale */
+ dev->cr1 = ST_LIS331DL_CR1_PD |
+ (full ? ST_LIS331DL_CR1_FS : 0) | (fast ? ST_LIS331DL_CR1_DR : 0) |
+ ST_LIS331DL_CR1_ZEN | ST_LIS331DL_CR1_YEN | ST_LIS331DL_CR1_XEN;
+
+ if (lis331dl_access(dev, ST_LIS331DL_CTRL_REG1, &dev->cr1, -1) == 1)
+ {
+ return OK;
+ }
+
+ return ERROR;
}
+int lis331dl_getprecision(FAR struct lis331dl_dev_s * dev)
+{
+ if (dev->cr1 & ST_LIS331DL_CR1_FS)
+ {
+ return 9200/127; /* typ. 9.2g full scale */
+ }
-int lis331dl_getsamplerate(struct lis331dl_dev_s * dev)
-{
- if (dev->cr1 & ST_LIS331DL_CR1_DR)
- return 400;
- return 100;
+ return 2300/127; /* typ. 2.3g full scale */
}
+int lis331dl_getsamplerate(FAR struct lis331dl_dev_s * dev)
+{
+ if (dev->cr1 & ST_LIS331DL_CR1_DR)
+ {
+ return 400;
+ }
+
+ return 100;
+}
-const struct lis331dl_vector_s * lis331dl_getreadings(struct lis331dl_dev_s * dev)
+FAR const struct lis331dl_vector_s *
+lis331dl_getreadings(FAR struct lis331dl_dev_s * dev)
{
- uint8_t retval[7];
-
- ASSERT(dev);
-
- if (lis331dl_access(dev, ST_LIS331DL_STATUS_REG, retval, 7) == 7) {
-
- /* If result is not yet ready, return NULL */
-
- if ( !(retval[0] & ST_LIS331DL_SR_ZYXDA) ) {
- errno = EAGAIN;
- return NULL;
+ uint8_t retval[7];
+
+ ASSERT(dev);
+
+ if (lis331dl_access(dev, ST_LIS331DL_STATUS_REG, retval, 7) == 7)
+ {
+ /* If result is not yet ready, return NULL */
+
+ if (!(retval[0] & ST_LIS331DL_SR_ZYXDA))
+ {
+ errno = EAGAIN;
+ return NULL;
}
-
- dev->a.x = retval[2];
- dev->a.y = retval[4];
- dev->a.z = retval[6];
- return &dev->a;
+
+ dev->a.x = retval[2];
+ dev->a.y = retval[4];
+ dev->a.z = retval[6];
+ return &dev->a;
}
-
- return NULL;
+
+ return NULL;
}
diff --git a/nuttx/fs/fs_closeblockdriver.c b/nuttx/fs/fs_closeblockdriver.c
index 2151b04df..5abccd82e 100644
--- a/nuttx/fs/fs_closeblockdriver.c
+++ b/nuttx/fs/fs_closeblockdriver.c
@@ -87,7 +87,7 @@ int close_blockdriver(FAR struct inode *inode)
/* Verify that the inode is a block driver. */
if (!INODE_IS_BLOCK(inode))
- {
+ {
fdbg("inode is not a block driver\n");
ret = -ENOTBLK;
goto errout;
diff --git a/nuttx/fs/fs_findblockdriver.c b/nuttx/fs/fs_findblockdriver.c
index febf28a7e..5c20d46a9 100644
--- a/nuttx/fs/fs_findblockdriver.c
+++ b/nuttx/fs/fs_findblockdriver.c
@@ -105,7 +105,7 @@ int find_blockdriver(FAR const char *pathname, int mountflags, FAR struct inode
/* Verify that the inode is a block driver. */
if (!INODE_IS_BLOCK(inode))
- {
+ {
fdbg("%s is not a block driver\n", pathname);
ret = -ENOTBLK;
goto errout_with_inode;
diff --git a/nuttx/fs/fs_umount.c b/nuttx/fs/fs_umount.c
index 5bf44e4f7..b485e9e68 100644
--- a/nuttx/fs/fs_umount.c
+++ b/nuttx/fs/fs_umount.c
@@ -114,10 +114,10 @@ int umount(const char *target)
/* Verify that the inode is a mountpoint */
if (!INODE_IS_MOUNTPT(mountpt_inode))
- {
+ {
errcode = EINVAL;
goto errout_with_mountpt;
- }
+ }
/* Unbind the block driver from the file system (destroying any fs
* private data.
diff --git a/nuttx/libc/sched/sched_getprioritymin.c b/nuttx/libc/sched/sched_getprioritymin.c
index dbb46d81e..b5156f4df 100644
--- a/nuttx/libc/sched/sched_getprioritymin.c
+++ b/nuttx/libc/sched/sched_getprioritymin.c
@@ -88,7 +88,7 @@
************************************************************************/
int sched_get_priority_min(int policy)
-{
+{
if (policy != SCHED_FIFO && policy != SCHED_RR)
{
return ERROR;
diff --git a/nuttx/libnx/nxtk/nxtk_drawlinetoolbar.c b/nuttx/libnx/nxtk/nxtk_drawlinetoolbar.c
index 6a975536a..2bcb8b890 100644
--- a/nuttx/libnx/nxtk/nxtk_drawlinetoolbar.c
+++ b/nuttx/libnx/nxtk/nxtk_drawlinetoolbar.c
@@ -94,7 +94,7 @@
int nxtk_drawlinetoolbar(NXTKWINDOW hfwnd, FAR struct nxgl_vector_s *vector,
nxgl_coord_t width, nxgl_mxpixel_t color[CONFIG_NX_NPLANES])
-{
+{
struct nxgl_trapezoid_s trap[3];
struct nxgl_rect_s rect;
int ret;
diff --git a/nuttx/libnx/nxtk/nxtk_drawlinewindow.c b/nuttx/libnx/nxtk/nxtk_drawlinewindow.c
index ba45a2dc8..176f60b82 100644
--- a/nuttx/libnx/nxtk/nxtk_drawlinewindow.c
+++ b/nuttx/libnx/nxtk/nxtk_drawlinewindow.c
@@ -93,7 +93,7 @@
int nxtk_drawlinewindow(NXTKWINDOW hfwnd, FAR struct nxgl_vector_s *vector,
nxgl_coord_t width, nxgl_mxpixel_t color[CONFIG_NX_NPLANES])
-{
+{
struct nxgl_trapezoid_s trap[3];
struct nxgl_rect_s rect;
int ret;
diff --git a/nuttx/tools/mkfsdata.pl b/nuttx/tools/mkfsdata.pl
index 589ad5f08..073e69775 100755
--- a/nuttx/tools/mkfsdata.pl
+++ b/nuttx/tools/mkfsdata.pl
@@ -44,8 +44,8 @@ closedir(DIR);
print(OUTPUT "#include <apps/netutils/httpd.h>\n\n");
print(OUTPUT "#ifndef NULL\n#define NULL 0\n#endif\n\n");
-foreach $file (@files) {
-
+foreach $file (@files) {
+
if(-d $file && $file !~ /^\./) {
print "Processing directory $file\n";
opendir(DIR, $file);
@@ -75,8 +75,8 @@ foreach $file (@files) {
printf(OUTPUT "%#02x, ", unpack("C", substr($file, $j, 1)));
}
printf(OUTPUT "0x00,\n ");
-
- $i = 0;
+
+ $i = 0;
while(read(FILE, $data, 1)) {
printf(OUTPUT "%#02x, ", unpack("C", $data));
$i++;