New generic I2C framework. Supports bit-bang and "intelligent" I2C

interface controllers (of varying intelligence levels).

Contributed by Wasabi Systems, Inc.  Primarily written by Steve Woodford,
with some modification by me.

(NOTE: "cvs ci" was missed on this directory during the initial checkin
of the new I2C code.)
This commit is contained in:
thorpej 2003-10-06 16:11:19 +00:00
parent 2af80d899e
commit 2c0d381bd7
11 changed files with 372 additions and 1671 deletions

View File

@ -1,10 +1,10 @@
# $NetBSD: files.iomd,v 1.2 2002/06/16 13:20:14 bjh21 Exp $
# $NetBSD: files.iomd,v 1.3 2003/10/06 16:11:19 thorpej Exp $
#
# IOMD-specific configuration data
#
# IOMD device
# parent to kbd, qms, opms, iic
# parent to kbd, qms, opms, iomdiic
# also provides irq and timer services
device iomd {}
attach iomd at mainbus
@ -16,23 +16,10 @@ file arch/arm/iomd/iomd_irqhandler.c iomd
file arch/arm/iomd/iomd_fiq.S iomd
file arch/arm/iomd/iomd_dma.c iomd
# IIC device
device iic { addr = -1 }
file arch/arm/iomd/iic.c iic needs-flag
attach iic at iomd with iic_iomd
file arch/arm/iomd/iic_iomd.c iic_iomd
file arch/arm/iomd/iomd_iic.S iic_iomd
# IIC based RTC
define todservice {}
device rtc : todservice
attach rtc at iic
file arch/arm/iomd/rtc.c rtc needs-flag
device todclock
attach todclock at todservice
file arch/arm/iomd/todclock.c todclock needs-count
# I^2C bus (bit-banged through IOMD control register)
device iomdiic: i2cbus, i2c_bitbang
attach iomdiic at iomd
file arch/arm/iomd/iomdiic.c iomdiic
# IOMD mouse devices
# clock device

View File

@ -1,343 +0,0 @@
/* $NetBSD: iic.c,v 1.8 2003/07/15 00:24:44 lukem Exp $ */
/*
* Copyright (c) 1994-1996 Mark Brinicombe.
* Copyright (c) 1994 Brini.
* All rights reserved.
*
* This code is derived from software written for Brini by Mark Brinicombe
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed by Mark Brinicombe.
* 4. The name of the company nor the name of the author may be used to
* endorse or promote products derived from this software without specific
* prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY BRINI ``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 BRINI 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.
*
* RiscBSD kernel project
*
* iic.c
*
* Routines to communicate with IIC devices
*
* Created : 13/10/94
*
* Based of kate/display/iiccontrol.c
*/
#include <sys/cdefs.h>
__KERNEL_RCSID(0, "$NetBSD: iic.c,v 1.8 2003/07/15 00:24:44 lukem Exp $");
#include <sys/param.h>
#include <sys/systm.h>
#include <sys/kernel.h>
#include <sys/conf.h>
#include <sys/malloc.h>
#include <sys/device.h>
#include <sys/event.h>
#include <machine/bus.h>
#include <machine/cpu.h>
#include <arm/cpufunc.h>
#include <arm/iomd/iic.h>
#include <arm/iomd/iicvar.h>
#include "locators.h"
/* Local function prototypes */
static int iic_getack __P((void));
static void iic_write_bit __P((int bit));
static int iic_write_byte __P((u_char value));
static u_char iic_read_byte __P((void));
static void iic_start_bit __P((void));
static void iic_stop_bit __P((void));
static int iicprint __P((void *aux, const char *name));
/* External functions that do the bit twiddling */
extern int iic_getstate __P((void));
extern void iic_set_state_and_ack __P((int, int));
extern void iic_set_state __P((int, int));
extern void iic_delay __P((int));
extern struct cfdriver iic_cd;
dev_type_open(iicopen);
dev_type_close(iicclose);
const struct cdevsw iic_cdevsw = {
iicopen, iicclose, noread, nowrite, noioctl,
nostop, notty, nopoll, nommap, nokqfilter,
};
/*
* Main entry to IIC driver.
*/
int
iic_control(address, buffer, count)
u_char address;
u_char *buffer;
int count;
{
int loop;
/* Send the start bit */
iic_start_bit();
/* Send the address */
if (!iic_write_byte(address)) {
iic_stop_bit();
return(-1);
}
/* Read or write the data as required */
if ((address & 1) == 0) {
/* Write bytes */
for (loop = 0; loop < count; ++loop) {
if (!iic_write_byte(buffer[loop])) {
iic_stop_bit();
return(-1);
}
}
}
else {
/* Read bytes */
for (loop = 0; loop < count; ++loop) {
buffer[loop] = iic_read_byte();
/* Send final acknowledge */
if (loop == (count - 1))
iic_write_bit(1);
else
iic_write_bit(0);
}
}
/* Send stop bit */
iic_stop_bit();
return(0);
}
static int
iic_getack()
{
u_int oldirqstate;
int ack;
iic_set_state(1, 0);
oldirqstate = disable_interrupts(I32_bit);
iic_set_state_and_ack(1, 1);
ack = iic_getstate();
iic_set_state(1, 0);
restore_interrupts(oldirqstate);
return((ack & 1) == 0);
}
static void
iic_write_bit(bit)
int bit;
{
u_int oldirqstate;
iic_set_state(bit, 0);
oldirqstate = disable_interrupts(I32_bit);
iic_set_state_and_ack(bit, 1);
iic_set_state(bit, 0);
restore_interrupts(oldirqstate);
}
static int
iic_write_byte(value)
u_char value;
{
int loop;
int bit;
for (loop = 0x80; loop != 0; loop = loop >> 1) {
bit = ((value & loop) != 0);
iic_write_bit(bit);
}
return(iic_getack());
}
static u_char
iic_read_byte()
{
int loop;
u_char byte;
u_int oldirqstate;
iic_set_state(1,0);
byte = 0;
for (loop = 0; loop < 8; ++loop) {
oldirqstate = disable_interrupts(I32_bit);
iic_set_state_and_ack(1, 1);
byte = (byte << 1) + (iic_getstate() & 1);
iic_set_state(1, 0);
restore_interrupts(oldirqstate);
}
return(byte);
}
static void
iic_start_bit()
{
iic_set_state(1, 1);
iic_set_state(0, 1);
iic_delay(10);
iic_set_state(0, 0);
}
static void
iic_stop_bit()
{
iic_set_state(0, 1);
iic_set_state(1, 1);
}
/* driver structures */
/*
* int iicprint(void *aux, const char *name)
*
* print function for child device configuration
*/
static int
iicprint(aux, name)
void *aux;
const char *name;
{
struct iicbus_attach_args *iba = aux;
if (!name) {
if (iba->ib_addr)
aprint_normal(" addr 0x%02x", iba->ib_addr);
}
/* XXXX print flags */
return (QUIET);
}
/*
* iic search function
*
* search for devices that are children of the iic device
* fill out the attach arguments and call the probe and
* attach function (as required).
*
* Note: since the offsets of the devices need to be specified in the
* config file we ignore the FSTAT_STAR.
*/
int
iicsearch(parent, cf, aux)
struct device *parent;
struct cfdata *cf;
void *aux;
{
struct iic_softc *sc = (struct iic_softc *)parent;
struct iicbus_attach_args iba;
int tryagain;
do {
iba.ib_iic_softc = sc;
iba.ib_addr = cf->cf_loc[IICCF_ADDR];
iba.ib_aux = NULL;
tryagain = 0;
if (config_match(parent, cf, &iba) > 0) {
config_attach(parent, cf, &iba, iicprint);
/* tryagain = (cf->cf_fstate == FSTATE_STAR);*/
}
} while (tryagain);
return (0);
}
/*
* Q: Do we really need a device interface ?
*/
int
iicopen(dev, flag, mode, p)
dev_t dev;
int flag;
int mode;
struct proc *p;
{
struct iic_softc *sc;
int unit = minor(dev);
if (unit >= iic_cd.cd_ndevs)
return(ENXIO);
sc = iic_cd.cd_devs[unit];
if (!sc) return(ENXIO);
if (sc->sc_flags & IIC_OPEN) return(EBUSY);
sc->sc_flags |= IIC_OPEN;
return(0);
}
int
iicclose(dev, flag, mode, p)
dev_t dev;
int flag;
int mode;
struct proc *p;
{
int unit = minor(dev);
struct iic_softc *sc = iic_cd.cd_devs[unit];
sc->sc_flags &= ~IIC_OPEN;
return(0);
}
/* End of iic.c */

