Merge branch 'master' of gitorious.psi.ch:sls_det_software/sls_detector_software

This commit is contained in:
Maliakal Dhanya 2014-10-14 15:39:11 +02:00
commit 0896fb137f
30 changed files with 10503 additions and 0 deletions

View File

@ -0,0 +1 @@
AXIS_BUILDTYPE ?= cris-axis-linux-gnu

View File

@ -0,0 +1,48 @@
# $Id: Makefile,v 1.1.1.1 2006/02/04 03:35:01 freza Exp $
# first compile
# make cris-axis-linux-gnu
CROSS = bfin-uclinux-
CC = $(CROSS)gcc
CFLAGS += -Wall -DMOENCHD -DMCB_FUNCS -DDACS_INT -DDEBUG #-DVERBOSE #-DVERYVERBOSE #-DVIRTUAL #-DDACS_INT_CSERVER
PROGS= jungfrauDetectorServer
INSTDIR= /tftpboot
INSTMODE= 0777
BINS = testlib_sharedlibc
SRCS = server.c server_funcs.c communication_funcs.c firmware_funcs.c mcb_funcs.c trimming_funcs.c sharedmemory.c
OBJS = $(SRCS:%.c=%.o)
all: clean $(PROGS)
boot: $(OBJS)
$(PROGS): $(OBJS)
echo $(OBJS)
$(CC) $(CFLAGS) -o $@ $^ $(LDLIBS_$@) $(LDFLAGS_$@)
install: $(PROGS)
$(INSTALL) -d $(INSTDIR)
$(INSTALL) -m $(INSTMODE) $(PROGS) $(INSTDIR)
romfs:
$(ROMFSINST) /bin/$(PROGS)
clean:
rm -rf $(PROGS) *.o *.gdb

View File

@ -0,0 +1,30 @@
DESTDIR ?= ./
CC = gcc
CFLAGS += -Wall -DMOENCHD -DMCB_FUNCS -DDACS_INT -DDEBUG -DVIRTUAL
PROGS= $(DESTDIR)/moenchVirtualServer
SRCS = server.c server_funcs.c communication_funcs.c firmware_funcs.c mcb_funcs.c trimming_funcs.c sharedmemory.c
OBJS = $(SRCS:%.c=%.o)
moenchVirtualServer = $(PROGS)
all: clean $(PROGS)
$(PROGS): $(OBJS)
$(CC) $(CFLAGS) -o $@ $^ $(LDLIBS_$@) $(LDFLAGS_$@)
clean:
rm -rf $(PROGS) *.o *.gdb

View File

@ -0,0 +1 @@
../commonFiles/communication_funcs.c

View File

@ -0,0 +1 @@
../commonFiles/communication_funcs.h

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,179 @@
#ifndef FIRMWARE_FUNCS_H
#define FIRMWARE_FUNCS_H
#include "sls_detector_defs.h"
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/mman.h>
#include <fcntl.h>
#include <stdarg.h>
#include <unistd.h>
//#include <asm/page.h>
#include <sys/mman.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <stdarg.h>
#include <unistd.h>
int mapCSP0(void);
u_int16_t bus_r16(u_int32_t offset);
u_int16_t bus_w16(u_int32_t offset, u_int16_t data);//aldos function
u_int32_t bus_w(u_int32_t offset, u_int32_t data);
u_int32_t bus_r(u_int32_t offset);
int setPhaseShiftOnce();
int phaseStep(int st);
int cleanFifo();
int setDAQRegister();
u_int32_t putout(char *s, int modnum);
u_int32_t readin(int modnum);
u_int32_t setClockDivider(int d);
u_int32_t getClockDivider();
u_int32_t setSetLength(int d);
u_int32_t getSetLength();
u_int32_t setWaitStates(int d);
u_int32_t getWaitStates();
u_int32_t setTotClockDivider(int d);
u_int32_t getTotClockDivider();
u_int32_t setTotDutyCycle(int d);
u_int32_t getTotDutyCycle();
u_int32_t setOversampling(int d);
u_int32_t setExtSignal(int d, enum externalSignalFlag mode);
int getExtSignal(int d);
u_int32_t setFPGASignal(int d, enum externalSignalFlag mode);
int getFPGASignal(int d);
int setTiming(int t);
int setConfigurationRegister(int d);
int setToT(int d);
int setContinousReadOut(int d);
int startReceiver(int d);
int setDACRegister(int idac, int val, int imod);
int getTemperature(int tempSensor,int imod);
int initHighVoltage(int val,int imod);
int initConfGain(int isettings,int val,int imod);
int setADC(int adc);
int configureMAC(int ipad, long long int macad, long long int detectormacadd, int detipad, int ival, int udpport);
int getAdcConfigured();
u_int64_t getDetectorNumber();
u_int32_t getFirmwareVersion();
int testFifos(void);
u_int32_t testFpga(void);
u_int32_t testRAM(void);
int testBus(void);
int setDigitalTestBit(int ival);
int64_t set64BitReg(int64_t value, int aLSB, int aMSB);
int64_t get64BitReg(int aLSB, int aMSB);
int64_t setFrames(int64_t value);
int64_t getFrames();
int64_t setExposureTime(int64_t value);
int64_t getExposureTime();
int64_t setGates(int64_t value);
int64_t getGates();
int64_t setDelay(int64_t value);
int64_t getDelay();
int64_t setPeriod(int64_t value);
int64_t getPeriod();
int64_t setTrains(int64_t value);
int64_t getTrains();
int64_t setProbes(int64_t value);
int64_t getProbes();
int64_t getProgress();
int64_t setProgress();
int64_t getActualTime();
int64_t getMeasurementTime();
u_int32_t runBusy(void);
u_int32_t runState(void);
u_int32_t dataPresent(void);
int startStateMachine();
int stopStateMachine();
int startReadOut();
u_int32_t fifoReset(void);
u_int32_t fifoReadCounter(int fifonum);
u_int32_t fifoReadStatus();
u_int32_t fifo_full(void);
u_int32_t* fifo_read_event();
u_int32_t* decode_data(int* datain);
//u_int32_t move_data(u_int64_t* datain, u_int64_t* dataout);
int setDynamicRange(int dr);
int getDynamicRange();
int getNModBoard();
int setNMod(int n);
int setStoreInRAM(int b);
int allocateRAM();
int clearRAM();
int setMaster(int f);
int setSynchronization(int s);
int loadImage(int index, short int ImageVals[]);
int readCounterBlock(int startACQ, short int CounterVals[]);
int resetCounterBlock(int startACQ);
int calibratePedestal(int frames);
/*
u_int32_t setNBits(u_int32_t);
u_int32_t getNBits();
*/
/*
//move to mcb_funcs?
int readOutChan(int *val);
u_int32_t getModuleNumber(int modnum);
int testShiftIn(int imod);
int testShiftOut(int imod);
int testShiftStSel(int imod);
int testDataInOut(int num, int imod);
int testExtPulse(int imod);
int testExtPulseMux(int imod, int ow);
int testDataInOutMux(int imod, int ow, int num);
int testOutMux(int imod);
int testFpgaMux(int imod);
int calibration_sensor(int num, int *values, int *dacs) ;
int calibration_chip(int num, int *values, int *dacs);
*/
#endif

View File

@ -0,0 +1,9 @@
Path: slsDetectorsPackage/slsDetectorSoftware/moenchDetectorServer
URL: origin git@gitorious.psi.ch:sls_det_software/sls_detector_software.git/moenchDetectorServer
Repository Root: origin git@gitorious.psi.ch:sls_det_software/sls_detector_software.git
Repsitory UUID: 046a469b1e6582c4c55bd6eaeb4818b618d0a9a9
Revision: 55
Branch: separate_receiver
Last Changed Author: Maliakal_Dhanya
Last Changed Rev: 14
Last Changed Date: 2014-06-03 12:26:45 +0200

