Merged in masayuki2009/nuttx.nuttx/lc823450_dvfs (pull request #566)

lc823450 dvfs

Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
Masayuki Ishikawa 2018-01-10 12:50:22 +00:00 committed by Gregory Nutt
commit 70c7e04686
14 changed files with 933 additions and 25 deletions

View File

@ -246,5 +246,8 @@ config HRT_TIMER
bool "High resolution timer"
default n
config DVFS
bool "Dynamic Voltage and Frequencey Scaling"
default n
endmenu

View File

@ -146,7 +146,8 @@ endif
endif
ifeq ($(CONFIG_DVFS),y)
CHIP_CSRCS += lc823450_dvfs.c
CHIP_CSRCS += lc823450_dvfs2.c
CHIP_CSRCS += lc823450_procfs_dvfs.c
endif
ifeq ($(CONFIG_PM),y)

View File

@ -0,0 +1,429 @@
/****************************************************************************
* arch/arm/src/lc823450/lc823450_dvfs2.c
*
* Copyright (C) 2015-2017 Sony Corporation. All rights reserved.
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
* Author: Masatoshi Tateishi <Masatoshi.Tateishi@jp.sony.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <nuttx/clock.h>
#include <arch/board/board.h>
#include <string.h>
#include "up_arch.h"
#include "lc823450_clockconfig.h"
#include "lc823450_syscontrol.h"
#include "lc823450_intc.h"
#include "lc823450_sdc.h"
#include "lc823450_dvfs2.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define FREQ_160 0
#define FREQ_080 1
#define FREQ_040 2
/****************************************************************************
* Private Data
****************************************************************************/
typedef struct freq_entry
{
uint16_t freq;
uint16_t pll1;
uint16_t mdiv;
uint16_t hdiv;
} t_freq_entry;
static struct freq_entry _dvfs_act_tbl[3] =
{
{ 160, OSCCNT_MCSEL, OSCCNT_MAINDIV_1, 3}, /* PLL1 */
{ 80, OSCCNT_MCSEL, OSCCNT_MAINDIV_2, 1}, /* PLL1 */
{ 40, OSCCNT_MCSEL, OSCCNT_MAINDIV_4, 0}, /* PLL1 */
};
static struct freq_entry _dvfs_idl_tbl[3] =
{
{ 24, 0, OSCCNT_MAINDIV_1, 0}, /* XT1 */
{ 12, 0, OSCCNT_MAINDIV_2, 0}, /* XT1 */
{ 6, 0, OSCCNT_MAINDIV_4, 0}, /* XT1 */
};
static uint16_t _dvfs_cur_idx = 0; /* current speed index */
static uint16_t _dvfs_cur_hdiv = 3;
static uint16_t _dvfs_cur_mdiv = OSCCNT_MAINDIV_1;
#if 0
static uint16_t _dvfs_init_timeout = (5 * 100); /* in ticks */
#endif
#if defined(CONFIG_SMP) && (CONFIG_SMP_NCPUS == 2)
static uint8_t _dvfs_cpu_is_active[CONFIG_SMP_NCPUS];
#endif
static void lc823450_dvfs_set_div(int idx, int tbl);
/****************************************************************************
* Public Data
****************************************************************************/
int8_t g_dvfs_enabled = 0;
uint16_t g_dvfs_cur_freq = 160;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: lc823450_dvfs_update_lpm
****************************************************************************/
static void lc823450_dvfs_update_lpm(int freq)
{
/* TODO */
}
#if defined(CONFIG_SMP) && (CONFIG_SMP_NCPUS == 2)
static int _dvfs_another_cpu_state(int me)
{
if (0 == me)
{
return _dvfs_cpu_is_active[1];
}
else
{
return _dvfs_cpu_is_active[0];
}
}
#endif
/****************************************************************************
* Name: lc823450_dvfs_set_div
* Set dividers in the OSC block
* target tbl: 0=active, 1=idle
****************************************************************************/
static void lc823450_dvfs_set_div(int idx, int tbl)
{
uint32_t target;
uint32_t t_hdiv;
uint32_t t_mdiv;
if (0 == tbl)
{
target = _dvfs_act_tbl[idx].freq;
t_hdiv = _dvfs_act_tbl[idx].hdiv;
t_mdiv = _dvfs_act_tbl[idx].mdiv;
}
else
{
target = _dvfs_idl_tbl[idx].freq;
t_hdiv = _dvfs_idl_tbl[idx].hdiv;
t_mdiv = _dvfs_idl_tbl[idx].mdiv;
}
if (100 < target)
{
/* Set ROM wait cycle (CPU=1wait) */
modifyreg32(MEMEN4, 0, MEMEN4_HWAIT);
}
/* adjust AHB */
if (t_hdiv > _dvfs_cur_hdiv)
{
uint32_t pclkdiv = t_hdiv;
#ifdef CONFIG_LC823450_SDRAM
pclkdiv += (t_hdiv << 16);
#endif
putreg32(pclkdiv, PERICLKDIV);
}
uint32_t regval = getreg32(OSCCNT);
/* NOTE: In LC823450, MCSEL is reflected first then MAINDIV */
/* To avoid spec violation, 2-step clock change is needed */
/* step 1 : change MAINDIV if needed */
if (t_mdiv > _dvfs_cur_mdiv)
{
regval &= ~OSCCNT_MAINDIV_MASK;
regval |= t_mdiv;
/* change the MAINDIV first */
putreg32(regval, OSCCNT);
}
/* step 2 : change MCSEL and MAINDIV */
regval = getreg32(OSCCNT);
regval &= ~(OSCCNT_MCSEL | OSCCNT_MAINDIV_MASK);
if (0 == tbl)
{
regval |= _dvfs_act_tbl[idx].pll1;
}
else
{
regval |= _dvfs_idl_tbl[idx].pll1;
}
regval |= t_mdiv;
/* set MCSEL and MAINDIV again */
putreg32(regval, OSCCNT);
/* update loops_per_msec for up_udelay(), up_mdelay() */
if (0 == tbl)
{
lc823450_dvfs_update_lpm(_dvfs_act_tbl[idx].freq);
}
else
{
lc823450_dvfs_update_lpm(_dvfs_idl_tbl[idx].freq);
}
/* adjust AHB */
if (t_hdiv < _dvfs_cur_hdiv)
{
uint32_t pclkdiv = t_hdiv;
#ifdef CONFIG_LC823450_SDRAM
pclkdiv += (t_hdiv << 16);
#endif
putreg32(pclkdiv, PERICLKDIV);
}
_dvfs_cur_idx = idx;
_dvfs_cur_hdiv = t_hdiv;
_dvfs_cur_mdiv = t_mdiv;
g_dvfs_cur_freq = target;
if (100 > target)
{
/* Clear ROM wait cycle (CPU=0wait) */
modifyreg32(MEMEN4, MEMEN4_HWAIT, 0);
}
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lc823450_get_apb
* Assumption: CPU=APB
****************************************************************************/
uint32_t lc823450_get_apb(void)
{
return g_dvfs_cur_freq * 1000000;
}
/****************************************************************************
* Name: lc823450_dvfs_tick_callback
* This callback is called in the timer interupt
****************************************************************************/
void lc823450_dvfs_tick_callback(void)
{
#if 0
if (_dvfs_init_timeout)
{
_dvfs_init_timeout--;
if (0 == _dvfs_init_timeout)
{
g_dvfs_enabled = 1;
}
}
#endif
}
/****************************************************************************
* Name: lc823450_dvfs_enter_idle
****************************************************************************/
void lc823450_dvfs_enter_idle(void)
{
irqstate_t flags = spin_lock_irqsave();
if (0 == g_dvfs_enabled)
{
goto exit_with_error;
}
#if defined(CONFIG_SMP) && (CONFIG_SMP_NCPUS == 2)
int me = up_cpu_index();
/* Update my state first : 0 (idle) */
_dvfs_cpu_is_active[me] = 0;
/* check if another core is still active */
if (_dvfs_another_cpu_state(me))
{
/* do not change to idle clock */
goto exit_with_error;
}
#endif
#ifdef CONFIG_DVFS_CHECK_SDC
if (lc823450_sdc_locked())
{
goto exit_with_error;
}
#endif
/* NOTE: set idle freq : idx=same, change:tbl */
lc823450_dvfs_set_div(_dvfs_cur_idx, 1);
exit_with_error:
spin_unlock_irqrestore(flags);
}
/****************************************************************************
* Name: lc823450_dvfs_exit_idle
* This API is called in up_ack_irq() (i.e. interrupt context)
****************************************************************************/
void lc823450_dvfs_exit_idle(int irq)
{
irqstate_t flags = spin_lock_irqsave();
if (0 == g_dvfs_enabled)
{
goto exit_with_error;
}
#if defined(CONFIG_SMP) && (CONFIG_SMP_NCPUS == 2)
int me = up_cpu_index();
/* Update my state first: 1 (active) */
_dvfs_cpu_is_active[me] = 1;
/* Check if another core is already active */
if (_dvfs_another_cpu_state(me))
{
/* do nothing */
goto exit_with_error;
}
#endif
/* NOTE: set active freq : idx=same, change:tbl */
lc823450_dvfs_set_div(_dvfs_cur_idx, 0);
exit_with_error:
spin_unlock_irqrestore(flags);
}
/****************************************************************************
* Name: lc823450_dvfs_boost
* boost the sytem clock to MAX (i.e. 160M)
* timeout in msec
****************************************************************************/
int lc823450_dvfs_boost(int timeout)
{
/* TODO */
return 0;
}
/****************************************************************************
* Name: lc823450_dvfs_set_freq
* NOTE: should be called from dvfs command only
****************************************************************************/
int lc823450_dvfs_set_freq(int freq)
{
int ret = 0;
int idx;
irqstate_t flags;
if (0 == g_dvfs_enabled)
{
return -1;
}
flags = spin_lock_irqsave();
switch (freq)
{
case 160:
idx = FREQ_160;
break;
case 80:
idx = FREQ_080;
break;
case 40:
idx = FREQ_040;
break;
default:
ret = -1;
break;
}
if (0 == ret)
{
lc823450_dvfs_set_div(idx, 0);
}
spin_unlock_irqrestore(flags);
return ret;
}

View File

@ -0,0 +1,75 @@
/****************************************************************************
* arch/arm/src/lc823450/lc823450_dvfs2.h
*
* Copyright (C) 2015-2017 Sony Corporation. All rights reserved.
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_LC823450_LC823450_DVFS2_H
#define __ARCH_ARM_SRC_LC823450_LC823450_DVFS2_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Public Data
****************************************************************************/
#ifndef __ASSEMBLY__
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
void lc823450_dvfs_set_min(uint8_t id, uint16_t mhz);
void lc823450_dvfs_enter_idle(void);
void lc823450_dvfs_exit_idle(int irq);
int lc823450_dvfs_set_freq(int freq);
void lc823450_dvfs_tick_callback(void);
int dvfs_procfs_register(void);
#if defined(__cplusplus)
}
#endif
#undef EXTERN
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LC823450_LC823450_DVFS2_H */

View File

@ -50,7 +50,7 @@
#include "up_arch.h"
#ifdef CONFIG_DVFS
# include "lc823450_dvfs.h"
# include "lc823450_dvfs2.h"
#endif
/****************************************************************************
@ -62,6 +62,8 @@ static int32_t g_in_sleep;
static uint64_t g_sleep_t0;
#endif /* CONFIG_LC823450_SLEEP_MODE */
static uint32_t g_idle_counter[2];
/****************************************************************************
* Private Functions
****************************************************************************/
@ -124,18 +126,21 @@ void up_idle(void)
regval &= ~NVIC_SYSCON_SLEEPDEEP;
putreg32(regval, NVIC_SYSCON);
leave_critical_section(flags);
#endif /* CONFIG_LC823450_SLEEP_MODE */
#ifdef CONFIG_DVFS
lc823450_dvfs_enter_idle();
#endif
leave_critical_section(flags);
#endif /* CONFIG_LC823450_SLEEP_MODE */
board_autoled_off(LED_CPU0 + up_cpu_index());
/* Sleep until an interrupt occurs to save power */
asm("WFI");
g_idle_counter[up_cpu_index()]++;
#endif
}