View File

@ -1,72 +0,0 @@
/* $NetBSD: iic.h,v 1.1 2001/10/05 22:27:40 reinoud Exp $ */
/*
* Copyright (c) 1996 Mark Brinicombe.
* All rights reserved.
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed by Brini.
* 4. The name of the company nor the name of the author may be used to
* endorse or promote products derived from this software without specific
* prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY BRINI ``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 BRINI 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.
*
* RiscBSD kernel project
*
* iic.h
*
* header file for IIC
*
* Created : 15/04/96
*/
/*
* IIC bus driver attach arguments
*/
#ifdef _KERNEL
struct iicbus_attach_args {
int ib_addr; /* i/o address */
void *ib_aux; /* driver specific */
void *ib_iic_softc; /* softc of iic parent */
};
#define iic_bitdelay 10
#define IIC_WRITE 0x00
#define IIC_READ 0x01
/* Prototypes for assembly functions */
void iic_set_state __P((int data, int clock));
void iic_set_state_and_ack __P((int data, int clock));
void iic_delay __P((int delay));
/* Prototype for kernel interface to IIC bus */
int iic_control __P((u_char address, u_char *buffer, int count));
#endif /* _KERNEL */
/* End of iic.h */

View File

@ -1,110 +0,0 @@
/* $NetBSD: iic_iomd.c,v 1.6 2003/07/15 00:24:44 lukem Exp $ */
/*
* Copyright (c) 1994-1996 Mark Brinicombe.
* Copyright (c) 1994 Brini.
* All rights reserved.
*
* This code is derived from software written for Brini by Mark Brinicombe
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed by Mark Brinicombe.
* 4. The name of the company nor the name of the author may be used to
* endorse or promote products derived from this software without specific
* prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY BRINI ``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 BRINI 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.
*
* RiscBSD kernel project
*
* iic.c
*
* Routines to communicate with IIC devices
*
* Created : 13/10/94
*
* Based of kate/display/iiccontrol.c
*/
#include <sys/cdefs.h>
__KERNEL_RCSID(0, "$NetBSD: iic_iomd.c,v 1.6 2003/07/15 00:24:44 lukem Exp $");
#include <sys/param.h>
#include <sys/systm.h>
#include <sys/kernel.h>
#include <sys/device.h>
#include <machine/bus.h>
#include <machine/intr.h>
#include <arm/iomd/iicvar.h>
#include <arm/iomd/iomdvar.h>
static int iic_iomd_probe __P((struct device *, struct cfdata *, void *));
static void iic_iomd_attach __P((struct device *, struct device *, void *));
CFATTACH_DECL(iic_iomd, sizeof(struct iic_softc),
iic_iomd_probe, iic_iomd_attach, NULL, NULL);
/*
* iic device probe function
*
* just validate the attach args
*/
static int
iic_iomd_probe(parent, cf, aux)
struct device *parent;
struct cfdata *cf;
void *aux;
{
struct iic_attach_args *ia = aux;
if (strcmp(ia->ia_name, "iic") == 0)
return(1);
return(0);
}
/*
* iic device attach function
*
* Initialise the softc structure and do a search for children
*/
static void
iic_iomd_attach(parent, self, aux)
struct device *parent;
struct device *self;
void *aux;
{
struct iic_softc *sc = (void *)self;
struct iic_attach_args *ia = aux;
sc->sc_iot = ia->ia_iot;
sc->sc_ioh = ia->ia_ioh;
printf("\n");
config_search(iicsearch, self, NULL);
}
/* End of iic_iomd.c */

