Commit 17e0fc6d authored by Alessandro Rubini's avatar Alessandro Rubini

Merge branch 'fan_speed_adjust' into v3-rc2

parents 5409bf4a da816b7a
# Trivial makefile for 2.6 modules
#LINUX ?= /lib/modules/$(shell uname -r)/build
obj-m = at91_softpwm.o
at91_softpwm-objs := fiq-asm.o fiq-at91sam92.o fiq-module.o softpwm_core.o
all:
$(MAKE) -C $(LINUX) M=$(shell /bin/pwd) modules
clean:
$(MAKE) -C $(LINUX) clean M=$(shell /bin/pwd)
rm -f Module.symvers modules.order *~
# $(MAKE) -C doc terse
#ifndef __AT91_SOFTPWM_H
#define __AT91_SOFTPWM_H
#define __AT91_SOFTPWM_IOC_MAGIC '5'
#define AT91_SOFTPWM_ENABLE _IO(__AT91_SOFTPWM_IOC_MAGIC, 4)
#define AT91_SOFTPWM_DISABLE _IO(__AT91_SOFTPWM_IOC_MAGIC, 5)
#define AT91_SOFTPWM_SETPOINT _IO(__AT91_SOFTPWM_IOC_MAGIC, 6)
#endif /*__AT91_SOFTPWM_H*/
/*
* Alessandro Rubini, 2007, GPL 2 or later
*
* This file implements entry/exit from the fiq handler.
* It must save r0..r8 (since R8 is used to preserve LR in the few lines
* I added in kernel code, before calling this with "bl").
*/
.globl fiq_entry
.type fiq_entry, #function
/* here, we can use r10..r13 to our pleasure */
fiq_entry:
ldr r11, fiq_handler
movs r11, r11
moveq pc, lr /* nobody registered, return */
/* count the fiq: it doesn't cost too much cpu time */
ldr r10, fiqcount
add r10, r10, #1
str r10, fiqcount
/* save all registers, build sp and branch to C */
adr r9, regpool
stmia r9, {r0 - r8, lr}
adr sp, fiq_sp
ldr sp, [sp]
mov lr, pc
mov pc, r11
adr r9, regpool
ldmia r9, {r0 - r8, pc}
/* data words*/
.globl fiqcount
fiqcount: .long 0
fiq_sp: .long fiq_stack+1020
/* The pointer */
.globl fiq_handler
fiq_handler:
.long 0
regpool:
.space 40 /* 10 registers */
.pool
.align 5
fiq_stack:
.space 1024
/* cpu-specific code for Atmel 92xx timers (actually, only 9263 as it is) */
#include <linux/module.h>
#include <linux/interrupt.h>
#include <asm/io.h>
#include <mach/hardware.h>
#include <mach/at91_aic.h>
#include <mach/at91_pmc.h>
#include <mach/at91_tc.h>
#include "fiq-engine.h"
#include "fiq-at91sam92.h"
static int fiq_irqnr;
/* The following are called from the cpu-independent source file */
int __fiq_register(void (*handler)(void), int irq)
{
int ret;
if (irq < FIQ_IRQ_MIN || irq > FIQ_IRQ_MAX) {
printk(KERN_WARNING "at91-fiq: irq %i not in valid range (%i-%i)\n",
irq, FIQ_IRQ_MIN, FIQ_IRQ_MAX);
return -EINVAL;
}
fiq_irqnr = irq; /* save it for ack and so on */
/* clock the peripheral */
at91_sys_write(AT91_PMC_PCER, 1 << fiq_irqnr);
fiq_handler = handler; /* used both from fiq and non-fiq */
/* request the irq in any case, only turn it to fiq as needed */
ret = request_irq(irq, fake_fiq_handler, IRQF_DISABLED,
"fake-fiq", &fiq_handler);
if (ret) {
printk(KERN_WARNING "at91-fiq: can't request irq %i\n", irq);
return ret;
}
if (fiq_use_fiq) {
at91_sys_write(AT91_AIC_FFER, 1 << fiq_irqnr);
}
return 0;
}
void __fiq_unregister(void (*handler)(void), int irq)
{
if (fiq_use_fiq) {
at91_sys_write(AT91_AIC_FFDR, 1 << fiq_irqnr);
}
free_irq(irq, &fiq_handler);
fiq_handler = NULL;
}
#ifndef __FIQ_AT91SAM92_H__
#define __FIQ_AT91SAM92_H__
/* defines for atmel 926x */
#include <mach/gpio.h>
#include <mach/at91_tc.h>
/*
* We have different setups for each of the three processors.
* This is mainly because of different names, but also because the 9263 differs
*/
#ifdef CONFIG_ARCH_AT91SAM9G45 /* one interrupt for tc block; use TC0 */
/* Limits we support */
# define FIQ_IRQ_MIN AT91SAM9G45_ID_TCB
# define FIQ_IRQ_MAX AT91SAM9G45_ID_TCB
/* Choices we make */
# define FIQ_IRQNR AT91SAM9G45_ID_TCB
# define FIQ_BASE AT91SAM9G45_BASE_TC0
#endif
#ifdef CONFIG_ARCH_AT91SAM9263 /* one interrupt for tc block; use TC0 */
/* Limits we support */
# define FIQ_IRQ_MIN AT91SAM9263_ID_TCB
# define FIQ_IRQ_MAX AT91SAM9263_ID_TCB
/* Choices we make */
# define FIQ_IRQNR AT91SAM9263_ID_TCB
# define FIQ_BASE AT91SAM9263_BASE_TC0
# define FIQ_BITNR AT91_PIN_PB20
#endif
#ifdef CONFIG_ARCH_AT91SAM9260 /* Use TC0 but any of TC0-TC2 can work */
/* Limits we support */
# define FIQ_IRQ_MIN AT91SAM9260_ID_TC0
# define FIQ_IRQ_MAX AT91SAM9260_ID_TC2
/* Choices we make */
# define FIQ_IRQNR AT91SAM9260_ID_TC0
# define FIQ_BASE AT91SAM9260_BASE_TC0
# define FIQ_BITNR AT91_PIN_PB20
#endif
#ifdef CONFIG_ARCH_AT91SAM9261 /* Use TC0 but any of TC0-TC2 can work */
/* Limits we support */
# define FIQ_IRQ_MIN AT91SAM9261_ID_TC0
# define FIQ_IRQ_MAX AT91SAM9261_ID_TC2
/* Choices we make */
# define FIQ_IRQNR AT91SAM9261_ID_TC0
# define FIQ_BASE AT91SAM9261_BASE_TC0
# define FIQ_BITNR AT91_PIN_PA20 /* very few pins are available */
#endif
#define FIQ_MHZ 3 /* timer clock runs at 99.328MHz/32 = 3.104MHz */
#define FIQ_TASK_CONVERT 1000, 3104 /* sysctl-stamp, used in fiq-task.c */
extern void *__fiq_timer_base; /* for register access to the timer */
/* how to get a time stamp (counts, not usec). This cpu counts up */
#define __GETSTAMP() __raw_readl(__fiq_timer_base + AT91_TC_CV)
static inline void __fiq_ack(void)
{
/* read status register */
static int foo;
foo = __raw_readl( __fiq_timer_base + AT91_TC_SR);
}
static inline void __fiq_sched_next_irq(int usec)
{
__raw_writel(usec * FIQ_MHZ, __fiq_timer_base + AT91_TC_RC);
}
/* This is not needed for the fiq engine, but our example task wants it */
#define __fiq_set_gpio_value(a,b) at91_set_gpio_value(a, b);
#endif /* __FIQ_AT91SAM92_H__ */
#ifndef __FIQ_ENGINE_H__
#define __FIQ_ENGINE_H__
#include <linux/irqreturn.h>
/* include cpu-specific defines to customize use */
#if defined(CONFIG_ARCH_AT91)
# include "fiq-at91sam92.h"
#elif defined(CONFIG_ARCH_PXA)
# include "fiq-pxa.h"
#elif defined(CONFIG_ARCH_OMAP3)
# include "fiq-omap3.h"
#else
# error "This package has no support for your architecture"
#endif
/* exported by the kernel (our patch) */
extern void (*fiq_userptr)(void);
/* declared in fiq-asm.S */
extern void fiq_entry(void);
extern unsigned long fiqcount;
extern void (*fiq_handler)(void);
/* declared in fiq-module.c */
extern irqreturn_t fake_fiq_handler(int irq, void *dev);
extern int fiq_verbose;
extern int fiq_use_fiq; /* false by default */
extern int fiq_register(void (*handler)(void), int irq);
extern int fiq_unregister(void (*handler)(void), int irq);
/* declared in the cpu-specific source file */
extern int __fiq_register(void (*handler)(void), int irq);
extern void __fiq_unregister(void (*handler)(void), int irq);
#endif /* __FIQ_ENGINE_H__ */
/*
* Fast-interrupt infrastructure for a real-time task.
* Alessandro Rubini, 2007,2008 GPL 2 or later.
* This code is generic, you must supplement it with cpu-specific code
* in another source file.
*/
#include <linux/module.h>
#include <linux/init.h>
#include <linux/kernel.h>
#include <linux/timer.h>
#include <linux/interrupt.h>
#include <asm/io.h>
#include "fiq-engine.h"
int fiq_use_fiq;
EXPORT_SYMBOL(fiq_use_fiq);
int fiq_verbose;
/*
* High-level interface (cpu-independent)
*/
/* An irq handler, faking fiq, to test with fiq=0 */
irqreturn_t fake_fiq_handler(int irq, void *dev)
{
(*fiq_handler)();
return IRQ_HANDLED;
}
/* Software PWM emulation for AT91SAM9xxx MCUs. Relies on Alessandro's fiq-engine.
Licensed under GPL v2 (c) T.W. 2012
*/
#include <linux/module.h>
#include <linux/moduleparam.h>
#include <linux/init.h>
#include <linux/ioctl.h>
#include <linux/interrupt.h>
#include <linux/fs.h>
#include <linux/miscdevice.h>
#include <mach/gpio.h>
#include <mach/at91_tc.h>
#include <mach/at91sam9g45.h>
#include "fiq-engine.h"
#include "at91_softpwm.h"
struct at91_softpwm_dev {
int in_use;
int pin;
int setpoint;
int state;
void *timer_base;
};
#define PERIOD 3000
static struct at91_softpwm_dev dev;
static void at91_softpwm_fiq_handler(void)
{
static int status;
status = __raw_readl(dev.timer_base + AT91_TC_SR);
if(!dev.in_use)
return;
if(dev.state)
{
__raw_writel(dev.setpoint, dev.timer_base + AT91_TC_RC); /* FIQ Rate = 1 kHz */
at91_set_gpio_value(dev.pin, 0);
dev.state = 0;
} else {
__raw_writel(PERIOD-dev.setpoint, dev.timer_base + AT91_TC_RC); /* FIQ Rate = 1 kHz */
at91_set_gpio_value(dev.pin, 1);
dev.state = 1;
}
}
static long at91_softpwm_ioctl(struct file *f, unsigned int cmd, unsigned long arg)
{
/* Check cmd type */
if (_IOC_TYPE(cmd) != __AT91_SOFTPWM_IOC_MAGIC)
return -ENOIOCTLCMD;
switch(cmd) {
case AT91_SOFTPWM_ENABLE:
dev.pin = arg;
dev.in_use = 1;
dev.state = 0;
return 0;
case AT91_SOFTPWM_DISABLE:
dev.in_use = 0;
dev.state = 0;
return 0;
case AT91_SOFTPWM_SETPOINT:
dev.setpoint = PERIOD - (arg * PERIOD / 1000);
return 0;
default:
return -ENOIOCTLCMD;
}
}
static struct file_operations at91_softpwm_fops = {
.owner = THIS_MODULE,
.unlocked_ioctl = at91_softpwm_ioctl
};
// TODO check available minor numbers
static struct miscdevice at91_softpwm_misc = {
.minor = 78,
.name = "at91_softpwm",
.fops = &at91_softpwm_fops
};
int __init at91_softpwm_init(void)
{
int err;
printk("at91_softpwm: initializing\n");
// register misc device
err = misc_register(&at91_softpwm_misc);
if (err < 0) {
printk(KERN_ERR "%s: Can't register misc device\n",
KBUILD_MODNAME);
return err;
}
dev.in_use = 0;
dev.setpoint = 0;
dev.timer_base = ioremap_nocache(AT91SAM9G45_BASE_TC2, 0x40);
__fiq_register(at91_softpwm_fiq_handler, AT91SAM9G45_ID_TCB);
__raw_writel(AT91_TC_TIMER_CLOCK3
| AT91_TC_WAVE
| AT91_TC_WAVESEL_UP_AUTO,
dev.timer_base + AT91_TC_CMR); /* Clock = 3 MHz */
__raw_writel(PERIOD, dev.timer_base + AT91_TC_RC); /* FIQ Rate = 1 kHz */
__raw_writel((1<<4) /* rc/rb compare */, dev.timer_base + AT91_TC_IER);
__raw_writel(AT91_TC_CLKEN | AT91_TC_SWTRG, dev.timer_base + AT91_TC_CCR);
return 0;
}
void __exit at91_softpwm_exit(void)
{
__fiq_unregister(at91_softpwm_fiq_handler, AT91SAM9G45_ID_TCB);
__raw_writel((1<<4)/* rc compare */, dev.timer_base + AT91_TC_IDR);
__raw_writel(AT91_TC_CLKDIS, dev.timer_base + AT91_TC_CCR);
if(dev.in_use)
at91_set_gpio_value(dev.pin, 0);
dev.in_use = 0;
misc_deregister(&at91_softpwm_misc);
iounmap(dev.timer_base);
}
module_init(at91_softpwm_init);
module_exit(at91_softpwm_exit);
MODULE_DESCRIPTION("Atmel AT91SAM9G45 software PWM");
MODULE_VERSION("0.1");
MODULE_LICENSE("GPL");
From 7008c0d8fe3224ea533c2634f8bdc34fe8dc1e5b Mon Sep 17 00:00:00 2001
From: Alessandro Rubini <rubini@unipv.it>
Date: Wed, 27 May 2009 00:44:01 +0200
Subject: [PATCH] arm fiq: allow modules to exploit the fiq mechanism
This patch exports "fiq_userptr" so that a module can hook to the fiq
handler. This mechanism is used by my "fiq-engine" external package
found in gnudd.com.
To prevent data aborts in vmalloc areas during fiq-mode, vmalloc.c is
modified to update the virtual memory of all processes in map_vm_area().
Without this patch such updates happen on demand, but page faults can't
be managed in fiq mode. Unfortunately, it's #fidef CONFIG_ARM in vmalloc.c
---
arch/arm/kernel/armksyms.c | 6 ++++++
arch/arm/kernel/entry-armv.S | 24 +++++++++++++++++++++++-
mm/vmalloc.c | 37 +++++++++++++++++++++++++++++++++++++
3 files changed, 66 insertions(+), 1 deletions(-)
diff --git a/arch/arm/kernel/armksyms.c b/arch/arm/kernel/armksyms.c
index e5e1e53..db1b872 100644
--- a/arch/arm/kernel/armksyms.c
+++ b/arch/arm/kernel/armksyms.c
@@ -49,6 +49,12 @@ extern void __aeabi_ulcmp(void);
extern void fpundefinstr(void);
+/*
+ * for fiq support (code in entry-armv.S -- ARub)
+ */
+extern void (*fiq_userptr)(void);
+EXPORT_SYMBOL(fiq_userptr);
+
EXPORT_SYMBOL(__backtrace);
diff --git a/arch/arm/kernel/entry-armv.S b/arch/arm/kernel/entry-armv.S
index bb96a7d..5692cbb 100644
--- a/arch/arm/kernel/entry-armv.S
+++ b/arch/arm/kernel/entry-armv.S
@@ -1193,9 +1193,31 @@ __stubs_start:
* other mode than FIQ... Ok you can switch to another mode, but you can't
* get out of that mode without clobbering one register.
*/
+/* ARub: try to use it instead (we won't leave FIQ mode anyway) */
vector_fiq:
- disable_fiq
+ ldr r9, 1f
+ ldr r9, [r9]
+ movs r9, r9
+ beq fiq_ret
+ mov r8, lr
+ mov lr, pc
+ mov pc, r9 /* jump to userptr */
+ mov lr, r8
+fiq_ret:
subs pc, lr, #4
+fiq_savemm:
+ .long 0
+
+
+
+1: .long fiq_userptr
+
+.section .text /* can't live here... */
+.globl fiq_userptr
+fiq_userptr:
+ .long 0 /* This must save r0..r8 inclusive */
+.previous
+
/*=============================================================================
* Address exception handler
diff --git a/mm/vmalloc.c b/mm/vmalloc.c
index eb5cc7d..aec65f2 100644
--- a/mm/vmalloc.c
+++ b/mm/vmalloc.c
@@ -1205,6 +1205,43 @@ int map_vm_area(struct vm_struct *area, pgprot_t prot, struct page ***pages)
err = 0;
}
+/*
+ * In order to support installation of a non-trivial FIQ handler, on ARM
+ * we need to replicate kernel virtual memory to all processes (so it
+ * can be accessed from fiq state irrespective of what current process is).
+ * The code comes from do_translation_fault, and is arm-specific.
+ */
+#ifdef CONFIG_ARM
+ if (!err) {
+ struct task_struct *p;
+ for_each_process(p) {
+ task_lock(p);
+ if (!p->mm)
+ goto next_process;
+ if (p->mm == &init_mm)
+ goto next_process;
+ for (addr = (unsigned long)area->addr;
+ addr < end; addr += PAGE_SIZE) {
+ /* "+= PMD_SIZE" may be faster... */
+ unsigned int index;
+ pgd_t *pgd, *pgd_k;
+ pmd_t *pmd, *pmd_k;
+ /* from do_translation_fault() */
+ index = pgd_index(addr);
+ pgd = p->mm->pgd + index;
+ pgd_k = init_mm.pgd + index;
+ if (!pgd_present(*pgd))
+ set_pgd(pgd, *pgd_k);
+ pmd_k = pmd_offset(pgd_k, addr);
+ pmd = pmd_offset(pgd, addr);
+ copy_pmd(pmd, pmd_k);
+ }
+ next_process:
+ task_unlock(p);
+ }
+ }
+#endif
+
return err;
}
EXPORT_SYMBOL_GPL(map_vm_area);
--
1.7.7.2
......@@ -20,6 +20,7 @@ export
# All targets must install as well, as later builds use headers/libs
all:
ln -sf ../../kernel/wbgen-regs include/regs
ln -sf ../../kernel/at91_softpwm/at91_softpwm.h include/at91_softpwm.h
for d in $(SUBDIRS); do $(MAKE) -C $$d $@ || exit 1; done
clean:
......
#ifndef __FAN_H
#define __FAN_H
int shw_init_fans();
void shw_update_fans();
#endif
\ No newline at end of file
......@@ -4,6 +4,7 @@
#include "pio.h"
#include "trace.h"
#include "pps_gen.h"
#include "fan.h"
/* Some global, very important constants */
......
......@@ -2,7 +2,7 @@ CC = $(CROSS_COMPILE)gcc
AR = $(CROSS_COMPILE)ar
CFLAGS = -I. -O2 -I../include -DDEBUG -g
OBJS = trace.o init.o fpga_io.o util.o pps_gen.o i2c.o pio_pins.o i2c_bitbang.o i2c_fpga_reg.o pio.o libshw_i2c.o i2c_sfp.o
OBJS = trace.o init.o fpga_io.o util.o pps_gen.o i2c.o pio_pins.o i2c_bitbang.o i2c_fpga_reg.o pio.o libshw_i2c.o i2c_sfp.o fan.o
SCAN_OBJS = i2cscan.o
LIB = libswitchhw.a
......
/* Fan speed servo driver. Monitors temperature of I2C onboard sensors and drives the fan accordingly */
#include <stdio.h>
#include <sys/ioctl.h>
#include <fcntl.h>
#include <unistd.h>
#include <trace.h>
#include <pio.h>
#include <pio_pins.h>
#include <at91_softpwm.h>
#include "i2c.h"
#include "i2c_fpga_reg.h"
#define FAN_UPDATE_TIMEOUT 500000
#define FAN_TEMP_SENSOR_ADDR 0x4c
#define DESIRED_TEMPERATURE 50.0
#define PI_FRACBITS 8
extern const pio_pin_t PIN_mbl_box_fan_en[];
/* PI regulator state */
typedef struct {
float ki, kp; /* integral and proportional gains (1<<PI_FRACBITS == 1.0f) */
float integrator; /* current integrator value */
float bias; /* DC offset always added to the output */
int anti_windup; /* when non-zero, anti-windup is enabled */
float y_min; /* min/max output range, used by clapming and antiwindup algorithms */
float y_max;
float x, y; /* Current input (x) and output value (y) */
} pi_controller_t;
static i2c_fpga_reg_t fpga_sensors_bus_master = {
.base_address = FPGA_I2C_SENSORS_ADDRESS,
.prescaler = 500,
};
static struct i2c_bus fpga_sensors_i2c = {
.name = "fpga_sensors",
.type = I2C_BUS_TYPE_FPGA_REG,
.type_specific = &fpga_sensors_bus_master,
};
static int pwm_fd;
static pi_controller_t fan_pi;
/* Processes a single sample (x) with PI control algorithm (pi). Returns the value (y) to
drive the actuator. */
static inline float pi_update(pi_controller_t *pi, float x)
{
float i_new, y;
pi->x = x;
i_new = pi->integrator + x;
y = ((i_new * pi->ki + x * pi->kp)) + pi->bias;
/* clamping (output has to be in <y_min, y_max>) and anti-windup:
stop the integrator if the output is already out of range and the output
is going further away from y_min/y_max. */
if(y < pi->y_min)
{
y = pi->y_min;
if((pi->anti_windup && (i_new > pi->integrator)) || !pi->anti_windup)
pi->integrator = i_new;
} else if (y > pi->y_max) {
y = pi->y_max;
if((pi->anti_windup && (i_new < pi->integrator)) || !pi->anti_windup)
pi->integrator = i_new;
} else /* No antiwindup/clamping? */
pi->integrator = i_new;
pi->y = y;
return y;
}
/* initializes the PI controller state. Currently almost a stub. */
static inline void pi_init(pi_controller_t *pi)
{
pi->integrator = 0;
}
static int enable_d0 = 0;
/* Configures a PWM output on gpio pin (pin). Rate accepts range from 0 (0%) to 1000 (100%) */
void pwm_configure_pin(const pio_pin_t *pin, int enable, int rate)
{
int index = pin->port * 32 + pin->pin;
if(enable && !enable_d0)
ioctl(pwm_fd, AT91_SOFTPWM_ENABLE, index);
else if(!enable && enable_d0)
ioctl(pwm_fd, AT91_SOFTPWM_DISABLE, index);
enable_d0 = enable;
ioctl(pwm_fd, AT91_SOFTPWM_SETPOINT, rate);
}
/* Texas Instruments TMP100 temperature sensor driver */
uint32_t tmp100_read_reg(int dev_addr, uint8_t reg_addr, int n_bytes)
{
uint8_t data[8];
uint32_t rv=0, i;
data[0] = reg_addr;
i2c_write(&fpga_sensors_i2c, dev_addr, 1, data);
i2c_read(&fpga_sensors_i2c, dev_addr, n_bytes, data);
for(i=0; i<n_bytes;i++)
{
rv <<= 8;
rv |= data[i];
}
return rv;
}
void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value)
{
uint8_t data[2];
data[0] = reg_addr;
data[1] = value;
i2c_write(&fpga_sensors_i2c, dev_addr, 2, data);
}
float tmp100_read_temp(int dev_addr)
{
int temp = tmp100_read_reg(dev_addr, 0, 2);
return (float) (temp >> 4) / 16.0;
}
int shw_init_fans()
{
uint8_t dev_map[128];
int detect, i;
TRACE(TRACE_INFO, "Configuring PWMs for fans (desired temperature = %.1f degC)...", DESIRED_TEMPERATURE);
pwm_fd = open("/dev/at91_softpwm", O_RDWR);
if(pwm_fd < 0)
{
TRACE(TRACE_FATAL, "at91_softpwm driver not installed or device not created.\n");
return -1;
}
if (i2c_init_bus(&fpga_sensors_i2c) < 0) {
TRACE(TRACE_FATAL, "can't initialize temperature sensors I2C bus.\n");
return -1;
}
tmp100_write_reg(FAN_TEMP_SENSOR_ADDR, 1, 0x60); // 12-bit resolution
fan_pi.ki = 1.0;
fan_pi.kp = 4.0;
fan_pi.y_min = 200;
fan_pi.bias = 200;
fan_pi.y_max = 800;
pi_init(&fan_pi);
return 0;
}
/* Reads out the temperature and drives the fan accordingly */
void shw_update_fans()
{
static int64_t last_tics = -1;
int64_t cur_tics = shw_get_tics();
if(last_tics < 0 || (cur_tics - last_tics) > FAN_UPDATE_TIMEOUT)
{
float t_cur = tmp100_read_temp(FAN_TEMP_SENSOR_ADDR);
float drive = pi_update(&fan_pi, t_cur - DESIRED_TEMPERATURE);
pwm_configure_pin((const pio_pin_t *)&PIN_mbl_box_fan_en, 1, (int)drive);
last_tics = cur_tics;
}
}
......@@ -28,6 +28,7 @@
#define FPGA_I2C0_ADDRESS 0x54000
#define FPGA_I2C1_ADDRESS 0x55000
#define FPGA_I2C_SENSORS_ADDRESS 0x56000
typedef struct
{
......
......@@ -19,6 +19,8 @@ int shw_init()
assert_init(shw_sfp_buses_init());
shw_sfp_gpio_init();
assert_init(shw_init_fans());
TRACE(TRACE_INFO, "HW initialization done!");
}
......
......@@ -12,12 +12,14 @@
//const pio_pin_t PIN_main_fpga_nrst[] = {{ PIOA, 5, PIO_MODE_GPIO, PIO_OUT }, {0}};
const pio_pin_t PIN_mbl_reset_n[] = {{PIOE, 1, PIO_MODE_GPIO, PIO_OUT_1}, {0}};
const pio_pin_t PIN_mbl_box_fan_en[] = {{PIOB, 20, PIO_MODE_GPIO, PIO_OUT_1}, {0}};
const pio_pin_t PIN_mbl_box_fan_en[] = {{PIOB, 20, PIO_MODE_GPIO, PIO_OUT_0}, {0}};
const pio_pin_t PIN_mbl_box_fan_tacho[] = {{PIOE, 7, PIO_MODE_GPIO, PIO_IN}, {0}};
const pio_pin_t * _all_cpu_gpio_pins[] =
{
PIN_mbl_reset_n,
PIN_mbl_box_fan_en,
PIN_mbl_box_fan_tacho,
0
};
......
......@@ -5,6 +5,7 @@ export WR_HOME="/wr"
$WR_HOME/bin/load-virtex $WR_HOME/lib/firmware/18ports_mb.bin
$WR_HOME/bin/load-lm32 $WR_HOME/lib/firmware/rt_cpu.bin
insmod $WR_HOME/lib/modules/at91_softpwm.ko
insmod $WR_HOME/lib/modules/wr_vic.ko
insmod $WR_HOME/lib/modules/wr-nic.ko
insmod $WR_HOME/lib/modules/wr_rtu.ko
......
......@@ -204,7 +204,7 @@ void hal_update()
{
hal_update_wripc();
hal_update_ports();
shw_update_fans();
// usleep(1000);
}
......
......@@ -36,6 +36,7 @@ int hal_init_timing()
{
TRACE(TRACE_INFO,"Not timing mode specified in the config file. Defaulting to Boundary Clock.");
timing_mode = HAL_TIMING_MODE_BC;
strcpy (str, "BoundaryClock");
} else {
if(!strcasecmp(str, "GrandMaster") || !strcasecmp(str, "GM"))
timing_mode = HAL_TIMING_MODE_GRAND_MASTER;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment