Skip to content

Commit

Permalink
Squashed commit of the following:
Browse files Browse the repository at this point in the history
Author: Alan Carvalho de Assis <[email protected]>

    Run all .h and .c files modified in last PR through nxstyle.

Author: Xiang Xiao <[email protected]>

    Fix stm32l4_otgfshost.c: error: 'ret' undeclared (#32)

    result by commit 6a3c2ad

    Change-Id: I68ba79417d8da102da8d91c74496961aef242dd9
    Signed-off-by: Xiang Xiao <[email protected]>
  • Loading branch information
xiaoxiang781216 authored and acassis committed Jan 3, 2020
1 parent 9b2fa81 commit d612fd3
Show file tree
Hide file tree
Showing 6 changed files with 78 additions and 56 deletions.
10 changes: 8 additions & 2 deletions arch/arm/src/lc823450/lc823450_usbdev.c
Original file line number Diff line number Diff line change
Expand Up @@ -917,6 +917,7 @@ int lc823450_usbpullup(struct usbdev_s *dev, bool enable)
{
modifyreg32(USB_DEVC, 0 , USB_DEVC_DISCON);
}

return 0;
}

Expand Down Expand Up @@ -956,6 +957,7 @@ static void usb_suspend_work_func(void *arg)
g_usbsuspend = 1;
wake_unlock(&priv->wlock);
}

spin_unlock_irqrestore(flags);
}
#endif
Expand Down Expand Up @@ -1151,7 +1153,6 @@ static void subintr_ep0(void)
case USB_REQ_RECIPIENT_INTERFACE:
resp[0] = 0; /* reserved */
break;

}

epbuf_write(0, &resp, 2);
Expand Down Expand Up @@ -1242,6 +1243,7 @@ static void subintr_ep0(void)
{
break;
}

up_udelay(10);
}
while (tout--);
Expand Down Expand Up @@ -1290,6 +1292,7 @@ static void subintr_epin(uint8_t epnum, struct lc823450_ep_s *privep)
req = &container_of(q_ent, struct lc823450_req_s, q_ent)->req;

/* Write to TX FIFO */

/* int clear!! before epbuf write */

epcmd_write(epnum, USB_EPCMD_EMPTY_CLR);
Expand Down Expand Up @@ -1925,7 +1928,7 @@ int usbdev_msc_epread(void *buf, int len)
CONFIG_USBMSC_EPBULKOUT << USB_DMAC_DMAEP_SHIFT |
USB_DMAC_START,
USB_DMAC1);
nxsem_wait(&dma_wait);
nxsem_wait(&dma_wait);

return 0;
}
Expand All @@ -1944,6 +1947,7 @@ void usbdev_msc_stop(void)
* return value : 0 : charger was not detected.
* !0 : charger was detected.
****************************************************************************/

int usbdev_is_usbcharger(void)
{
return g_usbdev.charger;
Expand Down Expand Up @@ -1971,11 +1975,13 @@ static void usbdev_pmnotify(struct pm_callback_s *cb, enum pm_state_e pmstate)
{
CLASS_RESUME(g_usbdev.driver, &g_usbdev.usbdev);
}

break;

default:
break;
}

spin_unlock_irqrestore(flags);
}
#endif
7 changes: 3 additions & 4 deletions arch/arm/src/sama5/sam_tsd.c
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,9 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/

/* Driver support ***********************************************************/

/* This format is used to construct the /dev/input[n] device driver path. It
* defined here so that it will be used consistently in all places.
*/
Expand Down Expand Up @@ -378,10 +380,6 @@ static int sam_tsd_waitsample(struct sam_tsd_s *priv, struct sam_sample_s *sampl

if (ret < 0)
{
/* If we are awakened by a signal, then we need to return
* the failure now.
*/

ierr("ERROR: nxsem_wait: %d\n", ret);
goto errout;
}
Expand Down Expand Up @@ -752,6 +750,7 @@ static void sam_tsd_bottomhalf(void *arg)
/* Exit, re-enabling touchscreen interrupts */

ignored:

/* Re-enable touchscreen interrupts as appropriate. */

sam_adc_putreg(priv->adc, SAM_ADC_IER, ier);
Expand Down
63 changes: 39 additions & 24 deletions arch/arm/src/stm32/stm32_adc.c
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,7 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/

/* RCC reset ****************************************************************/

#if defined(HAVE_IP_ADC_V1)
Expand Down Expand Up @@ -198,6 +199,7 @@
#endif

/* ADC Channels/DMA ********************************************************/

/* The maximum number of channels that can be sampled. If DMA support is
* not enabled, then only a single channel can be sampled. Otherwise,
* data overruns would occur.
Expand Down Expand Up @@ -1169,7 +1171,7 @@ static uint32_t adccmn_getreg(FAR struct stm32_dev_s *priv, uint32_t offset)

/* Return register value */

return getreg32(base+offset);
return getreg32(base + offset);
}
# endif
#endif /* HAVE_ADC_CMN_REGS */
Expand Down Expand Up @@ -1457,7 +1459,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)