View File

@ -1,4 +1,4 @@
/* $NetBSD: iomd_clock.c,v 1.11 2003/07/14 15:17:23 lukem Exp $ */
/* $NetBSD: iomd_clock.c,v 1.12 2003/10/06 16:11:19 thorpej Exp $ */
/*
* Copyright (c) 1994-1997 Mark Brinicombe.
@ -54,6 +54,8 @@ __KERNEL_RCSID(0, "$NetBSD");
#include <sys/time.h>
#include <sys/device.h>
#include <dev/clock_subr.h>
#include <machine/intr.h>
#include <arm/cpufunc.h>
@ -359,4 +361,91 @@ delay(n)
}
}
todr_chip_handle_t todr_handle;
/*
* todr_attach:
*
* Set the specified time-of-day register as the system real-time clock.
*/
void
todr_attach(todr_chip_handle_t todr)
{
if (todr_handle)
panic("todr_attach: rtc already configured");
todr_handle = todr;
}
/*
* inittodr:
*
* Initialize time from the time-of-day register.
*/
#define MINYEAR 2003 /* minimum plausible year */
void
inittodr(time_t base)
{
time_t deltat;
int badbase;
if (base < (MINYEAR - 1970) * SECYR) {
printf("WARNING: preposterous time in file system");
/* read the system clock anyway */
base = (MINYEAR - 1970) * SECYR;
badbase = 1;
} else
badbase = 0;
if (todr_handle == NULL ||
todr_gettime(todr_handle, (struct timeval *)&time) != 0 ||
time.tv_sec == 0) {
/*
* Believe the time in the file system for lack of
* anything better, resetting the TODR.
*/
time.tv_sec = base;
time.tv_usec = 0;
if (todr_handle != NULL && !badbase) {
printf("WARNING: preposterous clock chip time\n");
resettodr();
}
goto bad;
}
if (!badbase) {
/*
* See if we tained/lost two or more days; if
* so, assume something is amiss.
*/
deltat = time.tv_sec - base;
if (deltat < 0)
deltat = -deltat;
if (deltat < 2 * SECDAY)
return; /* all is well */
printf("WARNING: clock %s %ld days\n",
time.tv_sec < base ? "lost" : "gained",
(long)deltat / SECDAY);
}
bad:
printf("WARNING: CHECK AND RESET THE DATE!\n");
}
/*
* resettodr:
*
* Reset the time-of-day register with the current time.
*/
void
resettodr(void)
{
if (time.tv_sec == 0)
return;
if (todr_handle != NULL &&
todr_settime(todr_handle, (struct timeval *)&time) != 0)
printf("resettodr: failed to set time\n");
}
/* End of iomd_clock.c */

View File

