Skip to content

Commit

Permalink
cxd56xx improvements (#48)
Browse files Browse the repository at this point in the history
* arch: cxd56xx: Add size limitation for I2C SCU xfer

This is a fw restriction, unroll loop because it can be transfer
up to 16 bytes.

* arch: cxd56xx: Fix lack of leave_critical_section

add the missing leave_critical_section

* arch: cxd56xx: Remove unnecessary file

this header is duplicate and we can remove it

* arch: cxd56xx: Cosmetic change

remove space after function

* arch: cxd56xx: update topreg registers

the topreg registers are updated to match the cxd5602 HW

* arch: cxd56xx: Add voltage setting for low battery notification

Add voltage setting for low battery notification

* arch: cxd56xx: Improve perfomance of SD card

Improve a problem that the clock of SD Host Controller is lower than the
expected value in SDR25 transfer mode.

* arch: cxd56xx: Cosmetic changes

cleanup to comply with coding standard

* boards: cxd56xx: Cosmetic changes

updates to comply with coding standard

* boards: cxd56xx: Fix SD card cannot mount issue

SD card cannot mount when connecting and disconnecting three times
or more due to wrong state of parameter 'initialized'.

This change enables to skip swtching initialized state when mount
failed.
  • Loading branch information
jerpelea authored and acassis committed Jan 7, 2020
1 parent c5090d3 commit 077ef70
Show file tree
Hide file tree
Showing 92 changed files with 685 additions and 746 deletions.
6 changes: 3 additions & 3 deletions arch/arm/include/cxd56xx/adc.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
*
****************************************************************************/

#ifndef __ARCH_ARM_INCLUDE_CXD56XX_CXD56_ADC_H
#define __ARCH_ARM_INCLUDE_CXD56XX_CXD56_ADC_H
#ifndef __ARCH_ARM_INCLUDE_CXD56XX_ADC_H
#define __ARCH_ARM_INCLUDE_CXD56XX_ADC_H

/****************************************************************************
* include files
Expand Down Expand Up @@ -93,4 +93,4 @@

int cxd56_adcinitialize(void);

#endif /* __ARCH_ARM_INCLUDE_CXD56XX_CXD56_ADC_H */
#endif /* __ARCH_ARM_INCLUDE_CXD56XX_ADC_H */
6 changes: 3 additions & 3 deletions arch/arm/include/cxd56xx/audio.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@

/* audioutils Audio Utility */

#ifndef __ARCH_ARM_INCLUDE_CXD56XX_CXD56_AUDIO_H
#define __ARCH_ARM_INCLUDE_CXD56XX_CXD56_AUDIO_H
#ifndef __ARCH_ARM_INCLUDE_CXD56XX_AUDIO_H
#define __ARCH_ARM_INCLUDE_CXD56XX_AUDIO_H

/* API Documents creater with Doxgen */

Expand Down Expand Up @@ -948,4 +948,4 @@ bool board_audio_tone_generator(bool en, int16_t vol, uint16_t freq);
} /* end of extern "C" */
#endif /* __cplusplus */

#endif /* __ARCH_ARM_INCLUDE_CXD56XX_CXD56_AUDIO_H */
#endif /* __ARCH_ARM_INCLUDE_CXD56XX_AUDIO_H */
2 changes: 1 addition & 1 deletion arch/arm/include/cxd56xx/battery_ioctl.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/****************************************************************************
* include/arch/chip/battery_ioctl.h
* arch/arm/include/cxd56xx/battery_ioctl.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
Expand Down
2 changes: 1 addition & 1 deletion arch/arm/include/cxd56xx/ge2d.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/include/cxd56xx/cxd56_ge2d.h
* arch/arm/include/cxd56xx/ge2d.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
Expand Down
2 changes: 1 addition & 1 deletion arch/arm/include/cxd56xx/geofence.h
Original file line number Diff line number Diff line change
Expand Up @@ -230,4 +230,4 @@ struct cxd56_geofence_status_s
}
#endif

#endif /* __ARCH_ARM_INCLUDE_ARCH_CXD56XX_GEOFENCE_H */
#endif /* __ARCH_ARM_INCLUDE_CXD56XX_GEOFENCE_H */
2 changes: 1 addition & 1 deletion arch/arm/include/cxd56xx/gnss.h
Original file line number Diff line number Diff line change
Expand Up @@ -866,4 +866,4 @@ struct cxd56_gnss_get_var_ephemeris_s
}
#endif

#endif /* ARCH_ARM_INCLUDE_CXD56XX_GNSS_H */
#endif /* __ARCH_ARM_INCLUDE_CXD56XX_GNSS_H */
2 changes: 1 addition & 1 deletion arch/arm/include/cxd56xx/gnss_type.h
Original file line number Diff line number Diff line change
Expand Up @@ -707,4 +707,4 @@ struct cxd56_gnss_status_s
}
#endif /* __cplusplus */