/* Set the reload and prescaler values */

tim_putreg(priv, STM32_GTIM_PSC_OFFSET, prescaler-1);
tim_putreg(priv, STM32_GTIM_PSC_OFFSET, prescaler - 1);
tim_putreg(priv, STM32_GTIM_ARR_OFFSET, reload);

/* Clear the advanced timers repetition counter in TIM1 */
Expand Down Expand Up @@ -1564,6 +1566,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
case 4: /* TimerX TRGO event */
{
/* TODO: TRGO support not yet implemented */

/* Set the event TRGO */

ccenable = 0;
Expand Down Expand Up @@ -1645,7 +1648,8 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
# if defined(HAVE_GTIM_CCXNP)
else
{
ccer &= ~(GTIM_CCER_CC1NP | GTIM_CCER_CC2NP | GTIM_CCER_CC3NP | GTIM_CCER_CC4NP);
ccer &= ~(GTIM_CCER_CC1NP | GTIM_CCER_CC2NP | GTIM_CCER_CC3NP |
GTIM_CCER_CC4NP);
}
# endif

Expand Down Expand Up @@ -1775,7 +1779,6 @@ static void adc_reg_startconv(FAR struct stm32_dev_s *priv, bool enable)
}
#endif


#ifdef ADC_HAVE_INJECTED

/****************************************************************************
Expand Down Expand Up @@ -1854,15 +1857,15 @@ static void adc_inj_startconv(FAR struct stm32_dev_s *priv, bool enable)
#ifdef HAVE_ADC_CMN_DATA
static int adccmn_lock(FAR struct stm32_dev_s *priv, bool lock)
{
int ret = OK;
int ret;

if (lock)
{
ret = nxsem_wait_uninterruptible(&priv->cmn->lock);
}
else
{
nxsem_post(&priv->cmn->lock);
ret = nxsem_post(&priv->cmn->lock);
}

return ret;
Expand Down Expand Up @@ -1902,27 +1905,31 @@ static void adc_rccreset(FAR struct stm32_dev_s *priv, bool reset)
adcbit = RCC_RSTR_ADC1RST;
break;
}

#endif
#ifdef CONFIG_STM32_ADC2
case 2:
{
adcbit = RCC_RSTR_ADC2RST;
break;
}

#endif
#ifdef CONFIG_STM32_ADC3
case 3:
{
adcbit = RCC_RSTR_ADC3RST;
break;
}

#endif
#ifdef CONFIG_STM32_ADC4
case 4:
{
adcbit = RCC_RSTR_ADC4RST;
break;
}

#endif
default:
{
Expand Down Expand Up @@ -2003,6 +2010,7 @@ static void adc_rccreset(FAR struct stm32_dev_s *priv, bool reset)
adcbit = RCC_RSTR_ADC12RST;
break;
}

#endif
#if defined(CONFIG_STM32_ADC3) || defined(CONFIG_STM32_ADC4)
case 3:
Expand All @@ -2011,6 +2019,7 @@ static void adc_rccreset(FAR struct stm32_dev_s *priv, bool reset)
adcbit = RCC_RSTR_ADC34RST;
break;
}

#endif
default:
{
Expand Down Expand Up @@ -2664,29 +2673,29 @@ static void adc_dma_cfg(FAR struct stm32_dev_s *priv)
uint32_t setbits = 0;

#ifdef ADC_HAVE_DMACFG
/* Set DMA mode */
/* Set DMA mode */

if (priv->dmacfg == 0)
{
/* One Shot Mode */
if (priv->dmacfg == 0)
{
/* One Shot Mode */

clrbits |= ADC_CR2_DDS;
}
else
{
/* Circular Mode */
clrbits |= ADC_CR2_DDS;
}
else
{
/* Circular Mode */

setbits |= ADC_CR2_DDS;
}
setbits |= ADC_CR2_DDS;
}
#endif

/* Enable DMA */
/* Enable DMA */

setbits |= ADC_CR2_DMA;
setbits |= ADC_CR2_DMA;

/* Modify CR2 configuration */
/* Modify CR2 configuration */