@ -1,247 +0,0 @@
/* $NetBSD: iomd_iic.S,v 1.3 2001/11/23 16:53:07 thorpej Exp $ */
/*
* Copyright (c) 1994-1996 Mark Brinicombe.
* Copyright (c) 1994 Brini.
* All rights reserved.
*
* This code is derived from software written for Brini by Mark Brinicombe
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed by Mark Brinicombe.
* 4. The name of the company nor the name of the author may be used to
* endorse or promote products derived from this software without specific
* prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY BRINI ``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 BRINI 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.
*
* RiscBSD kernel project
*
* iic.s
*
* Low level routines to with IIC devices
*
* Created : 13/10/94
*
* Based of kate/display/iic.s
*/
#include "assym.h" /* for __PROG32 */
#include <machine/asm.h>
#include <machine/cpu.h>
#include <arm/iomd/iomdreg.h>
#define IIC_BITDELAY 10
Liomd_base:
.word _C_LABEL(iomd_base)
ENTRY(iic_set_state)
/*
* Parameters
* r0 - IIC data bit
* r1 - IIC clock bit
*/
/* Store temporary register */
/* stmfd sp!, {r4}*/
/*
* Mask the data and clock bits
* Since these routines are only called from iiccontrol.c this is not
* really needed
*/
and r0, r0, #0x00000001
and r1, r1, #0x00000001
/* Get address of IOMD control register */
ldr r2, Liomd_base
ldr r2, [r2]
/* Get the current CPSR */
/* mrs r4, cpsr_all
orr r3, r4, #(I32_bit | F32_bit)
msr cpsr_all, r3
*/
IRQdisable
/* Get current value of control register */
ldrb r3, [r2, #(IOMD_IOCR << 2)]
/* Preserve non-IIC bits */
bic r3, r3, #0x00000003
/* orr r3, r3, #0x000000c0*/
/* Set the IIC clock and data bits */
orr r3, r3, r0
orr r3, r3, r1, lsl #1
/* Store the new value of control register */
strb r3, [r2, #(IOMD_IOCR << 2)]
/* Restore CPSR state */
/* msr cpsr_all, r4 */
IRQenable
/* Restore temporary register */
/* ldmfd sp!, {r4} */
/* Pause a bit */
mov r0, #(IIC_BITDELAY)
/* Exit via iic_delay routine */
b _C_LABEL(iic_delay)
ENTRY(iic_set_state_and_ack)
/*
* Parameters
* r0 - IIC data bit
* r1 - IIC clock bit
*/
/* Store temporary register */
/* stmfd sp!, {r4} */
/*
* Mask the data and clock bits
* Since these routines are only called from iiccontrol.c this is not
* really needed
*/
and r0, r0, #0x00000001
and r1, r1, #0x00000001
/* Get address of IOMD control register */
ldr r2, Liomd_base
ldr r2, [r2]
/* Get the current CPSR */
/* mrs r4, cpsr_all
orr r3, r4, #(I32_bit | F32_bit)
msr cpsr_all, r3
*/
IRQdisable
/* Get current value of control register */
ldrb r3, [r2, #(IOMD_IOCR << 2)]
/* Preserve non-IIC bits */
bic r3, r3, #0x00000003
/* orr r3, r3, #0x000000c0*/
/* Set the IIC clock and data bits */
orr r3, r3, r0
orr r3, r3, r1, lsl #1
/* Store the new value of control register */
strb r3, [r2, #(IOMD_IOCR << 2)]
Liic_set_state_and_ack_loop:
ldrb r3, [r2, #(IOMD_IOCR << 2)]
tst r3, #0x00000002
beq Liic_set_state_and_ack_loop
/* Restore CPSR state */
/* msr cpsr_all, r4 */
IRQenable
/* Restore temporary register */
/* ldmfd sp!, {r4} */
/* Pause a bit */
mov r0, #(IIC_BITDELAY)
/* Exit via iic_delay routine */
b _C_LABEL(iic_delay)
ENTRY(iic_delay)
/*
* Parameters
* r0 - time to wait
*/
/* Load address of IOMD */
ldr r2, Liomd_base
ldr r2, [r2]
/* Latch current value of timer 1 */
strb r2, [r2, #(IOMD_T0LATCH << 2)]
/* Get the latched value */
ldrb r1, [r2, #(IOMD_T0LOW << 2)]
/* Loop until timer reaches end value */
Liic_delay_loop:
/* Latch the current value of timer1 */
strb r2, [r2, #(IOMD_T0LATCH << 2)]
/* Get the latched value */
ldrb r3, [r2, #(IOMD_T0LOW << 2)]
/* Loop until timer reached expected value */
teq r3, r1
movne r1, r3
beq Liic_delay_loop
subs r0, r0, #0x00000001
bne Liic_delay_loop
/* Exit */
mov pc, lr
ENTRY(iic_getstate)
/* Load address of IOMD */
ldr r2, Liomd_base
ldr r2, [r2]
/* Read IOCR */
ldrb r0, [r2, #(IOMD_IOCR << 2)]
mov pc, lr
/* End of iomd_iic.S */

232
sys/arch/arm/iomd/iomdiic.c Normal file
View File

@ -0,0 +1,232 @@
/* $NetBSD: iomdiic.c,v 1.1 2003/10/06 16:11:19 thorpej Exp $ */
/*
* Copyright (c) 2003 Wasabi Systems, Inc.
* All rights reserved.
*
* Written by Jason R. Thorpe for Wasabi Systems, Inc.
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed for the NetBSD Project by
* Wasabi Systems, Inc.
* 4. The name of Wasabi Systems, Inc. may not be used to endorse
* or promote products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY WASABI SYSTEMS, INC. ``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 WASABI SYSTEMS, INC
* 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.
*/
#include <sys/param.h>
#include <sys/device.h>
#include <sys/kernel.h>
#include <sys/systm.h>
#include <sys/lock.h>
#include <machine/bus.h>
#include <machine/cpu.h>
#include <arm/iomd/iomdreg.h>
#include <arm/iomd/iomdvar.h>
#include <dev/i2c/i2cvar.h>
#include <dev/i2c/i2c_bitbang.h>
#include <arm/iomd/iomdiicvar.h>
struct iomdiic_softc {
struct device sc_dev;
bus_space_tag_t sc_st;
bus_space_handle_t sc_sh;
struct i2c_controller sc_i2c;
struct lock sc_buslock;
/*
* The SDA pin is open-drain, so we make it an input by
* writing a 1 to it.
*/
uint8_t sc_iomd_iocr;
};
static int iomdiic_acquire_bus(void *, int);
static void iomdiic_release_bus(void *, int);
static int iomdiic_send_start(void *, int);
static int iomdiic_send_stop(void *, int);
static int iomdiic_initiate_xfer(void *, i2c_addr_t, int);
static int iomdiic_read_byte(void *, uint8_t *, int);
static int iomdiic_write_byte(void *, uint8_t, int);
#define IOMDIIC_READ *(__volatile uint8_t *)(IOMD_ADDRESS(IOMD_IOCR))
#define IOMDIIC_WRITE(x) *(__volatile uint8_t *)(IOMD_ADDRESS(IOMD_IOCR)) = (x)
#define IOMD_IOCR_SDA 0x01
#define IOMD_IOCR_SCL 0x02
static void
iomdiic_bb_set_bits(void *cookie, uint32_t bits)
{
struct iomdiic_softc *sc = cookie;
IOMDIIC_WRITE((IOMDIIC_READ & ~(IOMD_IOCR_SDA|IOMD_IOCR_SCL)) |
sc->sc_iomd_iocr | bits);
}
static void
iomdiic_bb_set_dir(void *cookie, uint32_t bits)
{
struct iomdiic_softc *sc = cookie;
sc->sc_iomd_iocr = bits;
}
static uint32_t
iomdiic_bb_read_bits(void *cookie)
{
return (IOMDIIC_READ);
}
static const struct i2c_bitbang_ops iomdiic_bbops = {
iomdiic_bb_set_bits,
iomdiic_bb_set_dir,
iomdiic_bb_read_bits,
{
IOMD_IOCR_SDA, /* SDA */
IOMD_IOCR_SCL, /* SCL */
0, /* SDA is output */
IOMD_IOCR_SDA, /* SDA is input */
}
};
static int
iomdiic_match(struct device *parent, struct cfdata *cf, void *aux)
{
return (1);
}
static void
iomdiic_attach(struct device *parent, struct device *self, void *aux)
{
struct iomdiic_softc *sc = (void *) self;
struct i2cbus_attach_args iba;
printf("\n");
lockinit(&sc->sc_buslock, PRIBIO|PCATCH, "iomdiiclk", 0, 0);
sc->sc_i2c.ic_cookie = sc;
sc->sc_i2c.ic_acquire_bus = iomdiic_acquire_bus;
sc->sc_i2c.ic_release_bus = iomdiic_release_bus;
sc->sc_i2c.ic_send_start = iomdiic_send_start;
sc->sc_i2c.ic_send_stop = iomdiic_send_stop;
sc->sc_i2c.ic_initiate_xfer = iomdiic_initiate_xfer;
sc->sc_i2c.ic_read_byte = iomdiic_read_byte;
sc->sc_i2c.ic_write_byte = iomdiic_write_byte;
iba.iba_name = "iic";
iba.iba_tag = &sc->sc_i2c;
(void) config_found(&sc->sc_dev, &iba, iicbus_print);
}
CFATTACH_DECL(iomdiic, sizeof(struct iomdiic_softc),
iomdiic_match, iomdiic_attach, NULL, NULL);
i2c_tag_t
iomdiic_bootstrap_cookie(void)
{
static struct iomdiic_softc sc;
/* XXX Yuck. */
strcpy(sc.sc_dev.dv_xname, "iomdiicboot");
sc.sc_i2c.ic_cookie = &sc;
sc.sc_i2c.ic_acquire_bus = iomdiic_acquire_bus;
sc.sc_i2c.ic_release_bus = iomdiic_release_bus;
sc.sc_i2c.ic_send_start = iomdiic_send_start;
sc.sc_i2c.ic_send_stop = iomdiic_send_stop;
sc.sc_i2c.ic_initiate_xfer = iomdiic_initiate_xfer;
sc.sc_i2c.ic_read_byte = iomdiic_read_byte;
sc.sc_i2c.ic_write_byte = iomdiic_write_byte;
return ((void *) &sc.sc_i2c);
}
static int
iomdiic_acquire_bus(void *cookie, int flags)
{
struct iomdiic_softc *sc = cookie;
/* XXX What should we do for the polling case? */
if (flags & I2C_F_POLL)
return (0);
return (lockmgr(&sc->sc_buslock, LK_EXCLUSIVE, NULL));
}
static void
iomdiic_release_bus(void *cookie, int flags)
{
struct iomdiic_softc *sc = cookie;
/* XXX See above. */
if (flags & I2C_F_POLL)
return;
(void) lockmgr(&sc->sc_buslock, LK_RELEASE, NULL);
}
static int
iomdiic_send_start(void *cookie, int flags)
{
return (i2c_bitbang_send_start(cookie, flags, &iomdiic_bbops));
}
static int
iomdiic_send_stop(void *cookie, int flags)
{
return (i2c_bitbang_send_stop(cookie, flags, &iomdiic_bbops));
}
static int
iomdiic_initiate_xfer(void *cookie, i2c_addr_t addr, int flags)
{
return (i2c_bitbang_initiate_xfer(cookie, addr, flags, &iomdiic_bbops));
}
static int
iomdiic_read_byte(void *cookie, uint8_t *bytep, int flags)
{
return (i2c_bitbang_read_byte(cookie, bytep, flags, &iomdiic_bbops));
}
static int
iomdiic_write_byte(void *cookie, uint8_t byte, int flags)
{
return (i2c_bitbang_write_byte(cookie, byte, flags, &iomdiic_bbops));
}

View File

@ -0,0 +1,44 @@
/* $NetBSD: iomdiicvar.h,v 1.1 2003/10/06 16:11:19 thorpej Exp $ */
/*
* Copyright (c) 2003 Wasabi Systems, Inc.
* All rights reserved.
*
* Written by Jason R. Thorpe for Wasabi Systems, Inc.
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed for the NetBSD Project by
* Wasabi Systems, Inc.
* 4. The name of Wasabi Systems, Inc. may not be used to endorse
* or promote products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY WASABI SYSTEMS, INC. ``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 WASABI SYSTEMS, INC
* 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 _ARM_IOMD_IOMDIICVAR_H_
#define _ARM_IOMD_IOMDIICVAR_H_
/* For use during bootstrap. */
i2c_tag_t iomdiic_bootstrap_cookie(void);
#endif /* _ARM_IOMD_IOMDIICVAR_H_ */

View File

@ -1,491 +0,0 @@
/* $NetBSD: rtc.c,v 1.11 2003/07/15 00:24:46 lukem Exp $ */
/*
* Copyright (c) 1994-1996 Mark Brinicombe.
* Copyright (c) 1994 Brini.
* All rights reserved.
*
* This code is derived from software written for Brini by Mark Brinicombe
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed by Brini.
* 4. The name of the company nor the name of the author may be used to
* endorse or promote products derived from this software without specific
* prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY BRINI ``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 BRINI 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.
*
* RiscBSD kernel project
*
* rtc.c
*
* Routines to read and write the RTC and CMOS RAM
*
* Created : 13/10/94
* Updated : 15/07/2000 DD
*/
#include <sys/cdefs.h>
__KERNEL_RCSID(0, "$NetBSD: rtc.c,v 1.11 2003/07/15 00:24:46 lukem Exp $");
#include <sys/param.h>
#include <sys/systm.h>
#include <sys/kernel.h>
#include <sys/conf.h>
#include <sys/malloc.h>
#include <sys/device.h>
#include <sys/event.h>
#include <machine/rtc.h>
#include <arm/iomd/iic.h>
#include <arm/iomd/todclockvar.h>
struct rtc_softc {
struct device sc_dev;
int sc_flags;
#define RTC_BROKEN 1
#define RTC_OPEN 2
};
void rtcattach __P((struct device *parent, struct device *self, void *aux));
int rtcmatch __P((struct device *parent, struct cfdata *cf, void *aux));
int rtc_read __P((void *, rtc_t *));
int rtc_write __P((void *, rtc_t *));
static __inline int hexdectodec __P((u_char));
static __inline int dectohexdec __P((u_char));
static int twodigits __P((char *, int));
/* Read a byte from CMOS RAM */
int
cmos_read(location)
int location;
{
u_char buff;
/*
* This commented code dates from when I was translating CMOS address
* from the RISCOS addresses. Now all addresses are specified as
* actual addresses in the CMOS RAM
*/
/*
if (location > 0xF0)
return(-1);
if (location < 0xC0)
buff = location + 0x40;
else
buff = location - 0xB0;
*/
buff = location;
if (iic_control(RTC_Write, &buff, 1))
return(-1);
if (iic_control(RTC_Read, &buff, 1))
return(-1);
return(buff);
}
/* Write a byte to CMOS RAM */
int
cmos_write(location, value)
int location;
int value;
{
u_char buff[2];
int oldvalue, oldsum;
/*
* This commented code dates from when I was translating CMOS address
* from the RISCOS addresses. Now all addresses are specified as
* actual addresses in the CMOS RAM
*/
/* if (location > 0xF0)
return(-1);
if (location < 0xC0)
buff = location + 0x40;
else
buff = location - 0xB0;
*/
buff[0] = location;
buff[1] = value;
/* Read the old CMOS location value and old checksum */
oldvalue = cmos_read(location);
if (oldvalue<0)
return(-1);
oldsum = cmos_read(RTC_ADDR_CHECKSUM);
if (oldsum<0)
return(-1);
if (iic_control(RTC_Write, buff, 2))
return(-1);
/* Now update the checksum. This code only modifies the value. It does */
/* not recalculate it */
buff[0] = RTC_ADDR_CHECKSUM;
buff[1] = oldsum - oldvalue + value;
if (iic_control(RTC_Write, buff, 2))
return(-1);
return(0);
}
/* Hex to BCD and BCD to hex conversion routines */
static __inline int
hexdectodec(n)
u_char n;
{
return(((n >> 4) & 0x0F) * 10 + (n & 0x0F));
}
static __inline int
dectohexdec(n)
u_char n;
{
return(((n / 10) << 4) + (n % 10));
}
/* Write the RTC data from an 8 byte buffer */
int
rtc_write(arg, rtc)
void *arg;
rtc_t *rtc;
{
u_char buff[8];
buff[0] = 1;
buff[1] = dectohexdec(rtc->rtc_centi);
buff[2] = dectohexdec(rtc->rtc_sec);
buff[3] = dectohexdec(rtc->rtc_min);
buff[4] = dectohexdec(rtc->rtc_hour) & 0x3f;
buff[5] = dectohexdec(rtc->rtc_day) | ((rtc->rtc_year & 3) << 6);
buff[6] = dectohexdec(rtc->rtc_mon);
if (iic_control(RTC_Write, buff, 7))
return(0);
if (cmos_write(RTC_ADDR_YEAR, rtc->rtc_year))
return(0);
if (cmos_write(RTC_ADDR_CENT, rtc->rtc_cen))
return(0);
return(1);
}
/* Read the RTC data into a 8 byte buffer */
int
rtc_read(arg, rtc)
void *arg;
rtc_t *rtc;
{
u_char buff[8];
int byte;
buff[0] = 0;
if (iic_control(RTC_Write, buff, 1))
return(0);
if (iic_control(RTC_Read, buff, 8))
return(0);
rtc->rtc_micro = 0;
rtc->rtc_centi = hexdectodec(buff[1] & 0xff);
rtc->rtc_sec = hexdectodec(buff[2] & 0x7f);
rtc->rtc_min = hexdectodec(buff[3] & 0x7f);
rtc->rtc_hour = hexdectodec(buff[4] & 0x3f);
/* If in 12 hour mode need to look at the AM/PM flag */
if (buff[4] & 0x80)
rtc->rtc_hour += (buff[4] & 0x40) ? 12 : 0;
rtc->rtc_day = hexdectodec(buff[5] & 0x3f);
rtc->rtc_mon = hexdectodec(buff[6] & 0x1f);
byte = cmos_read(RTC_ADDR_YEAR);
if (byte == -1)
return(0);
rtc->rtc_year = byte;
byte = cmos_read(RTC_ADDR_CENT);
if (byte == -1)
return(0);
rtc->rtc_cen = byte;
return(1);
}
/* device and attach structures */
CFATTACH_DECL(rtc, sizeof(struct rtc_softc),
rtcmatch, rtcattach, NULL, NULL);
extern struct cfdriver rtc_cd;
dev_type_open(rtcopen);
dev_type_close(rtcclose);
dev_type_read(rtcread);
dev_type_write(rtcwrite);
const struct cdevsw rtc_cdevsw = {
rtcopen, rtcclose, rtcread, rtcwrite, noioctl,
nostop, notty, nopoll, nommap, nokqfilter,
};
/*
* rtcmatch()
*
* Validate the IIC address to make sure its an RTC we understand
*/
int
rtcmatch(parent, cf, aux)
struct device *parent;
struct cfdata *cf;
void *aux;
{
struct iicbus_attach_args *ib = aux;
if ((ib->ib_addr & IIC_PCF8583_MASK) == IIC_PCF8583_ADDR)
return(1);
return(0);
}
/*
* rtcattach()
*
* Attach the rtc device
*/
void
rtcattach(parent, self, aux)
struct device *parent;
struct device *self;
void *aux;
{
struct rtc_softc *sc = (struct rtc_softc *)self;
struct iicbus_attach_args *ib = aux;
u_char buff[1];
struct todclock_attach_args ta;
sc->sc_flags |= RTC_BROKEN;
if ((ib->ib_addr & IIC_PCF8583_MASK) == IIC_PCF8583_ADDR) {
printf(": PCF8583");
/* Read RTC register 0 and report info found */
buff[0] = 0;
if (iic_control(RTC_Write, buff, 1))
return;
if (iic_control(RTC_Read, buff, 1))
return;
printf(" clock base ");
switch (buff[0] & 0x30) {
case 0x00:
printf("32.768KHz");
break;
case 0x10:
printf("50Hz");
break;
case 0x20:
printf("event");
break;
case 0x30:
printf("test mode");
break;
}
if (buff[0] & 0x80)
printf(" stopped");
if (buff[0] & 0x04)
printf(" alarm enabled");
sc->sc_flags &= ~RTC_BROKEN;
}
printf("\n");
ta.ta_name = "todclock";
ta.ta_rtc_arg = NULL;
ta.ta_rtc_write = rtc_write;
ta.ta_rtc_read = rtc_read;
ta.ta_flags = 0;
config_found(self, &ta, NULL);
}
int
rtcopen(dev, flag, mode, p)
dev_t dev;
int flag;
int mode;
struct proc *p;
{
struct rtc_softc *sc;
int unit = minor(dev);
if (unit >= rtc_cd.cd_ndevs)
return(ENXIO);
sc = rtc_cd.cd_devs[unit];
if (!sc) return(ENXIO);
if (sc->sc_flags & RTC_BROKEN) return(ENXIO);
if (sc->sc_flags & RTC_OPEN) return(EBUSY);
sc->sc_flags |= RTC_OPEN;
return(0);
}
int
rtcclose(dev, flag, mode, p)
dev_t dev;
int flag;
int mode;
struct proc *p;
{
int unit = minor(dev);
struct rtc_softc *sc = rtc_cd.cd_devs[unit];
sc->sc_flags &= ~RTC_OPEN;
return(0);
}
int
rtcread(dev, uio, flag)
dev_t dev;
struct uio *uio;
int flag;
{
rtc_t rtc;
int s;
char buffer[32];
int length;
s = splclock();
if (rtc_read(NULL, &rtc) == 0) {
(void)splx(s);
return(ENXIO);
}
(void)splx(s);
sprintf(buffer, "%02d:%02d:%02d.%02d%02d %02d/%02d/%02d%02d\n",
rtc.rtc_hour, rtc.rtc_min, rtc.rtc_sec, rtc.rtc_centi,
rtc.rtc_micro, rtc.rtc_day, rtc.rtc_mon, rtc.rtc_cen,
rtc.rtc_year);
if (uio->uio_offset > strlen(buffer))
return 0;
length = strlen(buffer) - uio->uio_offset;
if (length > uio->uio_resid)
length = uio->uio_resid;
return(uiomove((caddr_t)buffer, length, uio));
}
static int
twodigits(buffer, pos)
char *buffer;
int pos;
{
int result = 0;
if (buffer[pos] >= '0' && buffer[pos] <= '9')
result = (buffer[pos] - '0') * 10;
if (buffer[pos+1] >= '0' && buffer[pos+1] <= '9')
result += (buffer[pos+1] - '0');
return(result);
}
int
rtcwrite(dev, uio, flag)
dev_t dev;
struct uio *uio;
int flag;
{
rtc_t rtc;
int s;
char buffer[25];
int length;
int error;
/*
* We require atomic updates!
*/
length = uio->uio_resid;
if (uio->uio_offset || (length != sizeof(buffer)
&& length != sizeof(buffer - 1)))
return(EINVAL);
if ((error = uiomove((caddr_t)buffer, sizeof(buffer), uio)))
return(error);
if (length == sizeof(buffer) && buffer[sizeof(buffer) - 1] != '\n')
return(EINVAL);
printf("rtcwrite: %s\n", buffer);
rtc.rtc_micro = 0;
rtc.rtc_centi = twodigits(buffer, 9);
rtc.rtc_sec = twodigits(buffer, 6);
rtc.rtc_min = twodigits(buffer, 3);
rtc.rtc_hour = twodigits(buffer, 0);
rtc.rtc_day = twodigits(buffer, 14);
rtc.rtc_mon = twodigits(buffer, 17);
rtc.rtc_year = twodigits(buffer, 22);
rtc.rtc_cen = twodigits(buffer, 20);
s = splclock();
rtc_write(NULL, &rtc);
(void)splx(s);
return(0);
}
/* End of rtc.c */

View File

@ -1,333 +0,0 @@
/* $NetBSD: todclock.c,v 1.7 2002/10/02 15:45:13 thorpej Exp $ */
/*
* Copyright (c) 1994-1997 Mark Brinicombe.
* Copyright (c) 1994 Brini.
* All rights reserved.
*
* This code is derived from software written for Brini by Mark Brinicombe
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed by Mark Brinicombe.
* 4. The name of the company nor the name of the author may be used to
* endorse or promote products derived from this software without specific
* prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
* RiscBSD kernel project
*
* clock.c
*
* Timer related machine specific code
*
* Created : 29/09/94
*/
/* Include header files */
#include <sys/param.h>
__KERNEL_RCSID(0, "$NetBSD: todclock.c,v 1.7 2002/10/02 15:45:13 thorpej Exp $");
#include <sys/systm.h>
#include <sys/kernel.h>
#include <sys/time.h>
#include <sys/device.h>
#include <machine/rtc.h>
#include <arm/iomd/todclockvar.h>
#include "todclock.h"
#if NTODCLOCK > 1
#error "Can only have 1 todclock device"
#endif
/*
* softc structure for the todclock device
*/
struct todclock_softc {
struct device sc_dev; /* device node */
void *sc_rtc_arg; /* arg to read/write */
int (*sc_rtc_write) __P((void *, rtc_t *)); /* rtc write function */
int (*sc_rtc_read) __P((void *, rtc_t *)); /* rtc read function */
};
/* prototypes for functions */
static void todclockattach __P((struct device *parent, struct device *self,
void *aux));
static int todclockmatch __P((struct device *parent, struct cfdata *cf,
void *aux));
static __inline int yeartoday __P((int));
/*
* We need to remember our softc for functions like inittodr()
* and resettodr()
* since we only ever have one time-of-day device we can just store
* the direct pointer to softc.
*/
static struct todclock_softc *todclock_sc = NULL;
/* driver and attach structures */
CFATTACH_DECL(todclock, sizeof(struct todclock_softc),
todclockmatch, todclockattach, NULL, NULL);
/*
* int todclockmatch(struct device *parent, struct cfdata *cf, void *aux)
*
* todclock device probe function.
* just validate the attach args
*/
int
todclockmatch(parent, cf, aux)
struct device *parent;
struct cfdata *cf;
void *aux;
{
struct todclock_attach_args *ta = aux;
if (todclock_sc != NULL)
return(0);
if (strcmp(ta->ta_name, "todclock") != 0)
return(0);
if (ta->ta_flags & TODCLOCK_FLAG_FAKE)
return(1);
return(2);
}
/*
* void todclockattach(struct device *parent, struct device *self, void *aux)
*
* todclock device attach function.
* Initialise the softc structure and do a search for children
*/
void
todclockattach(parent, self, aux)
struct device *parent;
struct device *self;
void *aux;
{
struct todclock_softc *sc = (void *)self;
struct todclock_attach_args *ta = aux;
/* set up our softc */
todclock_sc = sc;
todclock_sc->sc_rtc_arg = ta->ta_rtc_arg;
todclock_sc->sc_rtc_write = ta->ta_rtc_write;
todclock_sc->sc_rtc_read = ta->ta_rtc_read;
printf("\n");
/*
* Initialise the time of day register.
* This is normally left to the filing system to do but not all
* filing systems call it e.g. cd9660
*/
inittodr(0);
}
static __inline int
yeartoday(year)
int year;
{
return((year % 4) ? 365 : 366);
}
static int month[12] = {31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31};
static int timeset = 0;
#define SECPERDAY (24*60*60)
#define SECPERNYEAR (365*SECPERDAY)
#define SECPER4YEARS (4*SECPERNYEAR+SECPERDAY)
#define EPOCHYEAR 1970
/*
* Globally visable functions
*
* These functions are used from other parts of the kernel.
* These functions use the functions defined in the tod_sc
* to actually read and write the rtc.
*
* The first todclock to be attached will be used for handling
* the time of day.
*/
/*
* Write back the time of day to the rtc
*/
void
resettodr()
{
int s;
time_t year, mon, day, hour, min, sec;
rtc_t rtc;
/* Have we set the system time in inittodr() */
if (!timeset)
return;
/* We need a todclock device and should always have one */
if (!todclock_sc)
return;
/* Abort early if there is not actually an RTC write routine */
if (todclock_sc->sc_rtc_write == NULL)
return;
sec = time.tv_sec;
sec -= rtc_offset * 60;
year = (sec / SECPER4YEARS) * 4;
sec %= SECPER4YEARS;
/* year now hold the number of years rounded down 4 */
while (sec > (yeartoday(EPOCHYEAR+year) * SECPERDAY)) {
sec -= yeartoday(EPOCHYEAR+year)*SECPERDAY;
year++;
}
/* year is now a correct offset from the EPOCHYEAR */
year+=EPOCHYEAR;
mon=0;
if (yeartoday(year) == 366)
month[1]=29;
else
month[1]=28;
while (sec >= month[mon]*SECPERDAY) {
sec -= month[mon]*SECPERDAY;
mon++;
}
day = sec / SECPERDAY;
sec %= SECPERDAY;
hour = sec / 3600;
sec %= 3600;
min = sec / 60;
sec %= 60;
rtc.rtc_cen = year / 100;
rtc.rtc_year = year % 100;
rtc.rtc_mon = mon+1;
rtc.rtc_day = day+1;
rtc.rtc_hour = hour;
rtc.rtc_min = min;
rtc.rtc_sec = sec;
rtc.rtc_centi =
rtc.rtc_micro = 0;
s = splclock();
todclock_sc->sc_rtc_write(todclock_sc->sc_rtc_arg, &rtc);
(void)splx(s);
}
/*
* Initialise the time of day register, based on the time base which is, e.g.
* from a filesystem.
*/
void
inittodr(base)
time_t base;
{
time_t n;
int i, days = 0;
int s;
int year;
rtc_t rtc;
/*
* Default to the suggested time but replace that we one from an
* RTC is we can.
*/
/* Use the suggested time as a fall back */
time.tv_sec = base;
time.tv_usec = 0;
/* Can we read an RTC ? */
if (todclock_sc != NULL && todclock_sc->sc_rtc_read) {
s = splclock();
if (todclock_sc->sc_rtc_read(todclock_sc->sc_rtc_arg, &rtc) == 0) {
(void)splx(s);
return;
}
(void)splx(s);
} else
return;
/* Convert the rtc time into seconds */
n = rtc.rtc_sec + 60 * rtc.rtc_min + 3600 * rtc.rtc_hour;
n += (rtc.rtc_day - 1) * 3600 * 24;
year = (rtc.rtc_year + rtc.rtc_cen * 100) - 1900;
if (yeartoday(year) == 366)
month[1] = 29;
for (i = rtc.rtc_mon - 2; i >= 0; i--)
days += month[i];
month[1] = 28;
for (i = 70; i < year; i++)
days += yeartoday(i);
n += days * 3600 * 24;
n += rtc_offset * 60;
time.tv_sec = n;
time.tv_usec = 0;
/* timeset is used to ensure the time is valid before a resettodr() */
timeset = 1;
/* If the base was 0 then keep quiet */
if (base) {
printf("inittodr: %02d:%02d:%02d.%02d%02d %02d/%02d/%02d%02d\n",
rtc.rtc_hour, rtc.rtc_min, rtc.rtc_sec, rtc.rtc_centi,
rtc.rtc_micro, rtc.rtc_day, rtc.rtc_mon, rtc.rtc_cen,
rtc.rtc_year);
if (n > base + 60) {
days = (n - base) / SECPERDAY;
printf("Clock has gained %d day%c %ld hours %ld minutes %ld secs\n",
days, ((days == 1) ? 0 : 's'),
(long)((n - base) / 3600) % 24,
(long)((n - base) / 60) % 60,
(long) (n - base) % 60);
}
}
}
/* End of todclock.c */

View File

@ -1,55 +0,0 @@
/* $NetBSD: todclockvar.h,v 1.1 2001/10/05 22:27:42 reinoud Exp $ */
/*
* Copyright (c) 1997 Mark Brinicombe.
* Copyright (c) 1997 Causality Limited
* All rights reserved.
*
* 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. All advertising materials mentioning features or use of this software
* must display the following acknowledgement:
* This product includes software developed by Mark Brinicombe
* 4. The name of the company nor the name of the author may be used to
* endorse or promote products derived from this software without specific
* prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
* todclockvar.h
*
* structures and variables for the todclock device
*
* Created : 12/02/97
*/
/*
* Attach args for todclock device
*/
struct todclock_attach_args {
const char *ta_name; /* device name */
void *ta_rtc_arg; /* arg to read/write */
int (*ta_rtc_write) __P((void *, rtc_t *)); /* function to write rtc */
int (*ta_rtc_read) __P((void *, rtc_t *)); /* function to read rtc */
int ta_flags; /* flags */
#define TODCLOCK_FLAG_FAKE 0x01 /* tod service is faked */
};
/* End of todclockvar.h */