View File

@ -0,0 +1,11 @@
//#define SVNPATH ""
#define SVNURL "git@gitorious.psi.ch:sls_det_software/sls_detector_software.git/moenchDetectorServer"
//#define SVNREPPATH ""
#define SVNREPUUID "046a469b1e6582c4c55bd6eaeb4818b618d0a9a9"
//#define SVNREV 0x14
//#define SVNKIND ""
//#define SVNSCHED ""
#define SVNAUTH "Maliakal_Dhanya"
#define SVNREV 0x14
#define SVNDATE 0x20140603
//

View File

@ -0,0 +1,11 @@
//#define SVNPATH ""
#define SVNURL ""
//#define SVNREPPATH ""
#define SVNREPUUID ""
//#define SVNREV ""
//#define SVNKIND ""
//#define SVNSCHED ""
#define SVNAUTH ""
#define SVNREV ""
#define SVNDATE ""
//

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,174 @@
#ifdef MCB_FUNCS
#ifndef MCB_FUNCS_H
#define MCB_FUNCS_H
#include "sls_detector_defs.h"
#define RGPRVALS {100,50,200}
#define RGSH1VALS {300,200,400}
#define RGSH2VALS {260,300,260}
//high,dynamic,low,medium,very high
#define CONF_GAIN {0,0, 0, 1, 6, 2, 1}//dynamic gain confgain yet to be figured out-probably 8 or 16
#define DEFAULTGAIN {11.66,9.32,14.99}
#define DEFAULTOFFSET {817.5,828.6,804.2}
// DAC definitions
enum dacsVal{VDAC0, VDAC1, VDAC2, VDAC3, VDAC4, VDAC5, VDAC6, VDAC7, HIGH_VOLTAGE, CONFGAIN};
/* DAC adresses */
#define DACCS {0,0,1,1,2,2,3,3,4,4,5,5,6,6}
#define DACADDR {0,1,0,1,0,1,0,1,0,1,0,1,0,1}
//Register Definitions for temp,hv,dac gain
enum adcVals{TEMP_FPGA, TEMP_ADC};
//dynamic range
/*
#define MAX5523 commented out by dhanya
#ifndef MAX5523
#define MAX5533
#endif
#ifdef MAX5533
#define DAC_DR 4096
#endif
#ifdef MAX5523
*/
#define DAC_DR 1024
//#endif
//reference voltage
#define DAC_REFOUT1
#ifdef DAC_REFOUT2
#define DAC_MAX 2.425
#define DAC_REFOUT 2
#define DAC_REFOUT1
#endif
#ifdef DAC_REFOUT3
#define DAC_MAX 3.885
#define DAC_REFOUT 3
#define DAC_REFOUT1
#endif
#ifdef DAC_REFOUT0
#define DAC_MAX 1.214
#define DAC_REFOUT 0
#endif
#ifdef DAC_REFOUT1
#define DAC_MAX 1.940
#define DAC_REFOUT 1
#endif
/* dac calibration constants */
#define VA 1.11
#define CVTRIM 52.430851
#define BVTRIM -0.102022
#define AVTRIM 0.000050
#define PARTREF {100,1.55,-2.5,-2.5,0,-2.5}
#define PARTR1 {78,10,10,10,10,10}
#define PARTR2 {0,4.7,27,47,22,47}
//chip shiftin register meaning
#define OUTMUX_OFFSET 20
#define PROBES_OFFSET 4
#define OUTBUF_OFFSET 0
void showbits(int h);
int initDetector();
int copyChannel(sls_detector_channel *destChan, sls_detector_channel *srcChan);
int copyChip(sls_detector_chip *destChip, sls_detector_chip *srcChip);
int copyModule(sls_detector_module *destMod, sls_detector_module *srcMod);
/* Register commands */
int clearDACSregister(int imod );
int nextDAC(int imod );
int clearCSregister(int imod );
int setCSregister(int imod );
int nextChip(int imod );
int firstChip(int imod );
int clearSSregister(int imod );
int setSSregister(int imod );
int nextStrip(int imod );
int selChannel(int strip,int imod );
int selChip(int chip,int imod );
int selMod(int mod,int imod );
/* DACs routines */
int program_one_dac(int addr, int value,int imod );
int set_one_dac(int imod);
int initDAC(int dac_addr, int value,int imod );
int initDACs(int* v,int imod );
int setSettings(int i,int imod);
int initDACbyIndex(int ind,int val, int imod);
int initDACbyIndexDACU(int ind,int val, int imod);
int getDACbyIndexDACU(int ind, int imod);
int getThresholdEnergy();
int setThresholdEnergy(int ethr);
/* Other DAC index routines*/
int getTemperatureByModule(int tempSensor, int imod);
int initHighVoltageByModule(int val, int imod);
int initConfGainByModule(int isettings,int val,int imod);
/* Initialization*/
int initChannel(int ft,int cae, int ae, int coe, int ocoe, int counts,int imod );
int initChannelbyNumber(sls_detector_channel myChan);
int getChannelbyNumber(sls_detector_channel*);
int getTrimbit(int imod, int ichip, int ichan);
int initChip(int obe, int ow,int imod );
int initChipWithProbes(int obe, int ow,int nprobes, int imod);
//int getNProbes();
int initChipbyNumber(sls_detector_chip myChip);
int getChipbyNumber(sls_detector_chip*);
int initMCBregisters(int cm,int imod );
int initModulebyNumber(sls_detector_module);
int getModulebyNumber(sls_detector_module*);
/* To chips */
int clearCounter(int imod );
int clearOutReg(int imod);
int setOutReg(int imod );
int extPulse(int ncal,int imod );
int calPulse(int ncal,int imod );
int counterClear(int imod );
int countEnable(int imod );
int counterSet(int imod );
/* moved from firmware_funcs */
int readOutChan(int *val);
int getModuleNumber(int modnum);
int testShiftIn(int imod);
int testShiftOut(int imod);
int testShiftStSel(int imod);
int testDataInOut(int num, int imod);
int testExtPulse(int imod);
int testExtPulseMux(int imod, int ow);
int testDataInOutMux(int imod, int ow, int num);
int testOutMux(int imod);
int testFpgaMux(int imod);
int calibration_sensor(int num, int *values, int *dacs) ;
int calibration_chip(int num, int *values, int *dacs);
ROI* setROI(int n, ROI arg[], int *retvalsize, int *ret);
#endif
#endif

View File