adc_modifyreg(priv, STM32_ADC_CR2_OFFSET, clrbits, setbits);
adc_modifyreg(priv, STM32_ADC_CR2_OFFSET, clrbits, setbits);
}
#endif

Expand Down Expand Up @@ -4320,14 +4329,15 @@ static uint32_t adc_injget(FAR struct stm32_adc_dev_s *dev, uint8_t chan)
FAR struct stm32_dev_s *priv = (FAR struct stm32_dev_s *)dev;
uint32_t regval = 0;

if (chan > priv->cj_channels-1)
if (chan > (priv->cj_channels - 1))
{
/* REVISIT: return valute with MSB set to indicate error ? */

goto errout;
}

regval = adc_getreg(priv, STM32_ADC_JDR1_OFFSET+4*(chan)) & ADC_JDR_JDATA_MASK;
regval = adc_getreg(priv, STM32_ADC_JDR1_OFFSET + 4 * (chan)) &
ADC_JDR_JDATA_MASK;

errout:
return regval;
Expand Down Expand Up @@ -4466,7 +4476,8 @@ void adc_sampletime_set(FAR struct stm32_adc_dev_s *dev,
uint8_t i;

/* Check if user wants to assign the same value for all channels
* or just wants to change sample time values for certain channels */
* or just wants to change sample time values for certain channels
*/

if (time_samples->all_same)
{
Expand Down Expand Up @@ -4582,6 +4593,7 @@ struct adc_dev_s *stm32_adcinitialize(int intf, FAR const uint8_t *chanlist,
# endif
break;
}

#endif /* CONFIG_STM32_ADC1 */
#ifdef CONFIG_STM32_ADC2
case 2:
Expand All @@ -4598,6 +4610,7 @@ struct adc_dev_s *stm32_adcinitialize(int intf, FAR const uint8_t *chanlist,
# endif
break;
}

#endif /* CONFIG_STM32_ADC2 */
#ifdef CONFIG_STM32_ADC3
case 3:
Expand All @@ -4614,6 +4627,7 @@ struct adc_dev_s *stm32_adcinitialize(int intf, FAR const uint8_t *chanlist,
# endif
break;
}

#endif /* CONFIG_STM32_ADC3 */
#ifdef CONFIG_STM32_ADC4
case 4:
Expand All @@ -4630,6 +4644,7 @@ struct adc_dev_s *stm32_adcinitialize(int intf, FAR const uint8_t *chanlist,
# endif
break;
}

#endif /* CONFIG_STM32_ADC4 */
default:
{
Expand Down
6 changes: 6 additions & 0 deletions arch/arm/src/stm32l4/stm32l4_otgfshost.c
Original file line number Diff line number Diff line change
Expand Up @@ -1079,6 +1079,7 @@ static int stm32l4_chan_wait(FAR struct stm32l4_usbhost_s *priv,
FAR struct stm32l4_chan_s *chan)
{
irqstate_t flags;
int ret;

/* Disable interrupts so that the following operations will be atomic. On
* the OTG FS global interrupt needs to be disabled. However, here we disable
Expand Down Expand Up @@ -4235,6 +4236,7 @@ static int stm32l4_epfree(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep)
* - Never called from an interrupt handler.
*
****************************************************************************/

#warning this function name is too generic
static int stm32l4_alloc(FAR struct usbhost_driver_s *drvr,
FAR uint8_t **buffer, FAR size_t *maxlen)
Expand Down Expand Up @@ -4280,6 +4282,7 @@ static int stm32l4_alloc(FAR struct usbhost_driver_s *drvr,
* - Never called from an interrupt handler.
*
****************************************************************************/

#warning this function name is too generic
static int stm32l4_free(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer)
{
Expand Down Expand Up @@ -4316,6 +4319,7 @@ static int stm32l4_free(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer)
* This function will *not* be called from an interrupt handler.
*
************************************************************************************/

#warning this function name is too generic
static int stm32l4_ioalloc(FAR struct usbhost_driver_s *drvr,
FAR uint8_t **buffer, size_t buflen)
Expand Down Expand Up @@ -4360,6 +4364,7 @@ static int stm32l4_ioalloc(FAR struct usbhost_driver_s *drvr,
* This function will *not* be called from an interrupt handler.
*
************************************************************************************/

#warning this function name is too generic
static int stm32l4_iofree(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer)
{
Expand Down Expand Up @@ -4884,6 +4889,7 @@ static void stm32l4_disconnect(FAR struct usbhost_driver_s *drvr,
/****************************************************************************
* Initialization
****************************************************************************/

/****************************************************************************
* Name: stm32l4_portreset
*
Expand Down
Loading

0 comments on commit d612fd3

Please sign in to comment.