summaryrefslogtreecommitdiff
path: root/nuttx/arch/sh
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-11-09 15:06:34 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-11-09 15:06:34 +0000
commit178b76fc31ef415864e57c75ac991e6c2df3746c (patch)
tree56f3fc992b2192f7aba21f3fd6754eb8103adbfd /nuttx/arch/sh
parente37724041718e6b0ea5828af36c690299dd1b142 (diff)
downloadpx4-nuttx-178b76fc31ef415864e57c75ac991e6c2df3746c.tar.gz
px4-nuttx-178b76fc31ef415864e57c75ac991e6c2df3746c.tar.bz2
px4-nuttx-178b76fc31ef415864e57c75ac991e6c2df3746c.zip
Add SH-1 system timer setup
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1175 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/sh')
-rw-r--r--nuttx/arch/sh/include/sh1/irq.h2
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_703x.h79
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_timerisr.c104
3 files changed, 175 insertions, 10 deletions
diff --git a/nuttx/arch/sh/include/sh1/irq.h b/nuttx/arch/sh/include/sh1/irq.h
index 60ee11160..407661b7f 100644
--- a/nuttx/arch/sh/include/sh1/irq.h
+++ b/nuttx/arch/sh/include/sh1/irq.h
@@ -190,7 +190,7 @@
#define SH1_WDTITI_IRQ (SH1_LASTSCI_IRQ+3) /* WDT ITI */
#define SH1_CMI_IRQ (SH1_LASTSCI_IRQ+4) /* REF CMI */
-#define STR71X_IRQ_SYSTIMER STR71X_IRQ_T0TIMI
+#define SH1_SYSTIMER_IRQ SH1_IMIA0_IRQ
#define NR_IRQS (SH1_CMI_IRQ+1)
#endif
diff --git a/nuttx/arch/sh/src/sh1/sh1_703x.h b/nuttx/arch/sh/src/sh1/sh1_703x.h
index 22de4753d..8be1cc386 100644
--- a/nuttx/arch/sh/src/sh1/sh1_703x.h
+++ b/nuttx/arch/sh/src/sh1/sh1_703x.h
@@ -313,6 +313,85 @@
#define SH1_SCISSR_RDRF (0x40) /* Bit 6: RDR contains valid received data */
#define SH1_SCISSR_TDRE (0x80) /* Bit 7: TDR does not contain valid transmit data */
+/* Integrated Timer unit (ITU) */
+
+#define SH1_ITUTSTR_STR0 (0x01) /* Bit 0: TCNT0 is counting */
+#define SH1_ITUTSTR_STR1 (0x02) /* Bit 1: TCNT1 is counting */
+#define SH1_ITUTSTR_STR2 (0x04) /* Bit 2: TCNT2 is counting */
+#define SH1_ITUTSTR_STR3 (0x08) /* Bit 3: TCNT3 is counting */
+#define SH1_ITUTSTR_STR4 (0x10) /* Bit 4: TCNT4 is counting */
+
+#define SH1_ITUTSNC_SYNC0 (0x01) /* Bit 0: Channel 0 operates synchronously */
+#define SH1_ITUTSNC_SYNC1 (0x02) /* Bit 1: Channel 1 operates synchronously */
+#define SH1_ITUTSNC_SYNC2 (0x04) /* Bit 2: Channel 2 operates synchronously */
+#define SH1_ITUTSNC_SYNC3 (0x08) /* Bit 3: Channel 3 operates synchronously */
+#define SH1_ITUTSNC_SYNC4 (0x10) /* Bit 4: Channel 4 operates synchronously */
+
+#define SH1_ITUTMDR_PWM0 (0x01) /* Bit 0: Channel 0 operated in PWM mode */
+#define SH1_ITUTMDR_PWM1 (0x02) /* Bit 1: Channel 1 operated in PWM mode */
+#define SH1_ITUTMDR_PWM2 (0x04) /* Bit 2: Channel 2 operated in PWM mode */
+#define SH1_ITUTMDR_PWM3 (0x08) /* Bit 3: Channel 3 operated in PWM mode */
+#define SH1_ITUTMDR_PWM4 (0x10) /* Bit 4: Channel 4 operated in PWM mode */
+#define SH1_ITUTMDR_FDIR (0x20) /* Bit 5: OVF set when TCNT2 overflows */
+#define SH1_ITUTMDR_MDF (0x40) /* Bit 6: Channel 2 operates in phase counting mode */
+
+#define SH1_ITUTFCR_BFA3 (0x01) /* Bit 0: GRA3 & BRA3 operate in mode in channel 4 */
+#define SH1_ITUTFCR_BFB3 (0x02) /* Bit 1: GRB3 & BRB3 operate in mode in channel 4 */
+#define SH1_ITUTFCR_BFA4 (0x04) /* Bit 2: GRA4 & BRA4 operate in mode in channel 4 */
+#define SH1_ITUTFCR_BFB4 (0x08) /* Bit 3: GRB4 & BRB4 operate in mode in channel 4 */
+#define SH1_ITUTFCR_CMDMASK (0x30) /* Bit 4-5: Command */
+#define SH1_ITUTFCR_34NDEF (0x00) /* Channels 3/4 normal (default) */
+#define SH1_ITUTFCR_34NORM (0x10) /* Channels 3/4 normal */
+#define SH1_ITUTFCR_34CPWM (0x20) /* Channels 3/4 in complementary PWM mode*/
+#define SH1_ITUTFCR_34RSPWN (0x30) /* Channels 3/4 in reset-synchronized PWM mode */
+
+#define SH1_ITUTOCR_OLS3 (0x01) /* Bit 0: 1=TIOCA3, A4 & B4 not inverted */
+#define SH1_ITUTOCR_OLS4 (0x02) /* Bit 1: 1=TIOCB3, XA4 & XB4 not inverted */
+
+#define SH1_ITUTCR_TPSCMSK (0x07) /* Bits 0-2: Clock setup, internal/external, divider */
+#define SH1_ITUTCR_DIV1 (0x00) /* Internal clock (phi) */
+#define SH1_ITUTCR_DIV2 (0x01) /* phi / 2 */
+#define SH1_ITUTCR_DIV4 (0x02) /* phi / 4 */
+#define SH1_ITUTCR_DIV8 (0x03) /* phi / 8 */
+#define SH1_ITUTCR_TCLKA (0x04) /* External clock A (TCLKA) */
+#define SH1_ITUTCR_TCLKB (0x05) /* External clock B (TCLKB) */
+#define SH1_ITUTCR_TCLKC (0x06) /* External clock C (TCLKC) */
+#define SH1_ITUTCR_TCLKD (0x07) /* External clock D (TCLKD) */
+#define SH1_ITUTCR_CKEGMSK (0x18) /* Bits 3-4: External clock input edge selection */
+#define SH1_ITUTCR_RISING (0x00) /* Count rising edges */
+#define SH1_ITUTCR_FALLING (0x08) /* Count falling edges */
+#define SH1_ITUTCR_BOTH (0x10) /* Count both */
+#define SH1_ITUTCR_CCLRMSK (0x60) /* Bits 5-6: TCNT clear controls */
+#define SH1_ITUTCR_NCLR (0x00) /* TCNT not cleared */
+#define SH1_ITUTCR_CGRA (0x20) /* TCNT cleared by GRA */
+#define SH1_ITUTCR_CGRB (0x40) /* TCNT cleared by GRB */
+#define SH1_ITUTCR_CSYNC (0x60) /* Synchronized clear */
+
+#define SH1_ITUTIOR_IOAMSK (0x07) /* Bits 0-3: GRA function */
+#define SH1_ITUTIOR_OCGRAD (0x00) /* GRA output comparator, disabled */
+#define SH1_ITUTIOR_OCGRA0 (0x01) /* GRA output comparator, 0 output at match */
+#define SH1_ITUTIOR_OCGRA1 (0x02) /* GRA output comparator, 1 output at match */
+#define SH1_ITUTIOR_OCATOG (0x03) /* GRA output comparator, output toggles at match */
+#define SH1_ITUTIOR_ICGRAR (0x04) /* GRA input capture, rising edge */
+#define SH1_ITUTIOR_ICGRAF (0x05) /* GRA input capture, falling edge */
+#define SH1_ITUTIOR_ICGRAB (0x06) /* GRA input capture, both edges */
+#define SH1_ITUTIOR_IOBMSK (0x70) /* Bits 4-6: GRB function */
+#define SH1_ITUTIOR_OCGRBD (0x00) /* GRB output comparator, disabled */
+#define SH1_ITUTIOR_OCGRB0 (0x10) /* GRB output comparator, 0 output at match */
+#define SH1_ITUTIOR_OCGRB1 (0x20) /* GRB output comparator, 1 output at match */
+#define SH1_ITUTIOR_OCBTOG (0x30) /* GRB output comparator, output toggles at match */
+#define SH1_ITUTIOR_ICGRBR (0x40) /* GRB input capture, rising edge */
+#define SH1_ITUTIOR_ICGRBF (0x50) /* GRB input capture, falling edge */
+#define SH1_ITUTIOR_ICGRBB (0x60) /* GRB input capture, both edges */
+
+#define SH1_ITUTSR_IMFA (0x01) /* Bit 0: 0=Clearing condition, 1=setting confition */
+#define SH1_ITUTSR_IMFB (0x02) /* Bit 1: 0=Clearing condition, 1=setting confition */
+#define SH1_ITUTSR_OVF (0x04) /* Bit 2: 0=Clearing condition, 1=setting confition */
+
+#define SH1_ITUTIER_IMIEA (0x01) /* Bit 0: Enables interrupt request from IMFA */
+#define SH1_ITUTIER_IMIEB (0x02) /* Bit 1: Enables interrupt request from IMFB */
+#define SH1_ITUTIER_OVIE (0x04) /* Bit 2: Enables interrupt request from OVR */
+
/* Interrupt Controller (INTC) */
#define SH1_IPRA_IRQ3MASK (0x000f) /* Bits 0-3: IRQ3 */
diff --git a/nuttx/arch/sh/src/sh1/sh1_timerisr.c b/nuttx/arch/sh/src/sh1/sh1_timerisr.c
index 874e25647..01113b390 100644
--- a/nuttx/arch/sh/src/sh1/sh1_timerisr.c
+++ b/nuttx/arch/sh/src/sh1/sh1_timerisr.c
@@ -58,7 +58,58 @@
* CLK_TCK (see include/time.h). CLK_TCK defines the desired number of
* system clock ticks per second. That value is a user configurable setting
* that defaults to 100 (100 ticks per second = 10 MS interval).
+ *
+ * ITU1 operates in periodic timer mode. TCNT counts up until it matches
+ * the value of GRA0, then an interrupt is generated. Two values must be
+ * computed:
+ *
+ * (1) The divider that determines the rate at which TCNT increments, and
+ * (2) The value of GRA0 that cause the interrupt to occur.
+ *
+ * These must be selected so that the frequency of interrupt generation is
+ * CLK_TCK. Ideally, we would like to use the full range of GRA0 for better
+ * timing acuracy:
+ */
+
+#define DESIRED_GRA0 65535
+
+/* The ideal divider would be one that generates exactly 65535 ticks in
+ * 1/CLK_TCK seconds. For example, if SH1_CLOCK is 10MHz and CLK_TCK is
+ * 100, then the ideal divider must be less greater than or equal to:
+ *
+ * (10,000,000 / CLK_TCK) / 65535 = 1.525
+ *
+ * The actual selected divider would then have to be 2, resulting in a
+ * counting rate of 5,000,0000 and a GRA0 setting of 50,000.
*/
+
+#define SYSCLKS_PER_TICK ((SH1_CLOCK + (CLK_TCK-1))/ CLK_TCK)
+#define DESIRED_DIVIDER ((SYSCLKS_PER_TICK + (DESIRED_GRA0-1))/ DESIRED_GRA0)
+
+#if (DESIRED_DIVIDER <= 1)
+# define SYSCLK_DIVIDER 1
+# define SH1_ITUTCR_DIV SH1_ITUTCR_DIV1
+#elif (DESIRED_DIVIDER <= 2)
+# define SYSCLK_DIVIDER 2
+# define SH1_ITUTCR_DIV SH1_ITUTCR_DIV2
+#elif (DESIRED_DIVIDER <= 4)
+# define SYSCLK_DIVIDER 4
+# define SH1_ITUTCR_DIV SH1_ITUTCR_DIV4
+#elif (DESIRED_DIVIDER <= 8)
+# define SYSCLK_DIVIDER 8
+# define SH1_ITUTCR_DIV SH1_ITUTCR_DIV8
+#else
+# error "No divider is available for this system clock"
+#endif
+
+/* The TCNT will then increment at the following rate: */
+
+#define TCNT_CLOCK ((SH1_CLOCK + (SYSCLK_DIVIDER/2))/ SYSCLK_DIVIDER)
+
+/* And the value of GRA0 that generates at CLK_TCK ticks per second is: */
+
+#define TCNT_PER_TICK ((TCNT_CLOCK + (CLK_TCK-1))/ CLK_TCK)
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -82,9 +133,18 @@
int up_timerisr(int irq, uint32 *regs)
{
+ ubyte reg8;
+
/* Process timer interrupt */
sched_process_timer();
+
+ /* Clear ITU0 interrupt status flag */
+
+ reg8 = getreg8(SH1_ITU0_TSR);
+ reg8 &= ~SH1_ITUTSR_IMFA;
+ putreg8(reg8, SH1_ITU0_TSR);
+
return 0;
}
@@ -99,19 +159,45 @@ int up_timerisr(int irq, uint32 *regs)
void up_timerinit(void)
{
-#warning "Timer initialization logic needed"
-#if 0
+ ubyte reg8;
- /* Set the IRQ interrupt priority */
+ /* Clear timer counter 0 */
- up_prioritize_irq(STR71X_IRQ_SYSTIMER, 1);
+ putreg16(0, SH1_ITU0_TCNT);
- /* Attach the timer interrupt vector */
+ /* Set the GRA0 match value. The interrupt will be generated when TNCT
+ * increments to this value
+ */
- (void)irq_attach(STR71X_IRQ_SYSTIMER, (xcpt_t)up_timerisr);
+ putreg16(TCNT_PER_TICK, SH1_ITU0_GRA);
- /* And enable the timer interrupt */
+ /* Set the timer control register. TCNT cleared by FRA */
- up_enable_irq(STR71X_IRQ_SYSTIMER);
-#endif
+ putreg8(SH1_ITUTCR_CGRA|SH1_ITUTCR_DIV, SH1_ITU0_TCR);
+
+ /* Set the timer I/O control register */
+
+ putreg8(0, SH1_ITU0_TIOR); /* GRA used but with no inputs/output pins */
+
+ /* Make sure that all status flags are clear */
+
+ putreg8(0, SH1_ITU0_TSR);
+
+ /* Attach the IMIA0 IRQ */
+
+ irq_attach(SH1_SYSTIMER_IRQ, (xcpt_t)up_timerisr);
+
+ /* Enabled interrupts from GRA compare match */
+
+ putreg8(SH1_ITUTIER_IMIEA, SH1_ITU0_TIER);
+
+ /* Set the interrupt priority */
+
+ up_prioritize_irq(SH1_SYSTIMER_IRQ, 7); /* Set ITU priority midway */
+
+ /* Start the timer */
+
+ reg8 = getreg8(SH1_ITU_TSTR);
+ reg8 |= SH1_ITUTSTR_STR0; /* Enable TCNT0 */
+ putreg8(reg8, SH1_ITU_TSTR); /* TCNT0 is counting */
}