@ -0,0 +1,464 @@
#ifndef REGISTERS_G_H
#define REGISTERS_G_H
#include "sls_detector_defs.h"
/* Definitions for FPGA*/
#define CSP0 0x20200000
#define MEM_SIZE 0x100000
/* values defined for FPGA */
#define MCSNUM 0x0
#define FIXED_PATT_VAL 0xacdc1980
#define FPGA_INIT_PAT 0x60008
#define FPGA_INIT_ADDR 0xb0000000
/* constant FPGAVersionReg_c : integer:= 0; */
/* constant FixedPatternReg_c : integer:= 1; */
/* constant StatusReg_c : integer:= 2; */
/* constant LookAtMeReg_c : integer:= 3; */
/* constant SystemStatusReg_c : integer:= 4; */
/* constant PLL_ParamOutReg_c : integer:=5; -- RO register to check control signals going to the chip */
/* --time registers use only even numbers! */
/* constant TimeFromStartReg_c : integer:= 16; */
/* --constant TimeFromStartReg_c : integer:= 17; MSB */
/* constant GetDelayReg_c : integer:= 18; */
/* --constant GetDelayReg_c : integer:= 19; MSB */
/* constant GetCyclesReg_c : integer:= 20; */
/* --constant GetTrainsReg_c : integer:= 21; MSB */
/* constant GetFramesReg_c : integer:= 22; */
/* --constant GetFramesReg_c : integer:= 23; MSB */
/* constant GetPeriodReg_c : integer:= 24; */
/* --constant GetPeriodReg_c : integer:= 25; MSB */
/* constant GetExpTimeReg_c : integer:= 26; */
/* --constant GetExpTimeReg_c : integer:= 27; MSB */
/* constant GetGatesReg_c : integer:= 28; */
/* --constant GetGatesReg_c : integer:= 29; MSB */
/* -----rw: */
/* constant DACReg_c : integer:= 64; */
/* constant ADCWriteReg_c : integer:= 65; */
/* constant ADCsyncReg_c : integer:= 66; */
/* constant HVReg_c : integer:= 67; */
/* constant DummyReg_c : integer:= 68; */
/* constant rx_udpip_AReg_c : integer:= 69; */
/* constant udpports_AReg_c : integer:= 70; */
/* constant rx_udpmacL_AReg_c : integer:= 71; */
/* constant rx_udpmacH_AReg_c : integer:= 72; */
/* constant detectormacL_AReg_c : integer:= 73; */
/* constant detectormacH_AReg_c : integer:= 74; */
/* constant detectorip_AReg_c : integer:= 75; */
/* constant ipchksum_AReg_c : integer:= 76; */
/* constant ConfigReg_c : integer:= 77; */
/* constant ExtSignalReg_c : integer:= 78; */
/* constant ControlReg_c : integer:= 79; */
/* constant PLL_ParamReg_c : integer:= 80; */
/* constant PLL_CntrlReg_c : integer:=81; */
/* --time registers use only even numbers! */
/* -- DELAY_AFTER_TRIGGER, */
/* constant SetDelayReg_c : integer:= 96; */
/* --constant SetDelayReg_c : integer:= 97; MSB */
/* -- CYCLES_NUMBER, */
/* constant SetCyclesReg_c : integer:= 98; */
/* --constant SetCyclesReg_c : integer:= 99;MSB */
/* -- FRAME_NUMBER, */
/* constant SetFramesReg_c : integer:= 100; */
/* --constant SetFramesReg_c : integer:= 101; MSB */
/* -- FRAME_PERIOD, */
/* constant SetPeriodReg_c : integer:= 102; */
/* --constant SetPeriodReg_c : integer:= 103; MSB */
/* -- ACQUISITION_TIME, */
/* constant SetExpTimeReg_c : integer:= 104; */
/* --constant SetExpTimeReg_c : integer:= 105; MSB */
/* -- GATES_NUMBER, */
/* constant SetGatesReg_c : integer:= 106; */
/* --constant SetGatesReg_c : integer:= 107; MSB */
/* registers defined in FPGA */
#define PCB_REV_REG 0x2c<<11
#define GAIN_REG 0x10<<11
//#define FLOW_CONTROL_REG 0x11<<11
//#define FLOW_STATUS_REG 0x12<<11
//#define FRAME_REG 0x13<<11
#define MULTI_PURPOSE_REG 0x14<<11
#define DAQ_REG 0x15<<11
//#define TIME_FROM_START_REG 0x16<<11
#define DAC_REG 64<<11//0x17<<11// control the dacs
//ADC
#define ADC_WRITE_REG 65<<11//0x18<<11
#define ADC_SYNC_REG 66<<11//0x19<<11
//#define MUTIME_REG 0x1a<<11
//temperature
#define TEMP_IN_REG 0x1b<<11
#define TEMP_OUT_REG 0x1c<<11
//configure MAC
#define TSE_CONF_REG 0x1d<<11
#define ENET_CONF_REG 0x1e<<11
//#define WRTSE_SHAD_REG 0x1f<<11
//HV
#define HV_REG 67<<11//0x20<<11
#define DUMMY_REG 68<<11//0x21<<11
#define FPGA_VERSION_REG 0<<11 //0x22<<11
#define FIX_PATT_REG 1<<11 //0x23<<11
#define CONTROL_REG 79<<11//0x24<<11
#define STATUS_REG 2<<11 //0x25<<11
#define CONFIG_REG 77<<11//0x26<<11
#define EXT_SIGNAL_REG 78<<11// 0x27<<11
#define FPGA_SVN_REG 0x29<<11
#define CHIP_OF_INTRST_REG 0x2A<<11
//FIFO
#define LOOK_AT_ME_REG 3<<11 //0x28<<11
#define SYSTEM_STATUS_REG 4<<11
#define FIFO_DATA_REG_OFF 0x50<<11 ///////
//to read back dac registers
#define MOD_DACS1_REG 0x65<<11
#define MOD_DACS2_REG 0x66<<11
#define MOD_DACS3_REG 0x67<<11
//user entered
#define GET_ACTUAL_TIME_LSB_REG 16<<11
#define GET_ACTUAL_TIME_MSB_REG 17<<11
#define SET_DELAY_LSB_REG 96<<11 //0x68<<11
#define SET_DELAY_MSB_REG 97<<11 //0x69<<11
#define GET_DELAY_LSB_REG 18<<11//0x6a<<11
#define GET_DELAY_MSB_REG 19<<11//0x6b<<11
#define SET_CYCLES_LSB_REG 98<<11//0x6c<<11
#define SET_CYCLES_MSB_REG 99<<11//0x6d<<11
#define GET_CYCLES_LSB_REG 20<<11//0x6e<<11
#define GET_CYCLES_MSB_REG 21<<11//0x6f<<11
#define SET_FRAMES_LSB_REG 100<<11//0x70<<11
#define SET_FRAMES_MSB_REG 101<<11//0x71<<11
#define GET_FRAMES_LSB_REG 22<<11//0x72<<11
#define GET_FRAMES_MSB_REG 23<<11//0x73<<11
#define SET_PERIOD_LSB_REG 102<<11//0x74<<11
#define SET_PERIOD_MSB_REG 103<<11//0x75<<11
#define GET_PERIOD_LSB_REG 24<<11//0x76<<11
#define GET_PERIOD_MSB_REG 25<<11//0x77<<11
#define SET_EXPTIME_LSB_REG 104<<11//0x78<<11
#define SET_EXPTIME_MSB_REG 105<<11//0x79<<11
#define GET_EXPTIME_LSB_REG 26<<11//0x7a<<11
#define GET_EXPTIME_MSB_REG 27<<11//0x7b<<11
#define SET_GATES_LSB_REG 106<<11//0x7c<<11
#define SET_GATES_MSB_REG 107<<11//0x7d<<11
#define GET_GATES_LSB_REG 28<<11//0x7e<<11
#define GET_GATES_MSB_REG 29<<11//0x7f<<11
#define PLL_PARAM_REG 80<<11//0x37<<11
#define PLL_PARAM_OUT_REG 5<<11 //0x38<<11
#define PLL_CNTRL_REG 81<<11//0x34<<11
#define RX_UDP_AREG 69<<11 //rx_udpip_AReg_c : integer:= 69; */
#define UDPPORTS_AREG 70<<11// udpports_AReg_c : integer:= 70; */
#define RX_UDPMACL_AREG 71<<11//rx_udpmacL_AReg_c : integer:= 71; */
#define RX_UDPMACH_AREG 72<<11//rx_udpmacH_AReg_c : integer:= 72; */
#define DETECTORMACL_AREG 73<<11//detectormacL_AReg_c : integer:= 73; */
#define DETECTORMACH_AREG 74<<11//detectormacH_AReg_c : integer:= 74; */
#define DETECTORIP_AREG 75<<11//detectorip_AReg_c : integer:= 75; */
#define IPCHKSUM_AREG 76<<11//ipchksum_AReg_c : integer:= 76; */
#define ROI_REG 0x35<<11
#define OVERSAMPLING_REG 0x36<<11
#define MOENCH_CNTR_REG 0x31<<11
#define MOENCH_CNTR_OUT_REG 0x33<<11
#define MOENCH_CNTR_CONF_REG 0x32<<11
//image
#define DARK_IMAGE_REG 0x81<<11
#define GAIN_IMAGE_REG 0x82<<11
//counter block memory
#define COUNTER_MEMORY_REG 0x85<<11
#define GET_MEASUREMENT_TIME_LSB_REG 0x023000
#define GET_MEASUREMENT_TIME_MSB_REG 0x024000
//#define GET_ACTUAL_TIME_LSB_REG 0x025000
//#define GET_ACTUAL_TIME_MSB_REG 0x026000
//not used
//#define MCB_DOUT_REG_OFF 0x200000
//#define FIFO_CNTRL_REG_OFF 0x300000
//#define FIFO_COUNTR_REG_OFF 0x400000
//not used so far
//#define SPEED_REG 0x006000
//#define SET_NBITS_REG 0x008000
//not used
//#define GET_SHIFT_IN_REG 0x022000
#define SHIFTMOD 2
#define SHIFTFIFO 9
/** for PCB_REV_REG */
#define DETECTOR_TYPE_MASK 0xF0000
#define DETECTOR_TYPE_OFFSET 16
#define BOARD_REVISION_MASK 0xFFFF
#define MOENCH_MODULE 2
/* for control register */
#define START_ACQ_BIT 0x00000001
#define STOP_ACQ_BIT 0x00000002
#define START_FIFOTEST_BIT 0x00000004 // ?????
#define STOP_FIFOTEST_BIT 0x00000008 // ??????
#define START_READOUT_BIT 0x00000010
#define STOP_READOUT_BIT 0x00000020
#define START_EXPOSURE_BIT 0x00000040
#define STOP_EXPOSURE_BIT 0x00000080
#define START_TRAIN_BIT 0x00000100
#define STOP_TRAIN_BIT 0x00000200
#define SYNC_RESET 0x00000400
/* for status register */
#define RUN_BUSY_BIT 0x00000001
#define READOUT_BUSY_BIT 0x00000002
#define FIFOTEST_BUSY_BIT 0x00000004 //????
#define WAITING_FOR_TRIGGER_BIT 0x00000008
#define DELAYBEFORE_BIT 0x00000010
#define DELAYAFTER_BIT 0x00000020
#define EXPOSING_BIT 0x00000040
#define COUNT_ENABLE_BIT 0x00000080
#define READSTATE_0_BIT 0x00000100
#define READSTATE_1_BIT 0x00000200
#define READSTATE_2_BIT 0x00000400
#define RUNSTATE_0_BIT 0x00001000
#define RUNSTATE_1_BIT 0x00002000
#define RUNSTATE_2_BIT 0x00004000
#define SOME_FIFO_FULL_BIT 0x00008000 // error!
#define ALL_FIFO_EMPTY_BIT 0x00010000 // data ready
#define RUNMACHINE_BUSY_BIT 0x00020000
#define READMACHINE_BUSY_BIT 0x00040000
/* for fifo status register */
#define FIFO_ENABLED_BIT 0x80000000
#define FIFO_DISABLED_BIT 0x01000000
#define FIFO_ERROR_BIT 0x08000000
#define FIFO_EMPTY_BIT 0x04000000
#define FIFO_DATA_READY_BIT 0x02000000
#define FIFO_COUNTER_MASK 0x000001ff
#define FIFO_NM_MASK 0x00e00000
#define FIFO_NM_OFF 21
#define FIFO_NC_MASK 0x001ffe00
#define FIFO_NC_OFF 9
/* for config register *///not really used yet
#define TOT_ENABLE_BIT 0x00000002
#define TIMED_GATE_BIT 0x00000004
#define CONT_RO_ENABLE_BIT 0x00080000
#define CPU_OR_RECEIVER_BIT 0x00001000
/* for speed register */
#define CLK_DIVIDER_MASK 0x000000ff
#define CLK_DIVIDER_OFFSET 0
#define SET_LENGTH_MASK 0x00000f00
#define SET_LENGTH_OFFSET 8
#define WAIT_STATES_MASK 0x0000f000
#define WAIT_STATES_OFFSET 12
#define TOTCLK_DIVIDER_MASK 0xff000000
#define TOTCLK_DIVIDER_OFFSET 24
#define TOTCLK_DUTYCYCLE_MASK 0x00ff0000
#define TOTCLK_DUTYCYCLE_OFFSET 16
/* for external signal register */
#define SIGNAL_OFFSET 4
#define SIGNAL_MASK 0xF
#define EXT_SIG_OFF 0x0
#define EXT_GATE_IN_ACTIVEHIGH 0x1
#define EXT_GATE_IN_ACTIVELOW 0x2
#define EXT_TRIG_IN_RISING 0x3
#define EXT_TRIG_IN_FALLING 0x4
#define EXT_RO_TRIG_IN_RISING 0x5
#define EXT_RO_TRIG_IN_FALLING 0x6
#define EXT_GATE_OUT_ACTIVEHIGH 0x7
#define EXT_GATE_OUT_ACTIVELOW 0x8
#define EXT_TRIG_OUT_RISING 0x9
#define EXT_TRIG_OUT_FALLING 0xA
#define EXT_RO_TRIG_OUT_RISING 0xB
#define EXT_RO_TRIG_OUT_FALLING 0xC
/* for temperature register */
#define T1_CLK_BIT 0x00000001
#define T1_CS_BIT 0x00000002
#define T2_CLK_BIT 0x00000004
#define T2_CS_BIT 0x00000008
/* fifo control register */
#define FIFO_RESET_BIT 0x00000001
#define FIFO_DISABLE_TOGGLE_BIT 0x00000002
//chip shiftin register meaning
#define OUTMUX_OFF 20
#define OUTMUX_MASK 0x1f
#define PROBES_OFF 4
#define PROBES_MASK 0x7f
#define OUTBUF_OFF 0
#define OUTBUF_MASK 1
/* multi purpose register */
#define PHASE_STEP_BIT 0x00000001
#define PHASE_STEP_OFFSET 0
// #define xxx_BIT 0x00000002
#define RESET_COUNTER_BIT 0x00000004
#define RESET_COUNTER_OFFSET 2
//#define xxx_BIT 0x00000008
//#define xxx_BIT 0x00000010
#define SW1_BIT 0x00000020
#define SW1_OFFSET 5
#define WRITE_BACK_BIT 0x00000040
#define WRITE_BACK_OFFSET 6
#define RESET_BIT 0x00000080
#define RESET_OFFSET 7
#define ENET_RESETN_BIT 0x00000800
#define ENET_RESETN_OFFSET 11
#define INT_RSTN_BIT 0x00002000
#define INT_RSTN_OFFSET 13
#define DIGITAL_TEST_BIT 0x00004000
#define DIGITAL_TEST_OFFSET 14
//#define CHANGE_AT_POWER_ON_BIT 0x00008000
//#define CHANGE_AT_POWER_ON_OFFSET 15
/* settings/conf gain register */
#define GAIN_MASK 0x0000000f
#define GAIN_OFFSET 0
#define SETTINGS_MASK 0x000000f0
#define SETTINGS_OFFSET 4
/* CHIP_OF_INTRST_REG */
#define CHANNEL_MASK 0xffff0000
#define CHANNEL_OFFSET 16
#define ACTIVE_ADC_MASK 0x0000001f
/**ADC SYNC CLEAN FIFO*/
#define ADCSYNC_CLEAN_FIFO_BITS 0x300000
#define CLEAN_FIFO_MASK 0x0fffff
#define PLL_CNTR_ADDR_OFF 16 //PLL_CNTR_REG bits 21 downto 16 represent the counter address
#define PLL_CNTR_RECONFIG_RESET_BIT 0
#define PLL_CNTR_READ_BIT 1
#define PLL_CNTR_WRITE_BIT 2
#define PLL_MODE_REG 0x0
#define PLL_STATUS_REG 0x1
#define PLL_START_REG 0x2
#define PLL_N_COUNTER_REG 0x3
#define PLL_M_COUNTER_REG 0x4
#define PLL_C_COUNTER_REG 0x5 //which ccounter stands in param 22:18; 7:0 lowcount 15:8 highcount; 16 bypassenable; 17 oddivision
#define PLL_PHASE_SHIFT_REG 0x6
#define PLL_K_COUNTER_REG 0x7
#define PLL_BANDWIDTH_REG 0x8
#define PLL_CHARGEPUMP_REG 0x9
#define PLL_VCO_DIV_REG 0x1c
#define PLL_MIF_REG 0x1f
#define PPL_M_CNT_PARAM_DEFAULT 0x4040
#define PPL_N_CNT_PARAM_DEFAULT 0x20D0C
#define PPL_C0_CNT_PARAM_DEFAULT 0x20D0C
#define PPL_C1_CNT_PARAM_DEFAULT 0xA0A0
#define PPL_C2_CNT_PARAM_DEFAULT 0x20D0C
#define PPL_C2_CNT_PARAM_DEFAULT 0x0808
#define PPL_BW_PARAM_DEFAULT 0x2EE0
#define PPL_VCO_PARAM_DEFAULT 0x1
#endif

