Skip to content
Snippets Groups Projects
Commit 9a86b49b authored by Benoit Rat's avatar Benoit Rat
Browse files

libswitchhw: update fan with new fpga spwm

parent 79a97ac9
No related merge requests found
#ifndef __FAN_H #ifndef __FAN_H
#define __FAN_H #define __FAN_H
#define SHW_FAN_UPDATETO_DEFAULT 5
int shw_init_fans(); int shw_init_fans();
void shw_update_fans(); void shw_update_fans();
#endif void shw_pwm_speed(int enable_mask, float rate);
\ No newline at end of file void shw_pwm_update_timeout(int tout_100ms);
int shw_init_i2c_sensors();
float tmp100_read_temp(int dev_addr);
void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value);
float tmp100_read_temp(int dev_addr);
#endif
...@@ -12,6 +12,9 @@ ...@@ -12,6 +12,9 @@
/* Routing Table */ /* Routing Table */
#define FPGA_BASE_RTU 0x60000 #define FPGA_BASE_RTU 0x60000
/* Simple PWM module */
#define FPGA_BASE_SPWM 0x57000
#define FPGA_BASE_ADDR _fpga_base_virt #define FPGA_BASE_ADDR _fpga_base_virt
......
/* Fan speed servo driver. Monitors temperature of I2C onboard sensors and drives the fan accordingly */ /*
* fan.c
*
* Fan speed servo driver. Monitors temperature of I2C onboard sensors and drives the fan accordingly.
*
* Created on: Jul 29, 2012
* Authors:
* - Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
* - Benoit RAT <benoit|AT|sevensols.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License...
*/
#include <stdio.h> #include <stdio.h>
#include <sys/ioctl.h> #include <sys/ioctl.h>
#include <fcntl.h> #include <fcntl.h>
...@@ -7,37 +27,28 @@ ...@@ -7,37 +27,28 @@
#include <trace.h> #include <trace.h>
#include <pio.h> #include <pio.h>
#include <pio_pins.h> #include <fan.h>
#include <at91_softpwm.h> #include <at91_softpwm.h>
#include "i2c.h" #include "i2c.h"
#include "i2c_fpga_reg.h" #include "i2c_fpga_reg.h"
#include "fpga_io.h"
#include "shw_io.h"
#include "spwm-regs.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[]; #define FAN_TEMP_SENSOR_ADDR 0x4c
/* PI regulator state */ #define DESIRED_TEMPERATURE 55.0
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 int fan_update_timeout = 0;
static int is_cpu_pwn = 0;
static int enable_d0 = 0;
static i2c_fpga_reg_t fpga_sensors_bus_master = { static i2c_fpga_reg_t fpga_sensors_bus_master = {
.base_address = FPGA_I2C_SENSORS_ADDRESS, .base_address = FPGA_I2C_SENSORS_ADDRESS,
.prescaler = 500, .prescaler = 500,
}; };
static struct i2c_bus fpga_sensors_i2c = { static struct i2c_bus fpga_sensors_i2c = {
...@@ -46,78 +57,128 @@ static struct i2c_bus fpga_sensors_i2c = { ...@@ -46,78 +57,128 @@ static struct i2c_bus fpga_sensors_i2c = {
.type_specific = &fpga_sensors_bus_master, .type_specific = &fpga_sensors_bus_master,
}; };
static int pwm_fd; #define PI_FRACBITS 8
/* 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 pi_controller_t fan_pi; static pi_controller_t fan_pi;
/* Processes a single sample (x) with PI control algorithm (pi). Returns the value (y) to
//-----------------------------------------
//-- Old CPU PWM system (<3.3)
static int pwm_fd;
//-- New FPGA PWM system
static volatile struct SPWM_WB *spwm_wbr;
//----------------------------------------
void shw_pwm_update_timeout(int tout_100ms)
{
fan_update_timeout=tout_100ms*100000;
TRACE(TRACE_INFO,"Fan tick timeout is =%d",fan_update_timeout);
}
/* Processes a single sample (x) with Proportional Integrator control algorithm (pi). Returns the value (y) to
drive the actuator. */ drive the actuator. */
static inline float pi_update(pi_controller_t *pi, float x) static inline float pi_update(pi_controller_t *pi, float x)
{ {
float i_new, y; float i_new, y;
pi->x = x; pi->x = x;
i_new = pi->integrator + x; i_new = pi->integrator + x;
y = ((i_new * pi->ki + x * pi->kp)) + pi->bias; y = ((i_new * pi->ki + x * pi->kp)) + pi->bias;
/* clamping (output has to be in <y_min, y_max>) and anti-windup: /* 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 stop the integrator if the output is already out of range and the output
is going further away from y_min/y_max. */ is going further away from y_min/y_max. */
if(y < pi->y_min) if(y < pi->y_min)
{ {
y = pi->y_min; y = pi->y_min;
if((pi->anti_windup && (i_new > pi->integrator)) || !pi->anti_windup) if((pi->anti_windup && (i_new > pi->integrator)) || !pi->anti_windup)
pi->integrator = i_new; pi->integrator = i_new;
} else if (y > pi->y_max) { } else if (y > pi->y_max) {
y = pi->y_max; y = pi->y_max;
if((pi->anti_windup && (i_new < pi->integrator)) || !pi->anti_windup) if((pi->anti_windup && (i_new < pi->integrator)) || !pi->anti_windup)
pi->integrator = i_new; pi->integrator = i_new;
} else /* No antiwindup/clamping? */ } else /* No antiwindup/clamping? */
pi->integrator = i_new; pi->integrator = i_new;
pi->y = y; pi->y = y;
return y; return y;
} }
/* initializes the PI controller state. Currently almost a stub. */ /* initializes the PI controller state. Currently almost a stub. */
static inline void pi_init(pi_controller_t *pi) static inline void pi_init(pi_controller_t *pi)
{ {
pi->integrator = 0; 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%) */ /* 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) void pwm_configure_pin(const pio_pin_t *pin, int enable, int rate)
{ {
int index = pin->port * 32 + pin->pin; int index = pin->port * 32 + pin->pin;
if(pin==0) return;
if(enable && !enable_d0) if(enable && !enable_d0)
ioctl(pwm_fd, AT91_SOFTPWM_ENABLE, index); ioctl(pwm_fd, AT91_SOFTPWM_ENABLE, index);
else if(!enable && enable_d0) else if(!enable && enable_d0)
ioctl(pwm_fd, AT91_SOFTPWM_DISABLE, index); ioctl(pwm_fd, AT91_SOFTPWM_DISABLE, index);
enable_d0 = enable; enable_d0 = enable;
ioctl(pwm_fd, AT91_SOFTPWM_SETPOINT, rate); ioctl(pwm_fd, AT91_SOFTPWM_SETPOINT, rate);
} }
/* Configures a PWM output on gpio pin (pin). Rate accepts range from 0 (0%) to 1000 (100%) */
void pwm_configure_fpga(int enmask, float rate)
{
uint8_t u8speed=(uint8_t)((rate>=1)?0xff:(rate*255.0));
if(enmask & 0x1) spwm_wbr->DR0=u8speed;
else spwm_wbr->DR0=0;
if(enmask & 0x2) spwm_wbr->DR1=u8speed;
else spwm_wbr->DR0=0;
}
/* Configures a PWM output. Rate accepts range is from 0 (0%) to 1 (100%) */
void shw_pwm_speed(int enmask, float rate)
{
//TRACE(TRACE_INFO,"%x %f",enmask,rate);
if(is_cpu_pwn)
{
pwm_configure_pin(get_pio_pin(shw_io_box_fan_en), enmask, rate*1000);
}
else
{
pwm_configure_fpga(enmask,rate);
}
}
/* Texas Instruments TMP100 temperature sensor driver */ /* Texas Instruments TMP100 temperature sensor driver */
uint32_t tmp100_read_reg(int dev_addr, uint8_t reg_addr, int n_bytes) uint32_t tmp100_read_reg(int dev_addr, uint8_t reg_addr, int n_bytes)
{ {
uint8_t data[8]; uint8_t data[8];
uint32_t rv=0, i; uint32_t rv=0, i;
data[0] = reg_addr; data[0] = reg_addr;
i2c_write(&fpga_sensors_i2c, dev_addr, 1, data); i2c_write(&fpga_sensors_i2c, dev_addr, 1, data);
i2c_read(&fpga_sensors_i2c, dev_addr, n_bytes, data); i2c_read(&fpga_sensors_i2c, dev_addr, n_bytes, data);
for(i=0; i<n_bytes;i++) for(i=0; i<n_bytes;i++)
{ {
rv <<= 8; rv <<= 8;
rv |= data[i]; rv |= data[i];
} }
return rv; return rv;
} }
...@@ -135,55 +196,89 @@ void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value) ...@@ -135,55 +196,89 @@ void tmp100_write_reg(int dev_addr, uint8_t reg_addr, uint8_t value)
float tmp100_read_temp(int dev_addr) float tmp100_read_temp(int dev_addr)
{ {
int temp = tmp100_read_reg(dev_addr, 0, 2); int temp = tmp100_read_reg(dev_addr, 0, 2);
return (float) (temp >> 4) / 16.0; return ((float) (temp >> 4)) / 16.0;
}
int shw_init_i2c_sensors()
{
if (i2c_init_bus(&fpga_sensors_i2c) < 0) {
TRACE(TRACE_FATAL, "can't initialize temperature sensors I2C bus.\n");
return -1;
}
} }
int shw_init_fans() int shw_init_fans()
{ {
uint8_t dev_map[128]; uint8_t dev_map[128];
uint32_t val=0;
int detect, i; int detect, i;
TRACE(TRACE_INFO, "Configuring PWMs for fans (desired temperature = %.1f degC)...", DESIRED_TEMPERATURE); TRACE(TRACE_INFO, "Configuring PWMs for fans (desired temperature = %.1f degC)...", DESIRED_TEMPERATURE);
pwm_fd = open("/dev/at91_softpwm", O_RDWR); //Set the type of PWM
if(pwm_fd < 0) if(shw_get_hw_ver()<3.3) is_cpu_pwn=1;
else is_cpu_pwn=0;
if(is_cpu_pwn)
{ {
TRACE(TRACE_FATAL, "at91_softpwm driver not installed or device not created.\n");
return -1;
}
if (i2c_init_bus(&fpga_sensors_i2c) < 0) { pwm_fd = open("/dev/at91_softpwm", O_RDWR);
TRACE(TRACE_FATAL, "can't initialize temperature sensors I2C bus.\n"); if(pwm_fd < 0)
return -1; {
TRACE(TRACE_FATAL, "at91_softpwm driver not installed or device not created.\n");
return -1;
}
fan_pi.ki = 1.0;
fan_pi.kp = 4.0;
fan_pi.y_min = 200;
fan_pi.bias = 200;
fan_pi.y_max = 800;
}
else
{
//Point to the corresponding WB direction
spwm_wbr= (volatile struct SPWM_WB *) (FPGA_BASE_ADDR + FPGA_BASE_SPWM);
//Configure SPWM register the 60=(62.5MHz÷(4kHz×2^8))−1
val= SPWM_CR_PRESC_W(60) | SPWM_CR_PERIOD_W(255);
spwm_wbr->CR=val;
fan_pi.ki = 1.0;
fan_pi.kp = 4.0;
fan_pi.y_min = 400;
fan_pi.bias = 200;
fan_pi.y_max = 1000;
} }
tmp100_write_reg(FAN_TEMP_SENSOR_ADDR, 1, 0x60); // 12-bit resolution shw_init_i2c_sensors();
fan_pi.ki = 1.0; tmp100_write_reg(FAN_TEMP_SENSOR_ADDR, 1, 0x60); // 12-bit resolution
fan_pi.kp = 4.0;
fan_pi.y_min = 200;
fan_pi.bias = 200;
fan_pi.y_max = 800;
pi_init(&fan_pi); pi_init(&fan_pi);
shw_pwm_update_timeout(SHW_FAN_UPDATETO_DEFAULT);
return 0; return 0;
} }
/* Reads out the temperature and drives the fan accordingly */ /*
* Reads out the temperature and drives the fan accordingly
* note: This call is done by hal_main.c:hal_update()
*/
void shw_update_fans() void shw_update_fans()
{ {
static int64_t last_tics = -1; static int64_t last_tics = -1;
int64_t cur_tics = shw_get_tics(); int64_t cur_tics = shw_get_tics();
if(last_tics < 0 || (cur_tics - last_tics) > FAN_UPDATE_TIMEOUT) if(fan_update_timeout>0 && (last_tics < 0 || (cur_tics - last_tics) > fan_update_timeout))
{ {
float t_cur = tmp100_read_temp(FAN_TEMP_SENSOR_ADDR); float t_cur = tmp100_read_temp(FAN_TEMP_SENSOR_ADDR);
float drive = pi_update(&fan_pi, t_cur - DESIRED_TEMPERATURE); float drive = pi_update(&fan_pi, t_cur - DESIRED_TEMPERATURE);
//TRACE(TRACE_INFO,"t=%f,pwm=%f",t_cur , drive);
pwm_configure_pin((const pio_pin_t *)&PIN_mbl_box_fan_en, 1, (int)drive); shw_pwm_speed(0xFF, drive/1000); //enable two and one
last_tics = cur_tics; last_tics = cur_tics;
} }
} }
......
/*
Register definitions for slave core: Simple Pulse Width Modulation Controller
* File : spwm-regs.h
* Author : auto-generated by wbgen2 from simple_pwm_wb.wb
* Created : Mon Jan 21 14:31:18 2013
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE simple_pwm_wb.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_SIMPLE_PWM_WB_WB
#define __WBGEN2_REGDEFS_SIMPLE_PWM_WB_WB
#include <inttypes.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: Control Register */
/* definitions for field: Prescaler Ratio in reg: Control Register */
#define SPWM_CR_PRESC_MASK WBGEN2_GEN_MASK(0, 16)
#define SPWM_CR_PRESC_SHIFT 0
#define SPWM_CR_PRESC_W(value) WBGEN2_GEN_WRITE(value, 0, 16)
#define SPWM_CR_PRESC_R(reg) WBGEN2_GEN_READ(reg, 0, 16)
/* definitions for field: Period in reg: Control Register */
#define SPWM_CR_PERIOD_MASK WBGEN2_GEN_MASK(16, 16)
#define SPWM_CR_PERIOD_SHIFT 16
#define SPWM_CR_PERIOD_W(value) WBGEN2_GEN_WRITE(value, 16, 16)
#define SPWM_CR_PERIOD_R(reg) WBGEN2_GEN_READ(reg, 16, 16)
/* definitions for register: Status Register */
/* definitions for field: Channel count in reg: Status Register */
#define SPWM_SR_N_CHANNELS_MASK WBGEN2_GEN_MASK(0, 4)
#define SPWM_SR_N_CHANNELS_SHIFT 0
#define SPWM_SR_N_CHANNELS_W(value) WBGEN2_GEN_WRITE(value, 0, 4)
#define SPWM_SR_N_CHANNELS_R(reg) WBGEN2_GEN_READ(reg, 0, 4)
/* definitions for register: Channel 0 Drive Register */
/* definitions for register: Channel 1 Drive Register */
/* definitions for register: Channel 2 Drive Register */
/* definitions for register: Channel 3 Drive Register */
/* definitions for register: Channel 4 Drive Register */
/* definitions for register: Channel 5 Drive Register */
/* definitions for register: Channel 6 Drive Register */
/* definitions for register: Channel 7 Drive Register */
PACKED struct SPWM_WB {
/* [0x0]: REG Control Register */
uint32_t CR;
/* [0x4]: REG Status Register */
uint32_t SR;
/* [0x8]: REG Channel 0 Drive Register */
uint32_t DR0;
/* [0xc]: REG Channel 1 Drive Register */
uint32_t DR1;
/* [0x10]: REG Channel 2 Drive Register */
uint32_t DR2;
/* [0x14]: REG Channel 3 Drive Register */
uint32_t DR3;
/* [0x18]: REG Channel 4 Drive Register */
uint32_t DR4;
/* [0x1c]: REG Channel 5 Drive Register */
uint32_t DR5;
/* [0x20]: REG Channel 6 Drive Register */
uint32_t DR6;
/* [0x24]: REG Channel 7 Drive Register */
uint32_t DR7;
};
#endif
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