#endif /* ARCH_ARM_INCLUDE_CXD56XX_GNSS_TYPE_H */
#endif /* __ARCH_ARM_INCLUDE_CXD56XX_GNSS_TYPE_H */
6 changes: 3 additions & 3 deletions arch/arm/include/cxd56xx/uart0.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/include/cxd56xx/cxd56_uart0.h
* arch/arm/include/cxd56xx/uart0.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
Expand Down Expand Up @@ -33,8 +33,8 @@
*
****************************************************************************/

#ifndef __ARM_ARCH_INCLUDE_CXD56XX_CXD56_UART0_H
#define __ARM_ARCH_INCLUDE_CXD56XX_CXD56_UART0_H
#ifndef __ARM_ARCH_INCLUDE_CXD56XX_UART0_H
#define __ARM_ARCH_INCLUDE_CXD56XX_UART0_H

/****************************************************************************
* Public Types
Expand Down
2 changes: 1 addition & 1 deletion arch/arm/src/cxd56xx/cxd56_cisif.c
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,7 @@ static void cisif_ycc_nstorage_int(uint8_t code)
uint32_t size;

size = cisif_reg_read(CISIF_YCC_DSTRG_CONT);
g_ycc_notify_callback_func (0, size, g_storage_addr);
g_ycc_notify_callback_func(0, size, g_storage_addr);
cisif_reg_write(CISIF_YCC_DREAD_CONT, size);
}

Expand Down
1 change: 1 addition & 0 deletions arch/arm/src/cxd56xx/cxd56_cpufifo.c
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,7 @@ int cxd56_cfpush(uint32_t data[2])
if (!sq_empty(&g_pushqueue))
{
ret = cpufifo_reserve(data);
leave_critical_section(flags);
return ret;
}

Expand Down
2 changes: 1 addition & 1 deletion arch/arm/src/cxd56xx/cxd56_dmac.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

#include <stdint.h>

#include "hardware/cxd56_dmac_common.h"
#include "cxd56_dmac_common.h"

/****************************************************************************
* Pre-processor Definitions
Expand Down
53 changes: 24 additions & 29 deletions arch/arm/src/cxd56xx/cxd56_i2c.c
Original file line number Diff line number Diff line change
Expand Up @@ -738,40 +738,35 @@ static int cxd56_i2c_scurecv(int port, int addr, uint8_t *buf, ssize_t buflen)
{
return OK;
}

rem = buflen;
while (rem)
if (buflen > 16)
{
len0 = rem > 8 ? 8 : rem;
rem -= len0;
len1 = rem > 8 ? 8 : rem;
rem -= len1;
return -EINVAL;
}

inst[0] = SCU_INST_RECV(len0);
if (len1)
{
inst[1] = SCU_INST_RECV(len1);
instn = 2;
}
else
{
instn = 1;
}
rem = buflen;
len0 = rem > 8 ? 8 : rem;
rem -= len0;
len1 = rem > 8 ? 8 : rem;
rem -= len1;

if (rem == 0)
{
inst[instn - 1] |= SCU_INST_LAST;
}
inst[0] = SCU_INST_RECV(len0);
if (len1)
{
inst[1] = SCU_INST_RECV(len1);
instn = 2;
}
else
{
instn = 1;
}

ret = scu_i2ctransfer(port, addr, inst, instn, buf, len0 + len1);
if (ret < 0)
{
syslog(LOG_ERR, "I2C receive failed. port %d addr %d\n",
port, addr);
break;
}
inst[instn - 1] |= SCU_INST_LAST;

buf += len0 + len1;
ret = scu_i2ctransfer(port, addr, inst, instn, buf, buflen);
if (ret < 0)
{
syslog(LOG_ERR, "I2C receive failed. port %d addr %d\n",
port, addr);
}

return ret;
Expand Down
2 changes: 1 addition & 1 deletion arch/arm/src/cxd56xx/cxd56_idle.c
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/cxd56/cxd56_idle.c
* arch/arm/src/cxd56xx/cxd56_idle.c
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
Expand Down
2 changes: 1 addition & 1 deletion arch/arm/src/cxd56xx/cxd56_irq.c
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/cxd56/cxd56_irq.c
* arch/arm/src/cxd56xx/cxd56_irq.c
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
Expand Down
61 changes: 59 additions & 2 deletions arch/arm/src/cxd56xx/cxd56_pmic.c
Original file line number Diff line number Diff line change
Expand Up @@ -748,9 +748,66 @@ int cxd56_pmic_get_gauge(FAR struct pmic_gauge_s *gauge)
*
****************************************************************************/

int cxd56_pmic_getlowervol(FAR int *vol)
int cxd56_pmic_getlowervol(FAR int *voltage)
{
return PM_PmicControl(PMIC_CMD_GETVSYS, vol);
return PM_PmicControl(PMIC_CMD_GETVSYS, voltage);
}

/****************************************************************************
* Name: cxd56_pmic_setlowervol
*
* Description:
* Set lower limit of voltage for system to be running.
*
* Input Parameter:
* voltage - Lower limit voltage (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/

int cxd56_pmic_setlowervol(int voltage)
{
return PM_PmicControl(PMIC_CMD_SETVSYS, (void *)voltage);
}

/****************************************************************************
* Name: cxd56_pmic_getnotifyvol
*
* Description:
* Get voltage for the low battery notification
*
* Input Parameter:
* voltage - Low battery voltage (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/

int cxd56_pmic_getnotifyvol(FAR int *voltage)
{
return PM_PmicControl(PMIC_CMD_GETPREVSYS, voltage);
}

/****************************************************************************
* Name: cxd56_pmic_setnotifyvol
*
* Description:
* Set voltage for the low battery notification
*
* Input Parameter:
* voltage - Low battery voltage (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/

int cxd56_pmic_setnotifyvol(int voltage)
{
return PM_PmicControl(PMIC_CMD_SETPREVSYS, (void *)voltage);
}

/****************************************************************************
Expand Down
50 changes: 49 additions & 1 deletion arch/arm/src/cxd56xx/cxd56_pmic.h
Original file line number Diff line number Diff line change
Expand Up @@ -457,7 +457,55 @@ int cxd56_pmic_get_gauge(FAR struct pmic_gauge_s *gauge);
*
****************************************************************************/

int cxd56_pmic_getlowervol(FAR int *vol);
int cxd56_pmic_getlowervol(FAR int *voltage);

/****************************************************************************
* Name: cxd56_pmic_setlowervol
*
* Description:
* Set lower limit of voltage for system to be running.
*
* Input Parameter:
* voltage - Lower limit voltage (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/

int cxd56_pmic_setlowervol(int voltage);

/****************************************************************************
* Name: cxd56_pmic_getnotifyvol
*
* Description:
* Get voltage for the low battery notification
*
* Input Parameter:
* voltage - Low battery voltage (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/

int cxd56_pmic_getnotifyvol(FAR int *voltage);

/****************************************************************************
* Name: cxd56_pmic_setnotifyvol
*
* Description:
* Set voltage for the low battery notification
*
* Input Parameter:
* voltage - Low battery voltage (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/

int cxd56_pmic_setnotifyvol(int voltage);

/****************************************************************************
* Name: cxd56_pmic_getchargevol
Expand Down
7 changes: 1 addition & 6 deletions arch/arm/src/cxd56xx/cxd56_sdhci.c
Original file line number Diff line number Diff line change
Expand Up @@ -119,13 +119,8 @@
# define CONFIG_CXD56_SD1BIT_FREQ 20000000 /* 20MHz SD 1-bit, normal clocking */
#endif
#ifndef CONFIG_CXD56_SD4BIT_FREQ
# define CONFIG_CXD56_SD4BIT_FREQ 25000000 /* 25MHz SD 4-bit, normal clocking */
# define CONFIG_CXD56_SD4BIT_FREQ 50000000 /* SDR25 SD 4-bit, normal clocking */
#endif
#ifndef CONFIG_CXD56_HSSD4BIT_FREQ
# define CONFIG_CXD56_HSSD4BIT_FREQ 50000000 /* 50MHz SD 4-bit, highspeed clocking */
#endif

#define CXD56_SDIO_BASECLK_FREQ (cxd56_get_sdio_baseclock()*2)

/* Timing */

Expand Down
4 changes: 2 additions & 2 deletions arch/arm/src/cxd56xx/cxd56_usbdev.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
*
****************************************************************************/

#ifndef __ARCH_ARM_SRC_CXD56XX_CXD56_USB_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_USB_H
#ifndef __ARCH_ARM_SRC_CXD56XX_CXD56_USBDEV_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_USBDEV_H

/****************************************************************************
* Included Files
Expand Down
6 changes: 3 additions & 3 deletions arch/arm/src/cxd56xx/hardware/cxd5602_backupmem.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
*
****************************************************************************/

#ifndef __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_BACKUPMEM_H
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_BACKUPMEM_H
#ifndef __ARCH_ARM_SRC_CXD56XX_HARDWARE_CXD5602_BACKUPMEM_H
#define __ARCH_ARM_SRC_CXD56XX_HARDWARE_CXD5602_BACKUPMEM_H

/********************************************************************************************
* Included Files
Expand Down Expand Up @@ -84,4 +84,4 @@ typedef struct {
* Public Functions
********************************************************************************************/

#endif /* __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_BACKUPMEM_H */
#endif /* __ARCH_ARM_SRC_CXD56XX_HARDWARE_CXD5602_BACKUPMEM_H */
6 changes: 3 additions & 3 deletions arch/arm/src/cxd56xx/hardware/cxd5602_pinconfig.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
*
****************************************************************************/

#ifndef __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_PINCONFIG_H
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_PINCONFIG_H
#ifndef __ARCH_ARM_SRC_CXD56XX_HARDWARE_CXD5602_PINCONFIG_H
#define __ARCH_ARM_SRC_CXD56XX_HARDWARE_CXD5602_PINCONFIG_H

/********************************************************************************************
* Included Files
Expand Down Expand Up @@ -656,4 +656,4 @@

#endif /* CONFIG_CXD56_CUSTOM_PINCONFIG */

#endif /* __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_PINCONFIG_H */
#endif /* __ARCH_ARM_SRC_CXD56XX_HARDWARE_CXD5602_PINCONFIG_H */
Loading

0 comments on commit 077ef70

Please sign in to comment.