View File

@ -0,0 +1,137 @@
/* A simple server in the internet domain using TCP
The port number is passed as an argument */
#include "sls_detector_defs.h"
#include "communication_funcs.h"
#include "server_funcs.h"
#include <stdlib.h>
extern int sockfd;
extern int phase_shift;
void error(char *msg)
{
perror(msg);
}
int main(int argc, char *argv[])
{
int portno, b;
char cmd[500];
int retval=OK;
int sd, fd;
int iarg;
int checkType = 1;
for(iarg=1; iarg<argc; iarg++){
if(!strcasecmp(argv[iarg],"-phaseshift")){
if(argc==iarg+1){
printf("No phaseshift given. Exiting.\n");
return 1;
}
if ( sscanf(argv[iarg+1],"%d",&phase_shift)==0) {
printf("could not decode phase shift\n");
return 1;
}
}
else if(!strcasecmp(argv[iarg],"-test")){
if(argc==iarg+1){
printf("No test condition given. Exiting.\n");
return 1;
}
if(!strcasecmp(argv[iarg+1],"with_gotthard")){
checkType = 0;
}else{
printf("could not decode test condition. Possible arguments: with_gotthard. Exiting\n");
return 1;
}
}
}
//stop server
if ((argc > 2) && (!strcasecmp(argv[2],"stopserver"))){
portno = DEFAULT_PORTNO+1;
if ( sscanf(argv[1],"%d",&portno) ==0) {
printf("could not open stop server: unknown port\n");
return 1;
}
b=0;
printf("\n\nStop Server\nOpening stop server on port %d\n",portno);
checkType=0;
}
//control server
else {
portno = DEFAULT_PORTNO;
if(checkType)
sprintf(cmd,"%s %d stopserver &",argv[0],DEFAULT_PORTNO+1);
else
sprintf(cmd,"%s %d stopserver -test with_gotthard &",argv[0],DEFAULT_PORTNO+1);
printf("\n\nControl Server\nOpening control server on port %d\n",portno );
//printf("\n\ncmd:%s\n",cmd);
system(cmd);
b=1;
checkType=1;
}
init_detector(b, checkType);
sd=bindSocket(portno);
sockfd=sd;
if (getServerError(sd)) {
printf("server error!\n");
return -1;
}
/* assign function table */
function_table();
#ifdef VERBOSE
printf("function table assigned \n");
#endif
/* waits for connection */
while(retval!=GOODBYE) {
#ifdef VERBOSE
printf("\n");
#endif
#ifdef VERY_VERBOSE
printf("Waiting for client call\n");
#endif
fd=acceptConnection(sockfd);
#ifdef VERY_VERBOSE
printf("Conenction accepted\n");
#endif
retval=decode_function(fd);
#ifdef VERY_VERBOSE
printf("function executed\n");
#endif
closeConnection(fd);
#ifdef VERY_VERBOSE
printf("connection closed\n");
#endif
}
exitServer(sockfd);
printf("Goodbye!\n");
return 0;
}

View File

@ -0,0 +1,63 @@
#ifndef SERVER_DEFS_H
#define SERVER_DEFS_H
#include "sls_detector_defs.h"
#include <stdint.h>
// Hardware definitions
#define NCHAN (160*160)
#define NCHIP 1
#define NMAXMODX 1
#define NMAXMODY 1
#define NMAXMOD (NMAXMODX*NMAXMODY)
#define NDAC 8
#define NADC 1
/**when moench readout tested with gotthard module*/
#define GOTTHARDNCHAN 128
#define GOTTHARDNCHIP 10
#define NCHANS (NCHAN*NCHIP*NMAXMOD)
#define NDACS (NDAC*NMAXMOD)
#define NTRIMBITS 6
#define NCOUNTBITS 24
#define NCHIPS_PER_ADC 2
//#define TRIM_DR ((2**NTRIMBITS)-1)
//#define COUNT_DR ((2**NCOUNTBITS)-1)
#define TRIM_DR (((int)pow(2,NTRIMBITS))-1)
#define COUNT_DR (((int)pow(2,NCOUNTBITS))-1)
#define ALLMOD 0xffff
#define ALLFIFO 0xffff
#define GOTTHARD_ADCSYNC_VAL 0x32214
#define ADCSYNC_VAL 0x02111
#define TOKEN_RESTART_DELAY 0x88000000
#define TOKEN_RESTART_DELAY_ROI 0x1b000000
#define TOKEN_TIMING_REV1 0x1f16
#define TOKEN_TIMING_REV2 0x1f0f
#define DEFAULT_PHASE_SHIFT 0 // 120
#define DEFAULT_IP_PACKETSIZE 0x0522
#define DEFAULT_UDP_PACKETSIZE 0x050E
#define ADC1_IP_PACKETSIZE 256*2+14+20
#define ADC1_UDP_PACKETSIZE 256*2+4+8+2
#ifdef VIRTUAL
#define DEBUGOUT
#endif
#define CLK_FREQ 65.6E+6
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,97 @@
#ifndef SERVER_FUNCS_H
#define SERVER_FUNCS_H
#include "sls_detector_defs.h"
#include <stdio.h>
/*
#include <sys/types.h>
#include <sys/socket.h>
#include <netinet/in.h>
*/
#include "communication_funcs.h"
#define GOODBYE -200
int sockfd;
int function_table();
int decode_function(int);
int init_detector(int,int);
int M_nofunc(int);
int exit_server(int);
// General purpose functions
int get_detector_type(int);
int set_number_of_modules(int);
int get_max_number_of_modules(int);
int exec_command(int);
int set_external_signal_flag(int);
int set_external_communication_mode(int);
int get_id(int);
int digital_test(int);
int write_register(int);
int read_register(int);
int set_dac(int);
int get_adc(int);
int set_channel(int);
int set_chip(int);
int set_module(int);
int get_channel(int);
int get_chip(int);
int get_module(int);
int get_threshold_energy(int);
int set_threshold_energy(int);
int set_settings(int);
int start_acquisition(int);
int stop_acquisition(int);
int start_readout(int);
int get_run_status(int);
int read_frame(int);
int read_all(int);
int start_and_read_all(int);
int set_timer(int);
int get_time_left(int);
int set_dynamic_range(int);
int set_roi(int);
int get_roi(int);
int set_speed(int);
void prepareADC(void);
int set_readout_flags(int);
int execute_trimming(int);
int lock_server(int);
int set_port(int);
int get_last_client_ip(int);
int set_master(int);
int set_synchronization(int);
int update_client(int);
int send_update(int);
int configure_mac(int);
int load_image(int);
int read_counter_block(int);
int reset_counter_block(int);
int start_receiver(int);
int stop_receiver(int);
int calibrate_pedestal(int);
int set_roi(int);
#endif

View File

@ -0,0 +1,39 @@
#include "sharedmemory.h"
struct statusdata *stdata;
int inism(int clsv) {
static int scansmid;
if (clsv==SMSV) {
if ( (scansmid=shmget(SMKEY,1024,IPC_CREAT | 0666 ))==-1 ) {
return -1;
}
if ( (stdata=shmat(scansmid,NULL,0))==(void*)-1) {
return -2;
}
}
if (clsv==SMCL) {
if ( (scansmid=shmget(SMKEY,0,0) )==-1 ) {
return -3;
}
if ( (stdata=shmat(scansmid,NULL,0))==(void*)-1) {
return -4;
}
}
return 1;
}
void write_status_sm(char *status) {
strcpy(stdata->status,status);
}
void write_stop_sm(int v) {
stdata->stop=v;
}
void write_runnumber_sm(int v) {
stdata->runnumber=v;
}

View File

@ -0,0 +1,48 @@
#ifndef SM
#define SM
#include "sls_detector_defs.h"
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/mman.h>
#include <fcntl.h>
#include <stdarg.h>
#include <unistd.h>
//#include <asm/page.h>
#include <sys/mman.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <stdarg.h>
#include <unistd.h>
#include <sys/shm.h>
#include <sys/ipc.h>
#include <sys/stat.h>
/* key for shared memory */
#define SMKEY 10001
#define SMSV 1
#define SMCL 2
struct statusdata {
int runnumber;
int stop;
char status[20];
} ;
/* for shared memory */
int inism(int clsv);
void write_status_sm(char *status);
void write_stop_sm(int v);
void write_runnumber_sm(int v);
#endif

View File

@ -0,0 +1 @@
../commonFiles/sls_detector_defs.h

View File

@ -0,0 +1 @@
../commonFiles/sls_detector_funcs.h

View File

@ -0,0 +1 @@
../../slsReceiverSoftware/includes/sls_receiver_defs.h

View File

@ -0,0 +1 @@
../../slsReceiverSoftware/includes/sls_receiver_funcs.h

View File

@ -0,0 +1,46 @@
/* A simple server in the internet domain using TCP
The port number is passed as an argument */
#include "sls_detector_defs.h"
#include "communication_funcs.h"
#include "firmware_funcs.h"
int sockfd;
int main(int argc, char *argv[])
{
int portno;
int retval=0;
portno = DEFAULT_PORTNO;
bindSocket(portno);
if (getServerError())
return -1;
/* waits for connection */
while(retval!=GOODBYE) {
#ifdef VERBOSE
printf("\n");
#endif
#ifdef VERY_VERBOSE
printf("Stop server: waiting for client call\n");
#endif
acceptConnection();
retval=stopStateMachine();
closeConnection();
}
exitServer();
printf("Goodbye!\n");
return 0;
}

View File

@ -0,0 +1,749 @@
#ifndef PICASSOD
#include "server_defs.h"
#else
#include "picasso_defs.h"
#endif
#include "trimming_funcs.h"
#include "mcb_funcs.h"
#include "firmware_funcs.h"
#include <math.h>
extern int nModX;
//extern int *values;
extern const int nChans;
extern const int nChips;
extern const int nDacs;
extern const int nAdcs;
int trim_fixed_settings(int countlim, int par2, int im)
{
int retval=OK;
#ifdef VERBOSE
printf("Trimming with fixed settings\n");
#endif
#ifdef VIRTUAL
return OK;
#endif
if (par2<=0)
retval=trim_with_level(countlim, im);
else
retval=trim_with_median(countlim,im);
return retval;
}
int trim_with_noise(int countlim, int nsigma, int im)
{
int retval=OK, retval1=OK, retval2=OK;
#ifdef VERBOSE
printf("Trimming using noise\n");
#endif
#ifdef VIRTUAL
return OK;
#endif
/* threshold scan */
#ifdef VERBOSE
printf("chosing vthresh and vtrim.....");
#endif
retval1=choose_vthresh_and_vtrim(countlim,nsigma, im);
#ifdef VERBOSE
printf("trimming with noise.....\n");
#endif
retval2=trim_with_level(countlim, im);
#ifdef DEBUGOUT
printf("done\n");
#endif
if (retval1==OK && retval2==OK)
retval=OK;
else
retval=FAIL;
return retval;
}
int trim_with_beam(int countlim, int nsigma, int im) //rpc
{
int retval=OK, retval1=OK, retval2=OK;
printf("Trimming using beam\n");
//return OK;
#ifdef VIRTUAL
printf("Trimming using beam\n");
return OK;
#endif
/* threshold scan */
#ifdef DEBUGOUT
printf("chosing vthresh and vtrim.....");
#endif
retval1=choose_vthresh_and_vtrim(countlim,nsigma,im);
retval2=trim_with_median(TRIM_DR, im);
#ifdef DEBUGOUT
printf("done\n");
#endif
if (retval1==OK && retval2==OK)
retval=OK;
else
retval=FAIL;
return retval;
}
int trim_improve(int maxit, int par2, int im) //rpc
{
int retval=OK, retval1=OK, retval2=OK;
#ifdef VERBOSE
printf("Improve the trimming\n");
#endif
#ifdef VIRTUAL
return OK;
#endif
if (par2!=0 && im==ALLMOD)
retval1=choose_vthresh();
retval2=trim_with_median(2*maxit+1, im);
#ifdef DEBUGOUT
printf("done\n");
#endif
if (retval1==OK && retval2==OK)
retval=OK;
else
retval=FAIL;
return retval;
}
int calcthr_from_vcal(int vcal) {
int thrmin;
//thrmin=140+3*vcal/5;
thrmin=180+3*vcal/5;
return thrmin;
}
int calccal_from_vthr(int vthr) {
int vcal;
vcal=5*(vthr-140)/3;
return vcal;
}
int choose_vthresh_and_vtrim(int countlim, int nsigma, int im) {
int retval=OK;
#ifdef MCB_FUNCS
int modma, modmi, nm;
int thr, thrstep=5, nthr=31;
int *fifodata;
double vthreshmean, vthreshSTDev;
int *thrmi, *thrma;
double c;
double b=BVTRIM;
double a=AVTRIM;
int *trim;
int ich, imod, ichan;
int nvalid=0;
u_int32_t *scan;
int ithr;
sls_detector_channel myChan;
setFrames(1);
// setNMod(getNModBoard());
if (im==ALLMOD){
modmi=0;
modma=nModX;
} else {
modmi=im;
modma=im+1;
}
nm=modma-modmi;
trim=malloc(sizeof(int)*nChans*nChips*nModX);
thrmi=malloc(sizeof(int)*nModX);
thrma=malloc(sizeof(int)*nModX);
for (ich=0; ich<nChans*nChips*nm; ich++)
trim[ich]=-1;
/*
setCSregister(im);
setSSregister(im);
initChannel(0,0,0,1,0,0,im);
counterClear(im);
clearSSregister(im);
usleep(500);
*/
myChan.chan=-1;
myChan.chip=-1;
myChan.module=ALLMOD;
myChan.reg=COMPARATOR_ENABLE;
initChannelbyNumber(myChan);
for (ithr=0; ithr<nthr; ithr++) {
fifoReset();
/* scanning threshold */
for (imod=modmi; imod<modma; imod++) {
//commented out by dhanya thr=getDACbyIndexDACU(VTHRESH,imod);
if (ithr==0) {
thrmi[imod]=thr;
//commented out by dhanya initDACbyIndexDACU(VTHRESH,thr,imod);
} else
;//commented out by dhanya initDACbyIndexDACU(VTHRESH,thr+thrstep,imod);
}
/* setCSregister(ALLMOD);
setSSregister(ALLMOD);
initChannel(0,0,0,1,0,0,im);
setDynamicRange(32);
*/
counterClear(ALLMOD);
clearSSregister(ALLMOD);
usleep(500);
startStateMachine();
while (runBusy()) {
}
usleep(500);
fifodata=fifo_read_event();
scan=decode_data(fifodata);
for (imod=modmi; imod<modma; imod++) {
for (ichan=0; ichan<nChans*nChips; ichan++){
ich=imod*nChips*nChans+ichan;
if (scan[ich]>countlim && trim[ich]==-1) {
//commented out by dhanya trim[ich]=getDACbyIndexDACU(VTHRESH,imod);
#ifdef VERBOSE
// printf("yes: %d %d %d\n",ich,ithr,scan[ich]);
#endif
}
#ifdef VERBOSE
/* else {
printf("no: %d %d %d\n",ich,ithr,scan[ich]);
}*/
#endif
}
}
free(scan);
}
for (imod=modmi; imod<modma; imod++) {
vthreshmean=0;
vthreshSTDev=0;
nvalid=0;
//commented out by dhanya thrma[imod]=getDACbyIndexDACU(VTHRESH,imod);
for (ichan=0; ichan<nChans*nChips; ichan++){
ich=imod*nChans*nChips+ichan;
if(trim[ich]>thrmi[imod] && trim[ich]<thrma[imod]) {
vthreshmean=vthreshmean+trim[ich];
vthreshSTDev=vthreshSTDev+trim[ich]*trim[ich];
nvalid++;
}
}
if (nvalid>0) {
vthreshmean=vthreshmean/nvalid;
//commented out by dhanya vthreshSTDev=sqrt((vthreshSTDev/nvalid)-vthreshmean*vthreshmean);
} else {
vthreshmean=thrmi[imod];
vthreshSTDev=nthr*thrstep;
printf("No valid channel for module %d\n",imod);
retval=FAIL;
}
#ifdef DEBUGOUT
printf("module= %d nvalid = %d mean=%f RMS=%f\n",imod, nvalid, vthreshmean,vthreshSTDev);
#endif
// *vthresh=round(vthreshmean-nsigma*vthreshSTDev);
thr=(int)(vthreshmean-nsigma*vthreshSTDev);
if (thr<0 || thr>(DAC_DR-1)) {
thr=thrmi[imod]/2;
printf("Can't find correct threshold for module %d\n",imod);
retval=FAIL;
}
//commented out by dhanya initDACbyIndexDACU(VTHRESH,thr,imod);
#ifdef VERBOSE
printf("vthresh=%d \n",thr);
#endif
c=CVTRIM-2.*nsigma*vthreshSTDev/63.;
//commented out by dhanya thr=(int)((-b-sqrt(b*b-4*a*c))/(2*a));
if (thr<500 || thr>(DAC_DR-1)) {
thr=750;
printf("Can't find correct trimbit size for module %d\n",imod);
retval=FAIL;
}
//commented out by dhanya initDACbyIndexDACU(VTRIM,thr,imod);
#ifdef VERBOSE
printf("vtrim=%d \n",thr);
#endif
}
free(trim);
free(thrmi);
free(thrma);
#endif
return retval;
}
int trim_with_level(int countlim, int im) {
int ich, itrim, ichan, ichip, imod;
u_int32_t *scan;
int *inttrim;
int modma, modmi, nm;
int retval=OK;
int *fifodata;
sls_detector_channel myChan;
printf("trimming module number %d", im);
#ifdef MCB_FUNCS
setFrames(1);
// setNMod(getNModBoard());
if (im==ALLMOD){
modmi=0;
modma=nModX;
} else {
modmi=im;
modma=im+1;
}
nm=modma-modmi;
inttrim=malloc(sizeof(int)*nChips*nChans*nModX);
printf("countlim=%d\n",countlim);
for (ich=0; ich<nChans*nChips*nModX; ich++)
inttrim[ich]=-1;
for (itrim=0; itrim<TRIM_DR+1; itrim++) {
fifoReset();
printf("Trimbit %d\n",itrim);
myChan.chan=-1;
myChan.chip=-1;
myChan.module=ALLMOD;
myChan.reg=COMPARATOR_ENABLE|(itrim<<TRIMBIT_OFF);
initChannelbyNumber(myChan);
/*
setCSregister(im);
setSSregister(im);
initChannel(itrim,0,0,1,0,0,ALLMOD);
setDynamicRange(32);
*/
setCSregister(ALLMOD);
setSSregister(ALLMOD);
counterClear(ALLMOD);
clearSSregister(ALLMOD);
usleep(500);
startStateMachine();
while (runBusy()) {
}
usleep(500);
fifodata=fifo_read_event();
scan=decode_data(fifodata);
for (imod=modmi; imod<modma; imod++) {
for (ichan=0; ichan<nChans*nChips; ichan++) {
ich=ichan+imod*nChans*nChips;
if (inttrim[ich]==-1) {
if (scan[ich]>countlim){
inttrim[ich]=itrim;
if (scan[ich]>2*countlim && itrim>0) {
//if (scan[ich]>2*countlim || itrim==0) {
inttrim[ich]=itrim-1;
}
#ifdef VERBOSE
printf("Channel %d trimbit %d counted %d (%08x) countlim %d\n",ich,itrim,scan[ich],fifodata[ich],countlim);
#endif
}
}
#ifdef VERBOSE
/* else
printf("Channel %d trimbit %d counted %d countlim %d\n",ich,itrim,scan[ich],countlim);*/
#endif
}
}
free(scan);
}
for (imod=modmi; imod<modma; imod++) {
clearCSregister(imod);
firstChip(im);
for (ichip=0; ichip<nChips; ichip++) {
clearSSregister(imod);
for (ichan=0; ichan<nChans; ichan++) {
nextStrip(imod);
ich=ichan+imod*nChans*nChips+ichip*nChans;
if (*(inttrim+ich)==-1) {
*(inttrim+ich)=TRIM_DR;
// printf("could not trim channel %d chip %d module %d - set to %d\n", ichan, ichip, imod, *(inttrim+ich) );
retval=FAIL;
}
#ifdef VERBOSE
// else
// printf("channel %d trimbit %d\n",ich,*(inttrim+ich) );
#endif
initChannel(inttrim[ich],0,0,1,0,0,imod);
}
nextChip(imod);
}
}
free(inttrim);
#endif
return retval;
}
#define ELEM_SWAP(a,b) { register int t=(a);(a)=(b);(b)=t; }
#define median(a,n) kth_smallest(a,n,(((n)&1)?((n)/2):(((n)/2)-1)))
int kth_smallest(int *a, int n, int k)
{
register int i,j,l,m ;
register double x ;
l=0 ; m=n-1 ;
while (l<m) {
x=a[k] ;
i=l ;
j=m ;
do {
while (a[i]<x) i++ ;
while (x<a[j]) j-- ;
if (i<=j) {
ELEM_SWAP(a[i],a[j]) ;
i++ ; j-- ;
}
} while (i<=j) ;
if (j<k) l=i ;
if (k<i) m=j ;
}
return a[k] ;
}
int ave(int *a, int n)
{
int av=0,i;
for (i=0; i<n; i++)
av=av+((double)*(a+i))/((double)n);
return av;
}
int choose_vthresh() {
int retval=OK;
#ifdef MCB_FUNCS
int imod, ichan;
u_int32_t *scan, *scan1;
int olddiff[nModX], direction[nModX];
int med[nModX], med1[nModX], diff, media;
int change_flag=1;
int iteration=0;
int maxiterations=10;
int vthreshmean=0;
int vthresh;
int im=ALLMOD;
int modma, modmi, nm;
int *fifodata;
setFrames(1);
// setNMod(getNModBoard());
if (im==ALLMOD){
modmi=0;
modma=nModX;
} else {
modmi=im;
modma=im+1;
}
nm=modma-modmi;
setDynamicRange(32);
setCSregister(ALLMOD);
setSSregister(ALLMOD);
counterClear(ALLMOD);
clearSSregister(ALLMOD);
usleep(500);
startStateMachine();
while (runBusy()) {
//printf(".");
}
usleep(500);
fifodata=fifo_read_event();
scan=decode_data(fifodata);
//
scan1=decode_data(fifodata);
for (imod=modmi; imod<modma; imod++) {
//
med[imod]=median(scan1+imod*nChans*nChips,nChans*nChips);
med1[imod]=med[imod];
//commented out by dhanya vthreshmean=vthreshmean+getDACbyIndexDACU(VTHRESH,imod);
olddiff[imod]=0xffffff;
direction[imod]=0;
printf("Median of module %d=%d\n",imod,med[imod]);
}
vthreshmean=vthreshmean/nm;
//media=median(scan,nChans*nChips*nModX);
//printf("Median overall=%d\n",media);
media=median(med1+modmi,nm);
printf("Median of modules=%d\n",media);
free(scan);
free(scan1);
while(change_flag && iteration<maxiterations) {
setDynamicRange(32);
fifoReset();
setCSregister(ALLMOD);
setSSregister(ALLMOD);
counterClear(ALLMOD);
clearSSregister(ALLMOD);
usleep(500);
startStateMachine();
while (runBusy()) {
}
usleep(500);
fifodata=fifo_read_event();
scan=decode_data(fifodata);
//
scan1=decode_data(fifodata);
change_flag=0;
printf("Vthresh iteration %3d 0f %3d\n",iteration, maxiterations);
for (ichan=modmi; ichan<modma; ichan++) {
med[ichan]=median(scan1+ichan*nChans*nChips,nChans*nChips);
med1[imod]=med[imod];
media=median(med1+modmi,nm);
diff=med[ichan]-media;
if (direction[ichan]==0) {
if (diff>0)
direction[ichan]=1;
else
direction[ichan]=-1;
}
//commented out by dhanya vthresh=getDACbyIndexDACU(VTHRESH,imod);
if ( direction[ichan]!=-3) {
if (abs(diff)>abs(olddiff[ichan])) {
vthresh=vthresh-direction[ichan];
if (vthresh>(DAC_DR-1)) {
vthresh=(DAC_DR-1);
printf("can't equalize threshold for module %d\n", ichan);
retval=FAIL;
}
if (vthresh<0) {
vthresh=0;
printf("can't equalize threshold for module %d\n", ichan);
retval=FAIL;
}
direction[ichan]=-3;
} else {
vthresh=vthresh+direction[ichan];
olddiff[ichan]=diff;
change_flag=1;
}
//commented out by dhanya initDACbyIndex(VTHRESH,vthresh, ichan);
}
}
iteration++;
free(scan);
free(scan1);
}
#endif
return retval;
}
int trim_with_median(int stop, int im) {
int retval=OK;
#ifdef MCB_FUNCS
int ichan, imod, ichip, ich;
u_int32_t *scan, *scan1;
int *olddiff, *direction;
int med, diff;
int change_flag=1;
int iteration=0;
int me[nModX], me1[nModX];
int modma, modmi, nm;
int trim;
int *fifodata;
setFrames(1);
// setNMod(getNModBoard());
if (im==ALLMOD){
modmi=0;
modma=nModX;
} else {
modmi=im;
modma=im+1;
}
nm=modma-modmi;
olddiff=malloc(4*nModX*nChips*nChans);
direction=malloc(4*nModX*nChips*nChans);
for (imod=modmi; imod<modma; imod++) {
for (ichip=0; ichip<nChips; ichip++) {
for (ich=0; ich<nChans; ich++) {
ichan=imod*nChips*nChans+ichip*nChans+ich;
direction[ichan]=0;
olddiff[ichan]=0x0fffffff;
}
}
}
/********
fifoReset();
setCSregister(ALLMOD);
setSSregister(ALLMOD);
counterClear(ALLMOD);
clearSSregister(ALLMOD);
usleep(500);
startStateMachine();
while (runBusy()) {
}
usleep(500);
scan=decode_data(fifo_read_event());
for (imod=modmi; imod<modma; imod++) {
me[imod]=median(scan+imod*nChans*nChips,nChans*nChips);
printf("Median of module %d=%d\n",imod,me[imod]);
}
med=median(me,nm);
printf("median is %d\n",med);
free(scan);
**************/
while(change_flag && iteration<stop) {
setDynamicRange(32);
fifoReset();
setCSregister(ALLMOD);
setSSregister(ALLMOD);
counterClear(ALLMOD);
clearSSregister(ALLMOD);
usleep(500);
startStateMachine();
while (runBusy()) {
}
usleep(500);
fifodata=fifo_read_event();
scan=decode_data(fifodata);
scan1=decode_data(fifodata);
/********* calculates median every time ***********/
for (imod=modmi; imod<modma; imod++) {
me[imod]=median(scan1+imod*nChans*nChips,nChans*nChips);
me1[imod]=me[imod];
printf("Median of module %d=%d\n",imod,me[imod]);
}
med=median(me1,nm);
printf("median is %d\n",med);
change_flag=0;
printf("Trimbits iteration %d of %d\n",iteration, stop);
for (imod=modmi; imod<modma; imod++) {
for (ichip=0; ichip<nChips; ichip++) {
selChip(ichip,imod);
clearSSregister(imod);
for (ich=0; ich<nChans; ich++) {
ichan=imod*nChips*nChans+ichip*nChans+ich;
nextStrip(imod);
diff=scan[ichan]-me[imod];
if (direction[ichan]==0) {
if (diff>0) {
direction[ichan]=1;
} else {
direction[ichan]=-1;
}
}
if ( direction[ichan]!=-3) {
if (abs(diff)>abs(olddiff[ichan])) {
trim=getTrimbit(imod,ichip,ich)+direction[ichan];
printf("%d old diff %d < new diff %d %d - trimbit %d\n",ichan, olddiff[ichan], diff, direction[ichan], trim);
direction[ichan]=-3;
} else {
trim=getTrimbit(imod,ichip,ich)-direction[ichan];
olddiff[ichan]=diff;
change_flag=1;
}
if (trim>TRIM_DR) {
trim=63;
printf("can't trim channel %d chip %d module %d to trim %d\n",ich, ichip, imod, trim);
retval=FAIL;
}
if (trim<0) {
printf("can't trim channel %d chip %d module %d to trim %d\n",ich, ichip, imod, trim);
trim=0;
retval=FAIL;
}
initChannel(trim,0,0,1,0,0,imod);
}
}
}
}
iteration++;
free(scan);
free(scan1);
}
free(olddiff);
free(direction);
#endif
return retval;
}

View File

@ -0,0 +1,20 @@
#ifndef TRIMMING_FUNCS_H
#define TRIMMING_FUNCS_H
#include "sls_detector_defs.h"
int trim_fixed_settings(int countlim, int par2, int imod);
int trim_with_noise(int countlim, int nsigma, int imod);
int trim_with_beam(int countlim, int nsigma, int imod);
int trim_improve(int maxit, int par2, int imod);
int calcthr_from_vcal(int vcal);
int calccal_from_vthr(int vthr);
int choose_vthresh_and_vtrim(int countlim, int nsigma, int imod);
int choose_vthresh();
int trim_with_level(int countlim, int imod);
int trim_with_median(int stop, int imod);
int calcthr_from_vcal(int vcal);
int calccal_from_vthr(int vthr);
#endif