Commit 88e9e820 authored by Richard R. Carrillo's avatar Richard R. Carrillo

added PTS tests for fmcdio5chttla board

parent 9a9c42ab
#!/bin/sh
LOGDIR=./log
mkdir -p $LOGDIR
sudo rm -fr $LOGDIR/pts*
serial=$1
if [ x$1 = x"" ]; then
echo -n "Please, input SERIAL number: "
read serial
fi
extra_serial=$2
if [ x$2 = x"" ]; then
echo -n "Please, input extra SERIAL number: "
read extra_serial
fi
if [ x$extra_serial = x"" ]; then
extra_serial=0000
fi
tmp=""
echo "--------------------------------------------------------------"
sudo ./pts.py -b FMC-DIO-5chTTLa -s $serial -e $extra_serial -t./test/fmcdio5chttla/python -l $LOGDIR 00 01 02 03 04 05
echo -n "Press enter to exit..."
read tmp
*******************************************************************************
FmcDIO5chTTLa's tests for TPS environment
*******************************************************************************
Seven Solutions S.L.
Author: Richard R. Carrillo <rcarrillo(AT)sevensols.com>
Licence: GPL v2 or later.
Website: http://www.ohwr.org
Website: http://www.sevensols.com
Last modifications: 1/4/2012
This batch of tests makes a connectivity test of the FmcDIO5chTTLa's components.
- test00: Check fmc-dio-5chttl board EEPROM and DAC presence and temperature-sensor operation
- test01: Check fmc-dio-5chttl-board LEDs (LEDs and LED circuit working)
- test02: Check fmc-dio-5chttl-board ports as output (port driver working, connector connectivity and LVDS to LVCMOS IC working)
- test03: Check fmc-dio-5chttl-board ports as inputs (DAC, LVDS comparator)
- test04: Check output-enable circuit of fmc-dio-5chttl-board ports
- test05: Check termination resistors of fmc-dio-5chttl-board ports
These tests are made to work stand-alone too. So, it is possible to execute each one using 'sudo ./test0x.py'
These tests are designed to use Python 2.7 or higher.
#!/usr/bin/python
# Author: Tomasz?
# Author (modifications): Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Last modifications: 1/4/2012
from i2c import *
class CDAC5578:
CMD_POWER_ON = 0x40
CMD_WRITE_CH = 0x30
CMD_SW_RESET = 0x70
CMD_LDAC_CTRL = 0x60
CMD_READ_REG = 0x10
def __init__(self, bus, addr):
""" Configure DAC """
self.bus = bus;
self.addr = addr;
self.cmd_out(self.CMD_SW_RESET, 0);
self.cmd_out(self.CMD_LDAC_CTRL, 0xff); # ignore LDAC pins
self.cmd_out(self.CMD_POWER_ON, 0x1f, 0xe0);
def cmd_out(self, cmd, data, data2 = 0):
""" Send a command to DAC which does not include answer """
self.bus.start(self.addr, True);
self.bus.write(cmd, False)
self.bus.write(data, False)
self.bus.write(data2, True)
def cmd_in(self, cmd):
""" Send a command to DAC which expects answer """
self.bus.start(self.addr, True)
self.bus.write(cmd, False)
self.bus.start(self.addr, False)
reg_val=self.bus.read(False)
self.bus.read(True)
return(reg_val)
def out(self, channel, data):
""" Set a value (data) to a specified DAC channel """
self.cmd_out(self.CMD_WRITE_CH | channel, data)
def rd_out(self, channel):
""" Return the value set to a specified DAC channel """
return(self.cmd_in(self.CMD_READ_REG | channel))
#!/usr/bin/python
# Author: Tomasz?
# Author (modifications): Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Last modifications: 1/4/2012
import rr
import struct
import time
import sys
from xwb_gpio import *
from i2c import *
from eeprom_24aa64 import *
from onewire import *
from ds18b20 import *
from cdac5578 import *
class CFmcDioError(Exception):
def __init__(self, bus_name, addr, msg):
self.error_msgs={CFmcDio.I2C_ADDR_EEPROM:"EEPROM (24AA64T)",
CFmcDio.I2C_ADDR_DAC:"DAC (DAC5578)"}
self.bus_name = bus_name
self.addr = addr
self.msg = msg
def __str__(self):
if self.bus_name == "FMC":
return self.msg + " in " + self.bus_name + ". Is the fmc-dio-5chttla correctly inserted into the carrier?"
elif self.bus_name == "I2C" and self.addr in self.error_msgs.keys():
return "I2C device %s at addr 0x%x produced the error: %s" %(self.error_msgs[self.addr], self.addr, self.msg)
else:
return "Error in "+self.bus_name+" bus. (Addr: "+hex(self.addr)+"): "+self.msg
class CFmcDio:
BASE_GPIO = 0x200
BASE_I2C = 0x100
BASE_ONEWIRE = 0x0
I2C_ADDR_DAC = 0x48
I2C_ADDR_EEPROM = 0x50
I2C_PRESCALER = 400
PIN_PRSNT = 30
GPIO_LED_TOP = 27
GPIO_LED_BOTTOM = 28
DAC_CHANNEL_CORRESP=[0,1,2,7,4,5]
def __init__(self, bus, base, init_devices):
""" fmc-dio-5chttla-board presence check, I2C devices response check and OneWire-device funct. init.
bus = host bus (PCIe, VME, etc...)
base = base address
init_devices = If it is True, I2C and OneWire devices are initialized and can then be used
"""
self.bus = bus
self.base = base
self.gpio = CGPIO(bus, base + self.BASE_GPIO)
if(not self.fmc_present()):
raise CFmcDioError("FMC", base, "DIOERR00: PRESENT line is not asserted")
if init_devices:
try:
self.i2c = COpenCoresI2C(bus, base + self.BASE_I2C, self.I2C_PRESCALER)
board_I2C_periph_addr=[self.I2C_ADDR_DAC,self.I2C_ADDR_EEPROM]
found_I2C_periph_addr=self.i2c.scan()
except I2CDeviceOperationError as e:
raise CFmcDioError("I2C", base, "DIOERR01: "+e.msg)
if not found_I2C_periph_addr:
raise CFmcDioError("I2C", base, "DIOERR02: No I2C device found")
for periph_addr in board_I2C_periph_addr:
if periph_addr not in found_I2C_periph_addr:
raise CFmcDioError("I2C", periph_addr, "DIOERR03: Device not found. Only "+str(len(found_I2C_periph_addr))+" I2C devices found")
try:
self.eeprom = C24AA64(self.i2c, self.I2C_ADDR_EEPROM);
except I2CDeviceOperationError as e:
raise CFmcDioError("I2C", self.I2C_ADDR_EEPROM, "DIOERR04: "+e.msg)
try:
self.dac = CDAC5578(self.i2c, self.I2C_ADDR_DAC);
except I2CDeviceOperationError as e:
raise CFmcDioError("I2C", self.I2C_ADDR_DAC, "DIOERR05: "+e.msg)
self.onewire = COpenCoresOneWire(self.bus, base + self.BASE_ONEWIRE, 624/2, 124/2)
self.ds1820 = CDS18B20(self.onewire, 0);
else:
self.i2c=None
self.onewire=None
self.dac=None
self.eeprom=None
self.ds1820=None
def fmc_present(self):
""" Return 1 if FMC PRESENT pin is asserted """
return not self.gpio.inp(self.PIN_PRSNT);
def set_dir(self, port, d):
""" Enable (d=1) or disable (d=0) the output of a specified port ([0-4]) """
self.gpio.outp(port * 4 + 1, not d)
def set_out(self, port, d):
""" Set the output value (d) of a specified port ([0-4]) """
self.gpio.outp(port * 4, d)
def set_term(self, port, d):
""" Enable (d=1) or disable (d=0) the termination resistor (50ohm)t of a specified port ([0-4]) """
self.gpio.outp(port * 4 + 2, d)
def get_in(self, port):
""" Return the input value of a specified port ([0-4]) """
return self.gpio.inp(port * 4)
def power(self, ins, clock):
pass
def set_led(self, led, state):
""" Changes the state of a specified fmc-dio-5chttla-board LED
led=[0,1]
state=[0=off,1=on]
"""
gpio_leds=[self.GPIO_LED_TOP, self.GPIO_LED_BOTTOM]
self.gpio.outp(gpio_leds[led],state)
#print "LED", gpio_leds[led], "set to", state
def set_in_threshold(self, port, threshold):
""" Configures a specified DAC channel (port) with a specified output value (threshold) """
if self.dac is not None:
# Saturation is done in order to eliminate residual calculation errors
if threshold>255:
threshold>255
if threshold<0:
threshold=0
try:
self.dac.out(self.DAC_CHANNEL_CORRESP[port], threshold)
except I2CDeviceOperationError as e:
raise CFmcDioError("I2C", self.I2C_ADDR_DAC, "DIOERR06: "+e.msg)
else:
raise CFmcDioError("I2C", self.base, "DIOERR07: Device not initialized")
def get_in_threshold(self, port):
""" Returns the DAC value set in a specified channel (port) """
if self.dac is not None:
try:
dacval=self.dac.rd_out(self.DAC_CHANNEL_CORRESP[port])
except I2CDeviceOperationError as e:
raise CFmcDioError("I2C", self.I2C_ADDR_DAC, "DIOERR08: "+e.msg)
return(dacval)
else:
raise CFmcDioError("I2C", self.base, "DIOERR07: Device not initialized")
def DACvalue2voltage(self, dacval):
""" Calculate the voltage corresponding to a specific DAC channel digital value """
return dacval/255*3.3
def DACvoltage2value(self, volt):
""" Calculate the DAC channel digital value corresponding to a specific voltage """
return int(volt/3.3*255+0.5) # +0.5 due to the int() truncation
def find_port_voltage(self,port,range_min,range_max):
""" Uses a binary search algorthm to find the voltage (DAC threshold) in a specified board port
port: number of fmc-dio-5chttla-board port [0-4]
range_max: high voltage limit of the range in which the threshold is expected to be found
range_min: low voltage limit
The range input parameters are specified just to increase the execution speed
"""
# Convert the range limits provided in volts to the corresponding digital DAC value
range_min=self.DACvoltage2value(range_min)
range_max=self.DACvoltage2value(range_max)
# check if the specified range_min is too restrictive
self.set_in_threshold(port,range_min)
time.sleep(0.010) # wait for the DAC output to stabilize
port_inp=self.get_in(port)
if port_inp:
range_low=range_min # correct provided range
else:
range_low=-1
# check if the specified range_max is too restrictive
self.set_in_threshold(port,range_max)
time.sleep(0.010) # wait for the DAC output to stabilize
port_inp=self.get_in(port)
if not port_inp:
range_high=range_max # correct provided range
else:
range_high=256
#print "L: {} H: {}".format(range_low,range_high)
while (range_high-range_low) > 1: # while thresold not found
range_mid=(range_low+range_high)/2 # integer arithmetics
self.set_in_threshold(port,range_mid)
time.sleep(0.010) # wait for the DAC output to stabilize
port_inp=self.get_in(port)
#print "DAC[{}]={}".format(range_mid,port_inp)
if port_inp: # DAC set to a value below the port input voltage
range_low=range_mid
else:
range_high=range_mid
return self.DACvalue2voltage((range_low+range_high)/2.0)
def get_unique_id(self):
""" Get the ID value of the OneWire IC DS1820 consisting in (crc:serial_number:family_code) """
if self.ds1820:
try:
return self.ds1820.read_serial_number()
except OneWireDeviceOperationError as e:
raise CFmcDioError("OneWire", self.base, "DIOERR09: "+e.msg)
else:
raise CFmcDioError("OneWire", self.base, "DIOERR10: Device not initialized")
def get_temp(self):
""" Returns a temperature value in Celsius degrees by means of the OneWire IC DS1820 """
if self.ds1820:
try:
serial_number = self.ds1820.read_serial_number()
temp=self.ds1820.read_temp(serial_number)
except OneWireDeviceOperationError as e:
raise CFmcDioError("OneWire", self.base, "DIOERR11: "+e.msg)
return temp
else:
raise CFmcDioError("OneWire", self.base, "DIOERR10: Device not initialized")
#spec = rr.Gennum()
#dio= CFmcDio(spec, 0x80000);
#print("S/N: %x" % dio.get_unique_id())
#print("Board temp: %d degC" % dio.get_temp());
#!/usr/bin/python
# Author: Tomasz?
# Author (modifications): Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Last modifications: 1/4/2012
import sys
import rr
import time
import onewire
class CDS18B20:
# ROM commands
ROM_SEARCH = 0xF0
ROM_READ = 0x33
ROM_MATCH = 0x55
ROM_SKIP = 0xCC
ROM_ALARM_SEARCH = 0xEC
# DS18B20 functions commands
CONVERT_TEMP = 0x44
WRITE_SCRATCHPAD = 0x4E
READ_SCRATCHPAD = 0xBE
COPY_SCRATCHPAD = 0x48
RECALL_EEPROM = 0xB8
READ_POWER_SUPPLY = 0xB4
FAMILY_CODE = 0x28
MIN_TEMPER = -55
MAX_TEMPER = 125
# Thermometer resolution configuration
RES = {'9-bit':0x0, '10-bit':0x1, '11-bit':0x2, '12-bit':0x3}
def __init__(self, onewire, port):
self.onewire = onewire
self.port = port
def read_serial_number(self):
#print('[DS18B20] Reading serial number')
self.onewire.reset(self.port)
#print('[DS18B20] Write ROM command %.2X') % self.ROM_READ
self.onewire.write_byte(self.port, self.ROM_READ)
family_code = self.onewire.read_byte(self.port)
if family_code != self.FAMILY_CODE:
raise onewire.OneWireDeviceOperationError("Invalid family code reported:"+hex(family_code)+" (expected:"+hex(self.FAMILY_CODE)+"). Wrong chip mounted?")
serial_number = 0
for i in range(6):
serial_number |= self.onewire.read_byte(self.port) << (i*8)
crc = self.onewire.read_byte(self.port)
#print('[DS18B20] Family code : %.2X') % family_code
#print('[DS18B20] Serial number: %.12X') % serial_number
#print('[DS18B20] CRC : %.2X') % crc
return ((crc<<56) | (serial_number<<8) | family_code)
def access(self, serial_number):
#print('[DS18B20] Accessing device')
self.onewire.reset(self.port)
#print('[DS18B20] Write ROM command %.2X') % self.ROM_MATCH
err = self.onewire.write_byte(self.port, self.ROM_MATCH)
#print serial_number
block = []
for i in range(8):
block.append(serial_number & 0xFF)
serial_number >>= 8
#print block
self.onewire.write_block(self.port, block)
def read_temp(self, serial_number):
#print('[DS18B20] Reading temperature')
self.access(serial_number)
#print('[DS18B20] Write function command %.2X') % self.CONVERT_TEMP
self.onewire.write_byte(self.port, self.CONVERT_TEMP)
time.sleep(0.9)
self.access(serial_number)
#print('[DS18B20] Write function command %.2X') % self.READ_SCRATCHPAD
self.onewire.write_byte(self.port, self.READ_SCRATCHPAD)
data = self.onewire.read_block(self.port, 9)
#for i in range(9):
# print('Scratchpad data[%1d]: %.2X') % (i, data[i])
temp = (data[1] << 8) | (data[0])
if temp & 0x1000:
temp = -0x10000 + temp
temp = temp/16.0
if temp < self.MIN_TEMPER or temp > self.MAX_TEMPER:
raise onewire.OneWireDeviceOperationError("Sensor reported an invalid temperature")
return temp
# Set temperature thresholds
# Configure thermometer resolution
#!/usr/bin/python
import sys
import rr
import time
import i2c
class C24AA64:
def __init__(self, i2c, i2c_addr):
self.i2c = i2c
self.i2c_addr = i2c_addr
def wr_data(self, mem_addr, data):
self.i2c.start(self.i2c_addr, True)
self.i2c.write((mem_addr >> 8), False)
self.i2c.write((mem_addr & 0xFF), False)
#print('24AA64:write: data lenght=%d')%(len(data))
for i in range(len(data)-1):
#print('24AA64:write: i=%d')%(i)
self.i2c.write(data[i],False)
i += 1
#print('24AA64:write:last i=%d')%(i)
self.i2c.write(data[i],True)
def rd_data(self, mem_addr, size):
self.i2c.start(self.i2c_addr, True)
self.i2c.write((mem_addr >> 8), False)
self.i2c.write((mem_addr & 0xFF), False)
self.i2c.start(self.i2c_addr, False)
data = []
#print('24AA64:read: data lenght=%d')%(size)
i=0
for i in range(size-1):
data.append(self.i2c.read(False))
#print('24AA64:read: i=%d')%(i)
i += 1
#print('24AA64:read:last i=%d')%(i)
data.append(self.i2c.read(True))
return data;
#!/usr/bin/python
import sys
import rr
import time
class I2CDeviceOperationError(Exception):
def __init__(self, msg):
self.msg = msg
def __str__(self):
return ("I2C Device produced the error: %s" %(msg))
class COpenCoresI2C:
# OpenCores I2C registers description
R_PREL = 0x0
R_PREH = 0x4
R_CTR = 0x8
R_TXR = 0xC
R_RXR = 0xC
R_CR = 0x10
R_SR = 0x10
CTR_EN = (1<<7)
CR_STA = (1<<7)
CR_STO = (1<<6)
CR_RD = (1<<5)
CR_WR = (1<<4)
CR_ACK = (1<<3)
SR_RXACK = (1<<7)
SR_TIP = (1<<1)
WAIT_TIME_OUT = 2
def wr_reg(self, addr, val):
self.bus.iwrite(0, self.base_addr + addr, 4, val)
def rd_reg(self,addr):
return self.bus.iread(0, self.base_addr + addr, 4)
# Function called during object creation
# bus = host bus (PCIe, VME, etc...)
# base_addr = I2C core base address
# prescaler = SCK prescaler, prescaler = (Fsys/(5*Fsck))-1
def __init__(self, bus, base_addr, prescaler):
self.bus = bus
self.base_addr = base_addr
self.wr_reg(self.R_CTR, 0)
#print("prescaler: %.4X") % prescaler
self.wr_reg(self.R_PREL, (prescaler & 0xff))
#print("PREL: %.2X") % self.rd_reg(self.R_PREL)
self.wr_reg(self.R_PREH, (prescaler >> 8))
#print("PREH: %.2X") % self.rd_reg(self.R_PREH)
self.wr_reg(self.R_CTR, self.CTR_EN)
#print("CTR: %.2X") % self.rd_reg(self.R_CTR)
if not(self.rd_reg(self.R_CTR) & self.CTR_EN):
raise I2CDeviceOperationError("I2C core is not enabled")
def wait_busy(self):
init_time=time.time()
while(self.rd_reg(self.R_SR) & self.SR_TIP):
if (time.time()-init_time) > self.WAIT_TIME_OUT:
raise I2CDeviceOperationError("Wait timeout")
def start(self, addr, write_mode):
#print('i2c:start: addr=%.2X')%addr
addr = addr << 1
#print('i2c:start: addr=%.2X')%addr
if(write_mode == False):
addr = addr | 1
#print('i2c:start: addr=%.2X')%addr
self.wr_reg(self.R_TXR, addr)
#print("R_TXR: %.2X") % self.rd_reg(self.R_TXR)
self.wr_reg(self.R_CR, self.CR_STA | self.CR_WR)
self.wait_busy()
if self.rd_reg(self.R_SR) & self.SR_RXACK:
raise I2CDeviceOperationError("Device ACK not received at the I2C message start")
def write(self, data, last):
self.wr_reg(self.R_TXR, data)
cmd = self.CR_WR
if(last):
cmd = cmd | self.CR_STO
self.wr_reg(self.R_CR, cmd)
self.wait_busy()
if(self.rd_reg(self.R_SR) & self.SR_RXACK):
raise I2CDeviceOperationError("No ACK upon write")
def read(self, last):
cmd = self.CR_RD
if(last):
cmd = cmd | self.CR_STO | self.CR_ACK
self.wr_reg(self.R_CR, cmd)
self.wait_busy()
return self.rd_reg(self.R_RXR)
def scan(self):
periph_addr = []
print "Addresses of I2C devices found:",
for i in range(0, 127):
addr = i << 1
# addr |= 1
self.wr_reg(self.R_TXR, addr)
self.wr_reg(self.R_CR, self.CR_STA | self.CR_WR)
self.wait_busy()
if(not(self.rd_reg(self.R_SR) & self.SR_RXACK)):
periph_addr.append(i)
print("0x{:X}".format(i)),
sys.stdout.flush()
self.wr_reg(self.R_TXR, 0)
self.wr_reg(self.R_CR, self.CR_STO | self.CR_WR)
self.wait_busy()
print ""
return periph_addr
##########################################
# Usage example
#gennum = rr.Gennum();
#i2c = COpenCoresI2C(gennum, 0x80000, 500);
#!/usr/bin/python
#coding: utf8
# Copyright Seven Solutions S.L., 2012
# Author: Richard Carrillo <rcarrillo@sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
import sys,select,fcntl,os
def kbhit():
""" Return True if there is a key pending to be read """
dr,dw,de = select.select([sys.stdin], [], [], 0.1)
# print "dr:"+str(dr)+" dw:"+str(dr)+" de:"+str(de)
return dr <> []
def getch():
""" Read one char from stdin """
return sys.stdin.read(1)
def purgestdin():
""" Discard all key strokes """
# make stdin a non-blocking file
fd = sys.stdin.fileno()
fl = fcntl.fcntl(fd, fcntl.F_GETFL)
fcntl.fcntl(fd, fcntl.F_SETFL, fl | os.O_NONBLOCK)
try:
sys.stdin.read(4096) # purge stdin
except:
pass # ignore resource-unavailable exception
# restore stdin attributes
fcntl.fcntl(fd, fcntl.F_SETFL, fl)
#!/usr/bin/python
# Author: Tomasz?
# Author (modifications): Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Last modifications: 1/4/2012
import sys
import rr
import time
class OneWireDeviceOperationError(Exception):
def __init__(self, msg):
self.msg = msg
def __str__(self):
return ("OneWire Device produced the error: %s" %(msg))
class COpenCoresOneWire:
# OpenCores 1-wire registers description
R_CSR = 0x0
R_CDR = 0x4
CSR_DAT_MSK = (1<<0)
CSR_RST_MSK = (1<<1)
CSR_OVD_MSK = (1<<2)
CSR_CYC_MSK = (1<<3)
CSR_PWR_MSK = (1<<4)
CSR_IRQ_MSK = (1<<6)
CSR_IEN_MSK = (1<<7)
CSR_SEL_OFS = 8
CSR_SEL_MSK = (0xF<<8)
CSR_POWER_OFS = 16
CSR_POWER_MSK = (0xFFFF<<16)
CDR_NOR_MSK = (0xFFFF<<0)
CDR_OVD_OFS = 16
CDR_OVD_MSK = (0XFFFF<<16)
WAIT_TIME_OUT = 2
MAX_BLOCK_LEN = 160
def wr_reg(self, addr, val):
self.bus.iwrite(0, self.base_addr + addr, 4, val)
def rd_reg(self,addr):
return self.bus.iread(0, self.base_addr + addr, 4)
# Function called during object creation
# bus = host bus (PCIe, VME, etc...)
# base_addr = 1-wire core base address
# clk_div_nor = clock divider normal operation, clk_div_nor = Fclk * 5E-6 - 1
# clk_div_ovd = clock divider overdrive operation, clk_div_ovd = Fclk * 1E-6 - 1
def __init__(self, bus, base_addr, clk_div_nor, clk_div_ovd):
self.bus = bus
self.base_addr = base_addr
#print('\n### Onewire class init ###')
#print("Clock divider (normal operation): %.4X") % clk_div_nor
#print("Clock divider (overdrive operation): %.4X") % clk_div_ovd
data = ((clk_div_nor & self.CDR_NOR_MSK) | ((clk_div_ovd<<self.CDR_OVD_OFS) & self.CDR_OVD_MSK))
#print('CRD register wr: %.8X') % data
self.wr_reg(self.R_CDR, data)
#print('CRD register rd: %.8X') % self.rd_reg(self.R_CDR)
# return: 1 -> presence pulse detected
# 0 -> no presence pulse detected
def reset(self, port):
data = ((port<<self.CSR_SEL_OFS) & self.CSR_SEL_MSK) | self.CSR_CYC_MSK | self.CSR_RST_MSK
#print('[onewire] Sending reset command, CSR: %.8X') % data
self.wr_reg(self.R_CSR, data)
while(self.rd_reg(self.R_CSR) & self.CSR_CYC_MSK):
pass
reg = self.rd_reg(self.R_CSR)
#print('[onewire] Reading CSR: %.8X') % reg
if not (~reg & self.CSR_DAT_MSK):
raise OneWireDeviceOperationError("No presence pulse detected")
def slot(self, port, bit):
data = ((port<<self.CSR_SEL_OFS) & self.CSR_SEL_MSK) | self.CSR_CYC_MSK | (bit & self.CSR_DAT_MSK)
self.wr_reg(self.R_CSR, data)
init_time=time.time()
while(self.rd_reg(self.R_CSR) & self.CSR_CYC_MSK):
if (time.time()-init_time) > self.WAIT_TIME_OUT:
raise OneWireDeviceOperationError("Wait timeout")
reg = self.rd_reg(self.R_CSR)
return reg & self.CSR_DAT_MSK
def read_bit(self, port):
return self.slot(port, 0x1)
def write_bit(self, port, bit):
return self.slot(port, bit)
def read_byte(self, port):
data = 0
for i in range(8):
data |= self.read_bit(port) << i
return data
def write_byte(self, port, byte):
data = 0
byte_old = byte
for i in range(8):
data |= self.write_bit(port, (byte & 0x1)) << i
byte >>= 1
if(byte_old != data):
raise OneWireDeviceOperationError("Error while checking written byte")
def write_block(self, port, block):
if(self.MAX_BLOCK_LEN < len(block)):
raise OneWireDeviceOperationError("Block too long")
data = []
for i in range(len(block)):
data.append(self.write_byte(port, block[i]))
return data
def read_block(self, port, length):
if(self.MAX_BLOCK_LEN < length):
raise OneWireDeviceOperationError("Block too long")
data = []
for i in range(length):
data.append(self.read_byte(port))
return data
#! /usr/bin/env python
# coding: utf8
class PtsException(Exception):
pass
class PtsCritical(PtsException):
"""critical error, abort the whole test suite"""
pass
class PtsError(PtsException):
"""error, continue remaining tests in test suite"""
pass
class PtsUser(PtsException):
"""error, user intervention required"""
pass
class PtsWarning(PtsException):
"""warning, a cautionary message should be displayed"""
pass
class PtsInvalid(PtsException):
"""reserved: invalid parameters"""
class PtsNoBatch(PtsInvalid):
"""reserved: a suite was created without batch of tests to run"""
pass
class PtsBadTestNo(PtsInvalid):
"""reserved: a bad test number was given"""
pass
if __name__ == '__main__':
pass
#! /usr/bin/env python
# :vi:ts=4 sw=4 et
from ctypes import *
import os, errno, re, sys, struct
import os.path
# python 2.4 kludge
if not 'SEEK_SET' in dir(os):
os.SEEK_SET = 0
# unsigned formats to unpack words
fmt = { 1: 'B', 2: 'H', 4: 'I', 8: 'L' }
# some defaults from rawrabbit.h
RR_DEVSEL_UNUSED = 0xffff
RR_DEFAULT_VENDOR = 0x1a39
RR_DEFAULT_DEVICE = 0x0004
RR_BAR_0 = 0x00000000
RR_BAR_2 = 0x20000000
RR_BAR_4 = 0x40000000
RR_BAR_BUF = 0xc0000000
bar_map = {
0 : RR_BAR_0,
2: RR_BAR_2,
4: RR_BAR_4,
0xc: RR_BAR_BUF }
# classes to interface with the driver via ctypes
Plist = c_int * 256
class RR_Devsel(Structure):
_fields_ = [
("vendor", c_ushort),
("device", c_ushort),
("subvendor", c_ushort),
("subdevice", c_ushort),
("bus", c_ushort),
("devfn", c_ushort),
]
class RR_U(Union):
_fields_ = [
("data8", c_ubyte),
("data16", c_ushort),
("data32", c_uint),
("data64", c_ulonglong),
]
class RR_Iocmd(Structure):
_anonymous_ = [ "data", ]
_fields_ = [
("address", c_uint),
("datasize", c_uint),
("data", RR_U),
]
def set_ld_library_path():
libpath = os.getenv('LD_LIBRARY_PATH')
here = os.getcwd()
libpath = here if not libpath else here + ':' + libpath
os.environ['LD_LIBRARY_PATH'] = libpath
class Gennum(object):
device = '/dev/rawrabbit'
rrlib = os.path.join(os.getcwd(), 'rrlib.so')
def __init__(self):
"""get a file descriptor for the Gennum device"""
set_ld_library_path()
self.lib = CDLL(Gennum.rrlib)
self.fd = os.open(Gennum.device, os.O_RDWR)
self.errno = 0
if self.fd < 0:
self.errno = self.fd
def iread(self, bar, offset, width):
"""do a read by means of the ioctl interface
bar = 0, 2, 4 (or c for DMA buffer access
offset = address within bar
width = data size (1, 2, 4 or 8 bytes)
"""
address = bar_map[bar] + offset
ds = RR_Iocmd(address=address, datasize=width)
self.errno = self.lib.rr_iread(self.fd, byref(ds))
return ds.data32
def read(self, bar, offset, width):
"""do a read by means of lseek+read
bar = 0, 2, 4 (or c for DMA buffer access
offset = address within bar
width = data size (1, 2, 4 or 8 bytes)
"""
address = bar_map[bar] + offset
self.errno = os.lseek(self.fd, address, os.SEEK_SET)
buf = os.read(self.fd, width)
return struct.unpack(fmt[width], buf)[0]
def iwrite(self, bar, offset, width, datum):
"""do a write by means of the ioctl interface
bar = 0, 2, 4 (or c for DMA buffer access
offset = address within bar
width = data size (1, 2, 4 or 8 bytes)
datum = value to be written
"""
address = bar_map[bar] + offset
ds = RR_Iocmd(address=address, datasize=width, data32=datum)
self.errno = self.lib.rr_iwrite(self.fd, byref(ds))
return ds.data32
def write(self, bar, offset, width, datum):
"""do a write by means of lseek+write
bar = 0, 2, 4 (or c for DMA buffer access
offset = address within bar
width = data size (1, 2, 4 or 8 bytes)
datum = value to be written
"""
address = bar_map[bar] + offset
self.errno = os.lseek(self.fd, address, os.SEEK_SET)
return os.write(self.fd, struct.pack(fmt[width], datum))
def irqwait(self):
"""wait for an interrupt"""
return self.lib.rr_irqwait(self.fd);
def irqena(self):
"""enable the interrupt line"""
return self.lib.rr_irqena(self.fd);
def getdmasize(self):
"""return the size of the allocated DMA buffer (in bytes)"""
return self.lib.rr_getdmasize(self.fd);
def getplist(self):
"""get a list of pages for DMA access
The addresses returned, shifted by 12 bits, give the physical
addresses of the allocated pages
"""
plist = Plist()
self.lib.rr_getplist(self.fd, plist);
return plist
def info(self):
"""get a string describing the interface the driver is bound to
The syntax of the string is
vendor:device/dubvendor:subdevice@bus:devfn
"""
ds = RR_Devsel()
self.errno = self.lib.rr_devget(self.fd, byref(ds))
for key in RR_Devsel._fields_:
setattr(self, key[0], getattr(ds, key[0], RR_DEVSEL_UNUSED))
return '%04x:%04x/%04x:%04x@%04x:%04x' % (
ds.vendor, ds.device,
ds.subvendor, ds.subdevice,
ds.bus, ds.devfn)
def parse_addr(self, addr):
"""take a string of the form
vendor:device[/subvendor:subdevice][@bus:devfn]
and return a dictionary object with the corresponding values,
initialized to RR_DEVSEL_UNUSED when absent
"""
# address format
reg = ( r'(?i)^'
r'(?P<vendor>[a-f0-9]{1,4}):(?P<device>[a-f0-9]{1,4})'
r'(/(?P<subvendor>[a-f0-9]{1,4}):(?P<subdevice>[a-f0-9]{1,4}))?'
r'(@(?P<bus>[a-f0-9]{1,4}):(?P<devfn>[a-f0-9]{1,4}))?$' )
match = re.match(reg, addr).groupdict()
if not 'sub' in match:
match['subvendor'] = match['subdevice'] = RR_DEVSEL_UNUSED
if not 'geo' in match:
match['bus'] = match['devfn'] = RR_DEVSEL_UNUSED
for k, v in match.items():
if type(v) is str:
match[k] = int(v, 16)
return match
def bind(self, device):
"""bind the rawrabbit driver to a device
The device is specified with a syntax described in parse_addr
"""
d = self.parse_addr(device)
ds = RR_Devsel(**d)
self.errno = self.lib.rr_devsel(self.fd, byref(ds))
return self.errno
if __name__ == '__main__':
g = Gennum()
print g.parse_addr('1a39:0004/1a39:0004@0020:0000')
print g.bind('1a39:0004/1a39:0004@0020:0000')
print '%x' % g.write(bar=RR_BAR_4, offset=0xa08, width=4, datum=0xdeadface)
print '%x' % g.read(bar=RR_BAR_4, offset=0xa08, width=4)
print g.getdmasize()
for page in g.getplist():
print '%08x ' % (page<<12),
#!/usr/bin/python
#coding: utf8
# Copyright Seven Solutions S.L., 2012
# Author: Tomasz?
# Author: Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Version: 0.1 (Last modifications: 1/4/2012)
from ptsexcept import *
from dio_fmc import *
import rr
import os
"""
test00: Check fmc-dio-5chttl-board EEPROM and DAC presence and temperature-sensor operation
Conditions: I2C bus and OneWire bus work
User intervention required: No
Procedure details:
- Load firmware
- Test mezzanine presence line.
- Initialize the board and its peripherals
- Check that I2C devices (EEPROM (24AA64T) and DAC (DAC5578)) are present
- Check that OneWire device (temperature sensor (DS18B20)) is present and responds
- Check temperature sensor ID
- Check temperature acquisition.
"""
class test00:
def __init__(self, spec):
""" Initialize the board, check PRESENT pin state and look for I2C devices """
try:
self.dio = CFmcDio(spec, 0x80000, True)
except CFmcDioError as e:
err_msg="While fmc-dio-5chttla initialization: "+str(e)
if e.bus_name == "FMC":
raise PtsCritical(err_msg) # Critical error: the fmc-dio-5chttl-board is apparently not present
else:
raise PtsError(err_msg) # Non-critical error: further tests could be performed successfully
def test_temp(self):
""" Check OneWire device response correctly and check temperature acquisition """
try:
uid = self.dio.get_unique_id()
except CFmcDioError as e:
print str(e)
emsg="While getting DS18B20 chip ID: "+str(e)
else:
try:
print ("FMC temperature: %3.3f°C" % self.dio.get_temp())
except CFmcDioError as e:
print str(e)
emsg="While getting temperature with DS18B20 chip: "+str(e)
else:
emsg=None # test completed successfully
return emsg
def main(default_directory="."):
# Configure the FPGA using the program fpga_loader
path_fpga_loader = '../firmwares/fpga_loader'
path_firmware = '../firmwares/spec_top.bin'
firmware_loader = os.path.join(default_directory, path_fpga_loader)
bitstream = os.path.join(default_directory, path_firmware)
print "Loading firmware: %s" % (firmware_loader + ' ' + bitstream)
os.system( firmware_loader + ' ' + bitstream )
# Load board library and open the corresponding device
print "Loading hardware access library and opening device\n"
spec = rr.Gennum()
print "Test Start"
init_test_time = time.time()
print "Configuring and checking fmc-dio-5chttla devices"
test=test00(spec)
print "\nChecking temperature acquisition"
emsg=test.test_temp()
end_test_time = time.time()
print "\nEnd of Test"
print "RESULT: [{}]".format("FAIL" if emsg else "OK")
print 'Test03 elapsed time: {:.2f} seconds'.format(end_test_time-init_test_time)
if emsg:
raise PtsError(emsg)
if __name__ == "__main__":
main(".")
#!/usr/bin/python
#coding: utf8
# Copyright Seven Solutions S.L., 2012
# Author: Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Version: 0.1 (Last modifications: 1/4/2012)
from ptsexcept import *
from dio_fmc import *
from keyb import *
import rr
import os
import sys
"""
test01: Check fmc-dio-5chttl-board LEDs (LED and LED circuit working)
Conditions: None
User intervention required: Yes
Procedure details:
- Load firmware
- Test mezzanine presence line
- Blink fmc-dio-5chttl-board LEDs
"""
class test01:
def __init__(self, spec):
""" check FMC PRESENT-pin state """
try:
self.dio = CFmcDio(spec, 0x80000, False)
except CFmcDioError as e:
err_msg="While fmc-dio-5chttla initialization: "+str(e)
if e.bus_name == "FMC":
raise PtsCritical(err_msg) # Critical error: the fmc-dio-5chttl-board is apparently not present
else:
raise PtsError(err_msg) # Non-critical error: further tests could be performed successfully
def test_LEDs(self):
""" LED-blink Check """
tmp_stdout = sys.stdout
sys.stdout = sys.__stdout__
tmp_stdin = sys.stdin
sys.stdin = sys.__stdin__
print "¿Are the two fmc-dio-5chttla-board LEDs blinking alternately?"
print "Press Y/N and Enter"
ans=""
while ans != "Y" and ans != "N":
for nled in range(2):
self.dio.set_led(nled,nled)
time.sleep(0.2)
for nled in range(2):
self.dio.set_led(nled,1-nled)
time.sleep(0.2)
if kbhit():
ans=raw_input().upper()
if ans <> "Y" and ans <> "N":
print "The valid inputs are only Y or N and Enter"
sys.stdout = tmp_stdout
sys.stdin = tmp_stdin
# purgestdin()
for nled in range(2):
self.dio.set_led(nled,0)
print "The user reported {} operation of board LEDs".format("a correct" if ans=="Y" else "an incorrect")
if ans == "N":
emsg="TSTERR00: Operation of fmc-dio-5chttla-board LEDs failed"
print emsg
else:
emsg=None # test completed successfully
return emsg
def main(default_directory="."):
# Configure the FPGA using the program fpga_loader
path_fpga_loader = '../firmwares/fpga_loader'
path_firmware = '../firmwares/spec_top.bin'
firmware_loader = os.path.join(default_directory, path_fpga_loader)
bitstream = os.path.join(default_directory, path_firmware)
print "Loading firmware: %s" % (firmware_loader + ' ' + bitstream)
os.system( firmware_loader + ' ' + bitstream )
# Load board library and open the corresponding device
print "Loading hardware access library and opening device\n"
spec = rr.Gennum()
print "Test Start"
print "Checking fmc-dio-5chttla board presence"
test=test01(spec)
print "\nChecking LEDs"
emsg=test.test_LEDs()
print "\nEnd of Test"
print "RESULT: [{}]".format("FAIL" if emsg else "OK")
if emsg:
raise PtsError(emsg)
if __name__ == "__main__":
main(".")
#!/usr/bin/python
#coding: utf8
# Copyright Seven Solutions S.L., 2012
# Author: Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Version: 0.1 (Last modifications: 1/4/2012)
from ptsexcept import *
from dio_fmc import *
from keyb import *
import rr
import os
"""
test02: Check fmc-dio-5chttl-board ports as output (port driver working, connector connectivity and LVDS to LVCMOS IC working)
Conditions: fmc-dio-5chttl-board presence line working
User intervention required: Yes
Procedure details:
- Load firmware.
- Test mezzanine presence line.
- Oscillate state of fmc-dio-5chttl-board ports
"""
class test02:
def __init__(self, spec):
""" check FMC PRESENT-pin state """
try:
self.dio = CFmcDio(spec, 0x80000, False)
except CFmcDioError as e:
err_msg="While fmc-dio-5chttla initialization: "+str(e)
if e.bus_name == "FMC":
raise PtsCritical(err_msg) # Critical error: the fmc-dio-5chttl-board is apparently not present
else:
raise PtsError(err_msg) # Non-critical error: further tests could be performed successfully
def osc_ports(self):
""" Oscillate state of fmc-dio-5chttl-board ports """
for lemon in range(5): # Enable output of all ports and set them to 0
self.dio.set_out(lemon,0)
self.dio.set_dir(lemon,1)
ans=""
lemon=0
while ans != "Y" and ans != "N":
time.sleep(0.05)
self.dio.set_out((lemon-1)%5,0)
self.dio.set_out(lemon,1)
lemon=(lemon+1)%5
if kbhit():
ans=raw_input().upper()
if ans <> "Y" and ans <> "N":
print "The valid inputs are only Y or N and Enter"
for lemon in range(5): # Disable output of all ports
self.dio.set_out(lemon, 0)
self.dio.set_dir(lemon, 0)
return ans
def test_port_out(self):
""" Port (LEMO 00 connectors) oscillation check """
tmp_stdout = sys.stdout
sys.stdout = sys.__stdout__
tmp_stdin = sys.stdin
sys.stdin = sys.__stdin__
print "Connect the testing LEDs to the LEMO 00 connectors of the fmc-dio-5chttla-board ports (120ohm serial resistor included)"
print "¿Are all the connected testing LEDs blinking alternately?"
print "Press Y/N and Enter"
for lemon in range(5): # Disable all termination resistors
self.dio.set_term(lemon, 0)
ans=self.osc_ports()
# purgestdin()
raw_input("Disconnect the red LEDs from the fmc-dio-5chttla-board ports (in order to perform further tests) and press Enter")
sys.stdout = tmp_stdout
sys.stdin = tmp_stdin
print "The user reported {} operation of board-port outputs".format("a correct" if ans=="Y" else "an incorrect")
if ans == "N":
emsg="TSTERR01: Operation of fmc-dio-5chttla-board ports as output failed"
print emsg
else:
emsg=None # test completed successfully
return emsg
def main(default_directory="."):
# Configure the FPGA using the program fpga_loader
path_fpga_loader = '../firmwares/fpga_loader'
path_firmware = '../firmwares/spec_top.bin'
firmware_loader = os.path.join(default_directory, path_fpga_loader)
bitstream = os.path.join(default_directory, path_firmware)
print "Loading firmware: %s" % (firmware_loader + ' ' + bitstream)
os.system( firmware_loader + ' ' + bitstream )
# Load board library and open the corresponding device
print "Loading hardware access library and opening device\n"
spec = rr.Gennum()
print "Test Start"
print "Checking fmc-dio-5chttla board presence"
test=test02(spec)
print "\nChecking connectivity of board ports"
emsg=test.test_port_out()
print "\nEnd of Test"
print "RESULT: [{}]".format("FAIL" if emsg else "OK")
if emsg:
raise PtsError(emsg)
if __name__ == "__main__":
main(".")
#!/usr/bin/python
#coding: utf8
# Copyright Seven Solutions S.L., 2012
# Author: Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Version: 0.1 (Last modifications: 1/4/2012)
from ptsexcept import *
from dio_fmc import *
import rr
import os
"""
test03: Check fmc-dio-5chttl-board ports as inputs (DAC, LVDS comparator)
Conditions: fmc-dio-5chttl-board ports work as outputs (test02 passed) and I2C bus works (test00 passed)
User intervention required: No
Procedure details:
- Load firmware.
- Test mezzanine presence line.
- Check the voltage of all ports (be means of the DAC) when port output set to 0 and when it is set to 1
"""
class test03:
def __init__(self, spec):
""" check FMC PRESENT-pin state """
try:
self.dio = CFmcDio(spec, 0x80000, True)
except CFmcDioError as e:
err_msg="While fmc-dio-5chttla initialization: "+str(e)
if e.bus_name == "FMC":
raise PtsCritical(err_msg) # Critical error: the fmc-dio-5chttl-board is apparently not present
else:
raise PtsError(err_msg) # Non-critical error: further tests could be performed successfully
def test_port_in(self):
""" Port (LEMO 00 connectors) input check """
print "Ensure that nothing is connected to the fmc-dio-5chttla-board ports"
print "(Termination resistors disabled, port outputs enabled)"
port_th=[]
port_warnlow=[]
port_warnhigh=[]
for lemon in range(5):
self.dio.set_term(lemon, 0) # Disable termination resistor
self.dio.set_out(lemon,0) # set port output value to 0
self.dio.set_dir(lemon,1) # Enable port output
try:
th0=self.dio.find_port_voltage(lemon,0.0,0.08) # Find the voltage (threshold) when out=0
self.dio.set_out(lemon,1) # set port output state to 1
th1=self.dio.find_port_voltage(lemon,3.28,3.3) # Find the voltage (threshold) when out=1
except CFmcDioError as e:
print str(e)
raise PtsError("While setting CDAC5578 channel value: "+str(e))
self.dio.set_dir(lemon,0) # Disable port output
if th0>0.1:
th0_warn="Warning: Strangely-high value "
port_warnhigh.append(lemon)
else:
th0_warn="OK "
if th1<3.2:
th1_warn="Warning: Strangely-low value "
port_warnlow.append(lemon)
else:
th1_warn="OK"
print "Port {} apparent input voltage when out=0: {:.3f}V {}".format(lemon,th0,th0_warn)
print "\t\t\t when out=1: {:.3f}V {}".format(th1,th1_warn)
port_th.insert(lemon,[th0,th1])
port_err=[]
for lemon in range(len(port_th)):
if port_th[lemon][0]>0.8 or port_th[lemon][1]<2.0: # normal operating conditions
port_err.append(lemon)
if port_err: # Some errors were detected
ret_error=["E","TSTERR02: Proper voltage reading not obtained in ports: {} when output enable=1".format(port_err)]
print ret_error[1]
else:
if port_warnlow or port_warnhigh: # Some warning were generated
warn_msg=""
if port_warnlow:
warn_msg=warn_msg+"TSTWRN00: Strangely-low voltage value obtained in ports: {} when output=1. ".format(port_warnlow)
if port_warnhigh:
warn_msg=warn_msg+"TSTWRN01: Strangely-high voltage value obtained in ports: {} when output=0. ".format(port_warnhigh)
ret_error=["W",warn_msg]
else:
ret_error=None
return ret_error
def main(default_directory="."):
# Configure the FPGA using the program fpga_loader
path_fpga_loader = '../firmwares/fpga_loader'
path_firmware = '../firmwares/spec_top.bin'
firmware_loader = os.path.join(default_directory, path_fpga_loader)
bitstream = os.path.join(default_directory, path_firmware)
print "Loading firmware: %s" % (firmware_loader + ' ' + bitstream)
os.system( firmware_loader + ' ' + bitstream )
# Load board library and open the corresponding device
print "Loading hardware access library and opening device\n"
spec = rr.Gennum()
print "Test Start"
init_test_time = time.time()
print "Configuring and checking fmc-dio-5chttla devices"
test=test03(spec)
print "\nChecking input operation of board ports"
ret_error=test.test_port_in()
end_test_time = time.time()
print "\nEnd of Test"
print "RESULT: [{}]".format("FAIL" if ret_error and ret_error[0]=="E" else ("OK with warnings" if ret_error and ret_error[0]=="W" else "OK"))
print 'Test03 elapsed time: {:.2f} seconds'.format(end_test_time-init_test_time)
if ret_error:
if ret_error[0]=="W": # Warning message returned by test funciton
raise PtsWarning(ret_error[1])
else: # Error message returned by test funciton
raise PtsError(ret_error[1])
if __name__ == "__main__":
main(".")
#!/usr/bin/python
#coding: utf8
# Copyright Seven Solutions S.L., 2012
# Author: Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Version: 0.1 (Last modifications: 1/4/2012)
from ptsexcept import *
from dio_fmc import *
import rr
import os
"""
test04: Check output-enable circuit of fmc-dio-5chttl-board ports
Conditions: fmc-dio-5chttl-board ports work as outputs (test02 passed), I2C bus works (test00 passed) and
fmc-dio-5chttl-board ports work as inputs (DAC, LVDS comparator) (test03 passed)
User intervention required: No
Procedure details:
- Load firmware.
- Test mezzanine presence line.
- Check the voltage of all ports (be means of the DAC) when port output set to 1 and output enable set to 0
"""
class test04:
def __init__(self, spec):
""" check FMC PRESENT-pin state """
try:
self.dio = CFmcDio(spec, 0x80000, True)
except CFmcDioError as e:
err_msg="While fmc-dio-5chttla initialization: "+str(e)
if e.bus_name == "FMC":
raise PtsCritical(err_msg) # Critical error: the fmc-dio-5chttl-board is apparently not present
else:
raise PtsError(err_msg) # Non-critical error: further tests could be performed successfully
def test_port_oe(self):
""" Port (LEMO 00 connectors) output-enable check """
print "Ensure that nothing is connected to the fmc-dio-5chttla-board ports"
print "(Termination resistors disabled, port outputs disabled)"
port_th=[]
port_warnhigh=[]
for lemon in range(5):
self.dio.set_term(lemon, 1) # Enable termination resistor to accelerate port state change to 0
self.dio.set_dir(lemon,0) # Disable port output
self.dio.set_out(lemon,1) # set port output value to 1
self.dio.set_term(lemon, 0) # Disable termination resistor (when port output is stable)
try:
th0=self.dio.find_port_voltage(lemon,0.0,0.08) # Find the voltage (threshold)
except CFmcDioError as e:
print str(e)
raise PtsError("While setting CDAC5578 channel value: "+str(e))
self.dio.set_dir(lemon,0) # Disable port output
self.dio.set_out(lemon,0) # set port output value to 0
if th0>0.1:
th0_warn="Warning: Strangely-high value "
port_warnhigh.append(lemon)
else:
th0_warn="OK "
print "Port {} apparent input voltage: {:.3f}V {}".format(lemon,th0,th0_warn)
port_th.insert(lemon,th0)
port_err=[]
for lemon in range(len(port_th)):
if port_th[lemon]>0.8: # normal operating conditions
port_err.append(lemon)
if port_err: # Some errors were detected
ret_error=["E","TSTERR03: Proper voltage reading not obtained in ports: {} when output enable=0".format(port_err)]
print ret_error[1]
else:
if port_warnhigh: # Some warning were generated
warn_msg="TSTWRN02: Strangely-high voltage value obtained in ports: {} when output enable=0".format(port_warnhigh)
ret_error=["W",warn_msg]
else:
ret_error=None
return ret_error
def main(default_directory="."):
# Configure the FPGA using the program fpga_loader
path_fpga_loader = '../firmwares/fpga_loader'
path_firmware = '../firmwares/spec_top.bin'
firmware_loader = os.path.join(default_directory, path_fpga_loader)
bitstream = os.path.join(default_directory, path_firmware)
print "Loading firmware: %s" % (firmware_loader + ' ' + bitstream)
os.system( firmware_loader + ' ' + bitstream )
# Load board library and open the corresponding device
print "Loading hardware access library and opening device\n"
spec = rr.Gennum()
print "Test Start"
init_test_time = time.time()
print "Configuring and checking fmc-dio-5chttla devices"
test=test04(spec)
print "\nChecking output-enable circuits of board ports"
ret_error=test.test_port_oe()
end_test_time = time.time()
print "\nEnd of Test"
print "RESULT: [{}]".format("FAIL" if ret_error and ret_error[0]=="E" else ("OK with warnings" if ret_error and ret_error[0]=="W" else "OK"))
print 'Test04 elapsed time: {:.2f} seconds'.format(end_test_time-init_test_time)
if ret_error:
if ret_error[0]=="W": # Warning message returned by test funciton
raise PtsWarning(ret_error[1])
else: # Error message returned by test funciton
raise PtsError(ret_error[1])
if __name__ == "__main__":
main(".")
#!/usr/bin/python
#coding: utf8
# Copyright Seven Solutions S.L., 2012
# Author: Richard Carrillo <rcarrillo(AT)sevensols.com>
# Licence: GPL v2 or later.
# Website: http://www.ohwr.org
# Website: http://www.sevensols.com
# Version: 0.1 (Last modifications: 1/4/2012)
from ptsexcept import *
from dio_fmc import *
import rr
import os
"""
test05: Check termination resistors of fmc-dio-5chttl-board ports
Conditions: fmc-dio-5chttl-board ports work as outputs (test02 passed), I2C bus works (test00 passed) and
fmc-dio-5chttl-board ports work as inputs (DAC, LVDS comparator) (test03 passed)
User intervention required: No
Procedure details:
- Load firmware.
- Test mezzanine presence line.
- Check the voltage of all ports (be means of the DAC) when port output set to 1, output enable set to 0
and termination resistor enabled
"""
class test05:
def __init__(self, spec):
""" check FMC PRESENT-pin state """
try:
self.dio = CFmcDio(spec, 0x80000, True)
except CFmcDioError as e:
err_msg="While fmc-dio-5chttla initialization: "+str(e)
if e.bus_name == "FMC":
raise PtsCritical(err_msg) # Critical error: the fmc-dio-5chttl-board is apparently not present
else:
raise PtsError(err_msg) # Non-critical error: further tests could be performed successfully
def test_port_term(self):
""" Port (LEMO 00 connectors) termination-resistor enable check """
print "Ensure that nothing is connected to the fmc-dio-5chttla-board ports"
print "(Termination resistors enabled, port outputs enabled)"
port_th=[]
port_warnlow=[]
port_warnhigh=[]
for lemon in range(5):
self.dio.set_term(lemon, 1) # Enable termination resistor
self.dio.set_dir(lemon,1) # Enable port output
self.dio.set_out(lemon,1) # Set port output value to 1
try:
th1=self.dio.find_port_voltage(lemon,2.95,3.02) # Find the voltage (threshold)
except CFmcDioError as e:
raise PtsError("While setting CDAC5578 channel value: "+str(e))
self.dio.set_dir(lemon,0) # Disable port output
self.dio.set_out(lemon,0) # Set port output value to 0
self.dio.set_term(lemon, 0) # Disable termination resistor
if th1>3.1:
th1_warn="Warning: Strangely-high value "
port_warnhigh.append(lemon)
elif th1<2.9:
th1_warn="Warning: Strangely-low value "
port_warnlow.append(lemon)
else:
th1_warn="OK"
print "Port {} apparent input voltage: {:.3f}V {}".format(lemon,th1,th1_warn)
port_th.insert(lemon,th1)
port_err=[]
for lemon in range(len(port_th)):
if port_th[lemon]>3.2 or port_th[lemon]<2.8: # normal operating conditions
port_err.append(lemon)
if port_err: # Some errors were detected
ret_error=["E","TSTERR04: Proper voltage reading not obtained in ports: {} when termination resistors enabled".format(port_err)]
print ret_error[1]
else:
if port_warnlow or port_warnhigh: # Some warning were generated
warn_msg=""
if port_warnlow:
warn_msg=warn_msg+"TSTWRN03: Strangely-low voltage value obtained in ports: {} when termination resistors enabled. ".format(port_warnlow)
if port_warnhigh:
warn_msg=warn_msg+"TSTWRN04: Strangely-high voltage value obtained in ports: {} when termination resistors enabled. ".format(port_warnhigh)
ret_error=["W",warn_msg]
else:
ret_error=None
return ret_error
def main(default_directory="."):
# Configure the FPGA using the program fpga_loader
path_fpga_loader = '../firmwares/fpga_loader'
path_firmware = '../firmwares/spec_top.bin'
firmware_loader = os.path.join(default_directory, path_fpga_loader)
bitstream = os.path.join(default_directory, path_firmware)
print "Loading firmware: %s" % (firmware_loader + ' ' + bitstream)
os.system( firmware_loader + ' ' + bitstream )
# Load board library and open the corresponding device
print "Loading hardware access library and opening device\n"
spec = rr.Gennum()
print "Test Start"
init_test_time = time.time()
print "Configuring and checking fmc-dio-5chttla devices"
test=test05(spec)
print "\nChecking output-enable circuits of board ports"
ret_error=test.test_port_term()
end_test_time = time.time()
print "\nEnd of Test"
print "RESULT: [{}]".format("FAIL" if ret_error and ret_error[0]=="E" else ("OK with warnings" if ret_error and ret_error[0]=="W" else "OK"))
print 'Test05 elapsed time: {:.2f} seconds'.format(end_test_time-init_test_time)
if ret_error:
if ret_error[0]=="W": # Warning message returned by test funciton
raise PtsWarning(ret_error[1])
else: # Error message returned by test funciton
raise PtsError(ret_error[1])
if __name__ == "__main__":
main(".")
#!/usr/bin/python
#simple driver for (x)wb_gpio_port from general-cores library
class CGPIO:
def __init__(self, bus, base):
self.bus =bus
self.base = base
#returns the value on pin pin
def inp(self, pin):
bank= 0x20 * (pin / 32);
r = self.rd_reg(0, self.base + bank + 0xc);
return (r >> pin) & 1;
#sets the pin "pin" to value "val"
def outp(self, pin, val):
bank= 0x20 * (pin >> 5);
if(val):
self.wr_reg(0, self.base + bank + 0x4, (1<<(pin&0x1f)))
else:
self.wr_reg(0, self.base + bank + 0x0, (1<<(pin&0x1f)))
# rd_reg and wr_reg are defined here in order not to comflict with original function definitions of file rr.py
def rd_reg(self, bar, addr):
return self.bus.iread(bar, addr, 4)
def wr_reg(self, bar, addr, value):
self.bus.iwrite(bar, addr, 4, value)
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