View File

@ -58,7 +58,7 @@
#include "lc823450_intc.h"
#ifdef CONFIG_DVFS
# include "lc823450_dvfs.h"
# include "lc823450_dvfs2.h"
#endif
/****************************************************************************

View File

@ -0,0 +1,354 @@
/****************************************************************************
* arch/arm/src/lc823450/lc823450_procfs_dvfs.c
*
* Copyright (C) 2018 Sony Corporation. All rights reserved.
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <sys/statfs.h>
#include <sys/stat.h>
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <fcntl.h>
#include <assert.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/sched.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/fs/procfs.h>
#include <nuttx/fs/dirent.h>
#include <arch/irq.h>
#include "lc823450_dvfs2.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define DVFS_LINELEN 64
#ifndef MIN
# define MIN(a,b) (a < b ? a : b)
#endif
/****************************************************************************
* Private Types
****************************************************************************/
struct dvfs_file_s
{
struct procfs_file_s base; /* Base open file structure */
unsigned int linesize; /* Number of valid characters in line[] */
char line[DVFS_LINELEN]; /* Pre-allocated buffer for formatted lines */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int dvfs_open(FAR struct file *filep, FAR const char *relpath,
int oflags, mode_t mode);
static int dvfs_close(FAR struct file *filep);
static ssize_t dvfs_read(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t dvfs_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static int dvfs_dup(FAR const struct file *oldp,
FAR struct file *newp);
static int dvfs_stat(FAR const char *relpath, FAR struct stat *buf);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct procfs_operations dvfs_procfsoperations =
{
dvfs_open, /* open */
dvfs_close, /* close */
dvfs_read, /* read */
dvfs_write, /* write */
dvfs_dup, /* dup */
NULL, /* opendir */
NULL, /* closedir */
NULL, /* readdir */
NULL, /* rewinddir */
dvfs_stat /* stat */
};
static const struct procfs_entry_s g_procfs_dvfs =
{
"dvfs",
&dvfs_procfsoperations
};
/****************************************************************************
* Public Data
****************************************************************************/
extern int8_t g_dvfs_enabled;
extern uint16_t g_dvfs_cur_freq;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: dvfs_open
****************************************************************************/
static int dvfs_open(FAR struct file *filep, FAR const char *relpath,
int oflags, mode_t mode)
{
FAR struct dvfs_file_s *priv;
finfo("Open '%s'\n", relpath);
/* "dvfs" is the only acceptable value for the relpath */
if (strcmp(relpath, "dvfs") != 0)
{
ferr("ERROR: relpath is '%s'\n", relpath);
return -ENOENT;
}
/* Allocate a container to hold the task and attribute selection */
priv = (FAR struct dvfs_file_s *)kmm_zalloc(sizeof(struct dvfs_file_s));
if (!priv)
{
ferr("ERROR: Failed to allocate file attributes\n");
return -ENOMEM;
}
/* Save the index as the open-specific state in filep->f_priv */
filep->f_priv = (FAR void *)priv;
return OK;
}
/****************************************************************************
* Name: dvfs_close
****************************************************************************/
static int dvfs_close(FAR struct file *filep)
{
FAR struct dvfs_file_s *priv;
/* Recover our private data from the struct file instance */
priv = (FAR struct dvfs_file_s *)filep->f_priv;
DEBUGASSERT(priv);
/* Release the file attributes structure */
kmm_free(priv);
filep->f_priv = NULL;
return OK;
}
/****************************************************************************
* Name: dvfs_read
****************************************************************************/
static ssize_t dvfs_read(FAR struct file *filep, FAR char *buffer,
size_t buflen)
{
FAR struct dvfs_file_s *priv;
size_t linesize;
size_t copysize;
size_t remaining;
size_t totalsize;
off_t offset = filep->f_pos;
finfo("buffer=%p buflen=%d\n", buffer, (int)buflen);
priv = (FAR struct dvfs_file_s *)filep->f_priv;
DEBUGASSERT(priv);
remaining = buflen;
totalsize = 0;
linesize = snprintf(priv->line,
DVFS_LINELEN,
"cur_freq %d \n", g_dvfs_cur_freq);
copysize = procfs_memcpy(priv->line, linesize, buffer, remaining, &offset);
totalsize += copysize;
buffer += copysize;
remaining -= copysize;
if (totalsize >= buflen)
{
return totalsize;
}
linesize = snprintf(priv->line,
DVFS_LINELEN,
"enable %d \n", g_dvfs_enabled);
copysize = procfs_memcpy(priv->line, linesize, buffer, remaining, &offset);
totalsize += copysize;
/* Update the file offset */
if (totalsize > 0)
{
filep->f_pos += totalsize;
}
return totalsize;
}
/****************************************************************************
* Name: procfs_write
****************************************************************************/
static ssize_t dvfs_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
char line[DVFS_LINELEN];
char cmd[16];
int n;
int freq;
int enable;
n = MIN(buflen, DVFS_LINELEN - 1);
strncpy(line, buffer, n);
line[n] = '\0';
n = MIN(strcspn(line, " "), sizeof(cmd) - 1);
strncpy(cmd, line, n);
cmd[n] = '\0';
if (0 == strcmp(cmd, "cur_freq"))
{
freq = atoi(line + (n + 1));
(void)lc823450_dvfs_set_freq(freq);
}
else if (0 == strcmp(cmd, "enable"))
{
enable = atoi(line + (n + 1));
g_dvfs_enabled = enable;
}
else
{
printf("%s not supported.\n", cmd);
}
return buflen;
}
/****************************************************************************
* Name: dvfs_dup
****************************************************************************/
static int dvfs_dup(FAR const struct file *oldp, FAR struct file *newp)
{
FAR struct dvfs_file_s *oldpriv;
FAR struct dvfs_file_s *newpriv;
finfo("Dup %p->%p\n", oldp, newp);
/* Recover our private data from the old struct file instance */
oldpriv = (FAR struct dvfs_file_s *)oldp->f_priv;
DEBUGASSERT(oldpriv);
/* Allocate a new container to hold the task and attribute selection */
newpriv = (FAR struct dvfs_file_s *)kmm_zalloc(sizeof(struct dvfs_file_s));
if (!newpriv)
{
ferr("ERROR: Failed to allocate file attributes\n");
return -ENOMEM;
}
/* The copy the file attributes from the old attributes to the new */
memcpy(newpriv, oldpriv, sizeof(struct dvfs_file_s));
/* Save the new attributes in the new file structure */
newp->f_priv = (FAR void *)newpriv;
return OK;
}
/****************************************************************************
* Name: dvfs_stat
****************************************************************************/
static int dvfs_stat(const char *relpath, struct stat *buf)
{
if (strcmp(relpath, "dvfs") != 0)
{
ferr("ERROR: relpath is '%s'\n", relpath);
return -ENOENT;
}
buf->st_mode =
S_IFREG |
S_IROTH | S_IWOTH |
S_IRGRP | S_IWGRP |
S_IRUSR | S_IWUSR;
buf->st_size = 0;
buf->st_blksize = 0;
buf->st_blocks = 0;
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: dvfs_procfs_register
****************************************************************************/
int dvfs_procfs_register(void)
{
return procfs_register(&g_procfs_dvfs);
}

View File

@ -62,6 +62,13 @@
#include "lc823450_clockconfig.h"
#include "lc823450_serial.h"
#ifdef CONFIG_DVFS
# include "lc823450_dvfs2.h"
#endif
#if !defined(CONFIG_LC823450_MTM0_TICK) && defined (CONFIG_DVFS)
# error "Use CONFIG_LC823450_MTM0_TICK=y"
#endif
/****************************************************************************
* Pre-processor Definitions

View File

@ -248,6 +248,26 @@ nsh> route
SEQ TARGET NETMASK ROUTER
1. 0.0.0.0 0.0.0.0 192.168.1.1
12. DVFS (Dynamic Voltage and Frequency Scaling)
lc823450-xgevk/audio and rndis configurations support DVFS.
You can check the status via /proc/dvfs
nsh> cat /proc/dvfs
cur_freq 160
enable 0
By default, DVFS is disabled. To enable,
nsh> echo "enable 1" > /proc/dvfs
In addition, you can change CPU frequency to 160/80/40. To change the
frequency, enable the DVFS first then do the following.
nsh> echo "cur_freq 80" > /proc/dvfs.
Currently, DVFS works in manual mode and Vdd1 is fixed to 1.2V
which will be changed in the future version.
TODO
^^^^

View File

@ -28,6 +28,7 @@ CONFIG_DEBUG_WARN=y
CONFIG_DEV_ZERO=y
CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_DRIVERS_AUDIO=y
CONFIG_DVFS=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_EXAMPLES_NSH=y
CONFIG_EXAMPLES_NXHELLO_BPP=1
@ -40,6 +41,7 @@ CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FS_FATTIME=y
CONFIG_FS_FAT=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_PROCFS=y
CONFIG_HRT_TIMER=y
CONFIG_I2C_RESET=y

View File

@ -1,19 +1,15 @@
# CONFIG_LC823450_SDIF is not set
# CONFIG_NSH_ARGCAT is not set
# CONFIG_NX_DISABLE_1BPP is not set
# CONFIG_SPI_EXCHANGE is not set
CONFIG_ADC=y
CONFIG_ANALOG=y
CONFIG_AQM_1248A=y
CONFIG_ARCH_BOARD_LC823450_XGEVK=y
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD="lc823450-xgevk"
CONFIG_ARCH_BOARD_LC823450_XGEVK=y
CONFIG_ARCH_CHIP_LC823450=y
CONFIG_ARCH_FLOAT_H=y
CONFIG_ARCH_INTERRUPTSTACK=2048
CONFIG_ARCH_STDARG_H=y
CONFIG_ARCH="arm"
CONFIG_BOARD_LOOPSPERMSEC=12061
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_LOOPSPERMSEC=12061
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CODECS_HASH_MD5=y
@ -41,12 +37,13 @@ CONFIG_FS_PROCFS=y
CONFIG_FS_WRITABLE=y
CONFIG_HRT_TIMER=y
CONFIG_I2C_RESET=y
CONFIG_I2C=y
CONFIG_I2CTOOL_MAXBUS=1
CONFIG_I2C=y
CONFIG_INTELHEX_BINARY=y
CONFIG_LC823450_I2C0=y
CONFIG_LC823450_I2C1=y
CONFIG_LC823450_MTM0_TICK=y
# CONFIG_LC823450_SDIF is not set
CONFIG_LC823450_SPI_DMA=y
CONFIG_LC823450_UART0=y
CONFIG_LC823450_WDT=y
@ -63,6 +60,7 @@ CONFIG_NETUTILS_CODECS=y
CONFIG_NFILE_DESCRIPTORS=45
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
# CONFIG_NSH_ARGCAT is not set
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_DISABLE_BASENAME=y
CONFIG_NSH_DISABLE_CP=y
@ -81,8 +79,8 @@ CONFIG_NSH_DISABLE_MKFIFO=y
CONFIG_NSH_DISABLE_MKRD=y
CONFIG_NSH_DISABLE_MV=y
CONFIG_NSH_DISABLE_PUT=y
CONFIG_NSH_DISABLE_RM=y
CONFIG_NSH_DISABLE_RMDIR=y
CONFIG_NSH_DISABLE_RM=y
CONFIG_NSH_DISABLE_SH=y
CONFIG_NSH_DISABLE_WGET=y
CONFIG_NSH_DISABLE_XD=y
@ -90,8 +88,9 @@ CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_MAXARGUMENTS=10
CONFIG_NSH_READLINE=y
CONFIG_NX_BLOCKING=y
CONFIG_NX=y
# CONFIG_NX_DISABLE_1BPP is not set
CONFIG_NXFONT_MONO5X8=y
CONFIG_NX=y
CONFIG_PIPES=y
CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=2048
CONFIG_PREALLOC_MQ_MSGS=4
@ -118,6 +117,7 @@ CONFIG_SDCLONE_DISABLE=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SMP_NCPUS=2
CONFIG_SMP=y
# CONFIG_SPI_EXCHANGE is not set
CONFIG_SPINLOCK_IRQ=y
CONFIG_SPI=y
CONFIG_START_DAY=3

View File

@ -30,6 +30,7 @@ CONFIG_DEBUG_WARN=y
CONFIG_DEV_ZERO=y
CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_DRIVERS_AUDIO=y
CONFIG_DVFS=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_EXAMPLES_NSH=y
CONFIG_EXAMPLES_NXHELLO_BPP=1
@ -42,6 +43,7 @@ CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FS_FATTIME=y
CONFIG_FS_FAT=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_PROCFS=y
CONFIG_HRT_TIMER=y
CONFIG_I2C_RESET=y
@ -168,6 +170,7 @@ CONFIG_SYSTEM_I2CTOOL=y
CONFIG_SYSTEM_NXPLAYER=y
CONFIG_SYSTEM_PING=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TELNET_CHARACTER_MODE=y
CONFIG_UART0_RXBUFSIZE=512
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART0_TXBUFSIZE=2048

View File

@ -57,6 +57,10 @@
# include "lc823450_wdt.h"
#endif
#ifdef CONFIG_DVFS
# include "lc823450_dvfs2.h"
#endif
#include "lc823450-xgevk.h"
/****************************************************************************
@ -80,6 +84,11 @@ int lc823450_bringup(void)
#endif
#ifdef CONFIG_FS_PROCFS
#ifdef CONFIG_DVFS
(void)dvfs_procfs_register();
#endif
/* Mount the procfs file system */
ret = mount(NULL, "/proc", "procfs", 0, NULL);

View File

@ -1,18 +1,15 @@
# CONFIG_NSH_ARGCAT is not set
# CONFIG_NX_DISABLE_1BPP is not set
# CONFIG_SPI_EXCHANGE is not set
CONFIG_ADC=y
CONFIG_ANALOG=y
CONFIG_AQM_1248A=y
CONFIG_ARCH_BOARD_LC823450_XGEVK=y
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD="lc823450-xgevk"
CONFIG_ARCH_BOARD_LC823450_XGEVK=y
CONFIG_ARCH_CHIP_LC823450=y
CONFIG_ARCH_FLOAT_H=y
CONFIG_ARCH_INTERRUPTSTACK=2048
CONFIG_ARCH_STDARG_H=y
CONFIG_ARCH="arm"
CONFIG_BOARD_LOOPSPERMSEC=12061
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_LOOPSPERMSEC=12061
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CODECS_HASH_MD5=y
@ -40,13 +37,13 @@ CONFIG_EXAMPLES_WATCHDOG=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_FAT=y
CONFIG_FS_PROCFS=y
CONFIG_HRT_TIMER=y
CONFIG_I2C_RESET=y
CONFIG_I2C=y
CONFIG_I2CTOOL_MAXBUS=1
CONFIG_I2C=y
CONFIG_INTELHEX_BINARY=y
CONFIG_LC823450_I2C0=y
CONFIG_LC823450_I2C1=y
@ -71,6 +68,7 @@ CONFIG_NETUTILS_CODECS=y
CONFIG_NFILE_DESCRIPTORS=45
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
# CONFIG_NSH_ARGCAT is not set
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDOPT_DD_STATS=y
CONFIG_NSH_DISABLE_EXEC=y
@ -91,8 +89,9 @@ CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_MAXARGUMENTS=10
CONFIG_NSH_READLINE=y
CONFIG_NX_BLOCKING=y
CONFIG_NX=y
# CONFIG_NX_DISABLE_1BPP is not set
CONFIG_NXFONT_MONO5X8=y
CONFIG_NX=y
CONFIG_PIPES=y
CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=2048
CONFIG_PREALLOC_MQ_MSGS=4
@ -120,6 +119,7 @@ CONFIG_SENSORS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SMP_NCPUS=2
CONFIG_SMP=y
# CONFIG_SPI_EXCHANGE is not set
CONFIG_SPINLOCK_IRQ=y
CONFIG_SPI=y
CONFIG_START_DAY=3