Commit 2da5bbf9 authored by Tomasz Wlostowski's avatar Tomasz Wlostowski

Initial version that works on the eRTM14 (synces with a WR switch)

parent 512c13a6
......@@ -30,7 +30,7 @@ LDS-$(CONFIG_WR_NODE) = arch/lm32/ram.ld
LDS-$(CONFIG_WR_SWITCH) = arch/lm32/ram-wrs.ld
LDS-$(CONFIG_HOST_PROCESS) =
obj-$(CONFIG_WR_NODE) += wrc_main.o
obj-$(CONFIG_WR_NODE) += wrc_main.o ertm14.o
obj-$(CONFIG_WR_NODE_SIM) += wrc_main_sim.o
obj-$(CONFIG_WR_SWITCH) += wrs_main.o
obj-$(CONFIG_WR_SWITCH) += ipc/minipc-mem-server.o ipc/rt_ipc.o
......@@ -42,7 +42,7 @@ obj-y += dump-info.o
cflags-y = -ffreestanding -include $(AUTOCONF) -Iinclude \
-I. -Isoftpll -Iipc
-I. -Isoftpll -Iipc -Iertm14
cflags-y += -I$(CURDIR)/pp_printf
cflags-$(CONFIG_LM32) += -Iinclude/std
......
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2019 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "ad951x.h"
#if 0
static struct spi_bus bus_ad951x[2] = {
{
&gpio_pin_div_spi_cs_n1,
&gpio_pin_div_spi_dio,
&gpio_pin_div_spi_dio,
&gpio_pin_div_spi_sclk,
AD951X_BIT_DELAY,
0
},
{
&gpio_pin_div_spi_cs_n2,
&gpio_pin_div_spi_dio,
&gpio_pin_div_spi_dio,
&gpio_pin_div_spi_sclk,
BIT_DELAY,
0
}
};
#endif
// Write to ad951x via SPI
void ad951x_write(struct ad951x_device *dev, uint32_t reg, uint32_t value) {
bb_spi_cs(dev->bus, 1);
bb_spi_write(dev->bus, reg & 0x1fff, 16);
bb_spi_write(dev->bus, value & 0xff, 8);
bb_spi_cs(dev->bus, 0);
}
// Read from ad951x via SPI
uint32_t ad951x_read(struct ad951x_device *dev, uint32_t reg) {
uint32_t rv;
bb_spi_cs(dev->bus, 1);
bb_spi_write( dev->bus, 0x8000 | (reg & 0x1fff), 16); // read address cmd
rv = bb_spi_read(dev->bus, 8);
bb_spi_cs(dev->bus, 0);
return rv;
}
// Configure ad951x
int ad951x_configure(struct ad951x_device *dev, struct ad951x_config *cfg) {
int i;
for(i = 0; i < cfg->n_regs; i++) {
ad951x_write(dev, cfg->regs[i].addr, cfg->regs[i].value);
}
ad951x_write(dev, 0x232, 0x01); // commit
for(i = 0; i < cfg->n_regs; i++) {
int rdbk = ad951x_read(dev, cfg->regs[i].addr);
}
int lock_timeout = 1000;
while(lock_timeout--)
{
uint8_t r = ad951x_read(dev, 0x01F);
if( r & 0x1 )
return 0;
}
pp_printf("ad9516: can't lock.\n");
return -1;
}
int ad951x_init(struct ad951x_device *dev, struct spi_bus *spi, struct gpio_pin *pin_reset, struct gpio_pin *pin_lock)
{
dev->bus = spi;
dev->pin_reset = pin_reset;
dev->pin_lock = pin_lock;
if( dev->pin_reset )
{
gen_gpio_set_dir(dev->pin_reset, 1);
gen_gpio_out(dev->pin_reset, 0);
//timer_delay(1);
gen_gpio_out(dev->pin_reset, 1);
//timer_delay(1);
}
ad951x_write(dev, 0x00, 0x99); // bidir mode, long command
ad951x_write(dev, 0x232, 0x01); // commit
uint8_t id = ad951x_read( dev, 0x3 );
pp_printf("AD9516 ID: 0x%02x\n", id );
return 0;
}
#if 0
void ad951x_init() {
int i;
// Configure SPI bus to ad951x
gpio_set_dir(&gpio_pin_div_function, 1);
gpio_out(&gpio_pin_div_function, 0);
spi_delay(&bus_ad951x[0]);
gpio_out(&gpio_pin_div_function, 1);
spi_delay(&bus_ad951x[0]);
// Configure ad951x
ad951x_configure(&bus_ad951x[0], &default_config);
ad951x_configure(&bus_ad951x[1], &default_config);
}
#endif
\ No newline at end of file
#ifndef __AD951x_H
#define __AD951x_H
#include <stdint.h>
#include "board.h"
#include "dev/gpio.h"
#include "dev/spi.h"
#define AD951X_BIT_DELAY 100
struct ad951x_config_reg {
uint16_t addr;
uint8_t value;
};
struct ad951x_config {
int n_regs;
struct ad951x_config_reg regs[];
};
struct ad951x_device {
struct spi_bus *bus;
struct gpio_pin *pin_reset;
struct gpio_pin *pin_lock;
};
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2019 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "ad951x.h"
void ad951x_write(struct ad951x_device *dev, uint32_t reg, uint32_t value);
uint32_t ad951x_read(struct ad951x_device *dev, uint32_t reg);
int ad951x_configure(struct ad951x_device *dev, struct ad951x_config *cfg);
int ad951x_init(struct ad951x_device *dev, struct spi_bus *spi, struct gpio_pin *pin_reset, struct gpio_pin *pin_lock);
#endif
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2019 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "board.h"
#include "dev/gpio.h"
#include "dev/spi.h"
void bb_spi_delay(struct spi_bus *bus)
{
int i;
for(i=0;i<bus->bit_delay;i++)
asm volatile("nop");
}
void bb_spi_cs(struct spi_bus *bus, int cs)
{
bb_spi_delay(bus);
gen_gpio_out(bus->pin_cs, !cs);
}
uint32_t bb_spi_read(struct spi_bus *bus, int n_bits)
{
uint32_t rv = 0;
int i;
bb_spi_delay(bus);
gen_gpio_out(bus->pin_sck, 0);
bb_spi_delay(bus);
gen_gpio_out(bus->pin_mosi, 0);
gen_gpio_set_dir(bus->pin_miso, 0);
bb_spi_delay(bus);
for(i=0;i<n_bits;i++)
{
rv<<=1;
if( bus->rd_falling_edge )
{
if(gen_gpio_in(bus->pin_miso))
rv |= 1;
}
gen_gpio_out(bus->pin_sck, 1);
bb_spi_delay(bus);
if( !bus->rd_falling_edge )
{
if(gen_gpio_in(bus->pin_miso))
rv |= 1;
}
gen_gpio_out(bus->pin_sck, 0);
bb_spi_delay(bus);
}
bb_spi_delay(bus);
return rv;
}
void bb_spi_write(struct spi_bus *bus, uint32_t d, int n_bits)
{
int i;
bb_spi_delay(bus);
gen_gpio_out(bus->pin_mosi, 0);
gen_gpio_set_dir(bus->pin_mosi, 1);
gen_gpio_out(bus->pin_sck, 0);
bb_spi_delay(bus);
for(i=0;i<n_bits;i++)
{
gen_gpio_out(bus->pin_mosi, d & (1<<(n_bits-1-i)) ? 1 : 0);
bb_spi_delay(bus);
gen_gpio_out(bus->pin_sck, 1);
bb_spi_delay(bus);
gen_gpio_out(bus->pin_sck, 0);
bb_spi_delay(bus);
}
}
int bb_spi_create( struct spi_bus *bus,
struct gpio_pin *pin_cs,
struct gpio_pin *pin_mosi,
struct gpio_pin *pin_miso,
struct gpio_pin *pin_sck,
int bit_delay
)
{
bus->bit_delay = bit_delay;
bus->pin_cs = pin_cs;
bus->pin_miso = pin_miso;
bus->pin_mosi = pin_mosi;
bus->pin_sck = pin_sck;
gen_gpio_out( bus->pin_sck, 0 );
gen_gpio_out( bus->pin_cs, 1 );
gen_gpio_set_dir( bus->pin_cs, 1 );
gen_gpio_set_dir( bus->pin_mosi, 1 );
gen_gpio_set_dir( bus->pin_miso, 0 );
gen_gpio_set_dir( bus->pin_sck, 1 );
}
\ No newline at end of file
......@@ -13,10 +13,10 @@ obj-$(CONFIG_EMBEDDED_NODE) += \
dev/devicelist.o \
dev/rxts_calibrator.o \
dev/flash.o \
dev/ad951x.o \
dev/bb_spi.o \
dev/gpio.o \
dev/bb_spi.o
dev/ad951x.o
obj-$(CONFIG_WR_NODE) += \
dev/temperature.o \
dev/pps_gen.o
......
/*
** This work is part of the White Rabbit project
*
* Copyright (C) 2019 CERN (www.cern.ch)
* Author: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "board.h"
#include "dev/gpio.h"
#define GPIO_REG_COR 0
#define GPIO_REG_SOR 4
#define GPIO_REG_DDR 8
#define GPIO_REG_PSR 12
#define GPIO_BANK_SIZE 32
static void wb_gpio_set_dir(const struct gpio_pin *pin, int dir)
{
void *base = (void*)pin->device->priv;
volatile uint32_t *dr = base + (GPIO_BANK_SIZE * (pin->pin >> 5)) + GPIO_REG_DDR;
uint32_t mask = 1 << (pin->pin & 0x1f);
if (dir)
*dr |= mask;
else
*dr &= ~mask;
}
static void wb_gpio_out(const struct gpio_pin *pin, int value)
{
void *base = (void*)pin->device->priv;
volatile void *regs = base + (GPIO_BANK_SIZE * (pin->pin >> 5));
uint32_t mask = 1 << (pin->pin & 0x1f);
if(value)
*(volatile uint32_t *)(regs + GPIO_REG_SOR) = mask;
else
*(volatile uint32_t *)(regs + GPIO_REG_COR) = mask;
}
static int wb_gpio_in(const struct gpio_pin *pin)
{
void *base = (void*)pin->device->priv;
volatile uint32_t *psr = base + (GPIO_BANK_SIZE * (pin->pin >> 5)) + GPIO_REG_PSR;
uint32_t mask = 1 << (pin->pin & 0x1f);
return (*psr & mask) ? 1 : 0;
}
int wb_gpio_create( struct gpio_device *device, uint32_t base_addr )
{
device->priv = (void*) base_addr;
device->set_dir = wb_gpio_set_dir;
device->set_out = wb_gpio_out;
device->read_pin = wb_gpio_in;
return device;
};
void gen_gpio_set_dir(const struct gpio_pin *pin, int dir)
{
pin->device->set_dir(pin, dir);
}
void gen_gpio_out(const struct gpio_pin *pin, int value)
{
pin->device->set_out(pin, value);
}
int gen_gpio_in(const struct gpio_pin *pin)
{
return pin->device->read_pin(pin);
}
\ No newline at end of file
#!/usr/bin/python
import sys
import re
n_regs = 0;
regs = []
for l in open(sys.argv[1],"rb").readlines():
r = re.match('^"(\w+)","\w+","(\w+)"', l)
if r != None:
addr = int(r.group(1), 16)
value = int(r.group(2), 16)
regs += [(addr,value)]
n_regs+=1
print("{")
print("%d," % n_regs)
print("{")
for r in regs:
print(" { 0x%02x, 0x%02x }, " % r );
print("}\n};\n")
"AD9516 Setup File"
"Rev.","1.1.0"
""
"Addr(Hex)","Value(Bin)","Value(Hex)"
"0000","00011000","18"
"0001","00000000","00"
"0002","00010000","10"
"0003","11000011","C3"
"0004","00000000","00"
"0010","01111100","7C"
"0011","00000001","01"
"0012","00000000","00"
"0013","00000110","06"
"0014","00001001","09"
"0015","00000000","00"
"0016","00000101","05"
"0017","00000000","00"
"0018","00000111","07"
"0019","00000000","00"
"001A","00000000","00"
"001B","00000000","00"
"001C","00000010","02"
"001D","00000000","00"
"001E","00000000","00"
"001F","00001110","0E"
"00A0","00000001","01"
"00A1","00000000","00"
"00A2","00000000","00"
"00A3","00000001","01"
"00A4","00000000","00"
"00A5","00000000","00"
"00A6","00000001","01"
"00A7","00000000","00"
"00A8","00000000","00"
"00A9","00000001","01"
"00AA","00000000","00"
"00AB","00000000","00"
"00F0","00001000","08"
"00F1","00001010","0A"
"00F2","00001000","08"
"00F3","00001010","0A"
"00F4","00001010","0A"
"00F5","00001000","08"
"0140","01000011","43"
"0141","01000010","42"
"0142","01000011","43"
"0143","01000010","42"
"0190","00100010","22"
"0191","00000000","00"
"0192","00000000","00"
"0193","00100010","22"
"0194","00000000","00"
"0195","00000000","00"
"0196","00100010","22"
"0197","00000000","00"
"0198","00000000","00"
"0199","00100010","22"
"019A","00000000","00"
"019B","00000000","00"
"019C","00000000","00"
"019D","00000000","00"
"019E","00100010","22"
"019F","00000000","00"
"01A0","00000000","00"
"01A1","00000000","00"
"01A2","00000000","00"
"01A3","00000000","00"
"01E0","00000000","00"
"01E1","00000010","02"
"0230","00000000","00"
"0231","00000000","00"
"0232","00000000","00"
"","",""
"Other Settings..."
"REF 1:",10
"REF 2:",0
"VCO:",1500
"CLK:",1200
"CPRSet:",5100
"Auto Update:",1
"Load All Regs:",0
{
68,
{
{ 0x00, 0x99 },
{ 0x01, 0x00 },
{ 0x02, 0x10 },
{ 0x03, 0xc3 },
{ 0x04, 0x00 },
{ 0x10, 0x7c },
{ 0x11, 0x01 },
{ 0x12, 0x00 },
{ 0x13, 0x06 },
{ 0x14, 0x09 },
{ 0x15, 0x00 },
{ 0x16, 0x05 },
{ 0x17, 0x00 },
{ 0x18, 0x07 },
{ 0x19, 0x00 },
{ 0x1a, 0x00 },
{ 0x1b, 0x00 },
{ 0x1c, 0x02 },
{ 0x1d, 0x00 },
{ 0x1e, 0x00 },
{ 0x1f, 0x0e },
{ 0xa0, 0x01 },
{ 0xa1, 0x00 },
{ 0xa2, 0x00 },
{ 0xa3, 0x01 },
{ 0xa4, 0x00 },
{ 0xa5, 0x00 },
{ 0xa6, 0x01 },
{ 0xa7, 0x00 },
{ 0xa8, 0x00 },
{ 0xa9, 0x01 },
{ 0xaa, 0x00 },
{ 0xab, 0x00 },
{ 0xf0, 0x08 },
{ 0xf1, 0x0a },
{ 0xf2, 0x08 },
{ 0xf3, 0x0a },
{ 0xf4, 0x0a },
{ 0xf5, 0x08 },
{ 0x140, 0x43 },
{ 0x141, 0x42 },
{ 0x142, 0x43 },
{ 0x143, 0x42 },
{ 0x190, 0x22 },
{ 0x191, 0x00 },
{ 0x192, 0x00 },
{ 0x193, 0x22 },
{ 0x194, 0x00 },
{ 0x195, 0x00 },
{ 0x196, 0x22 },
{ 0x197, 0x00 },
{ 0x198, 0x00 },
{ 0x199, 0x22 },
{ 0x19a, 0x00 },
{ 0x19b, 0x00 },
{ 0x19c, 0x00 },
{ 0x19d, 0x00 },
{ 0x19e, 0x22 },
{ 0x19f, 0x00 },
{ 0x1a0, 0x00 },
{ 0x1a1, 0x00 },
{ 0x1a2, 0x00 },
{ 0x1a3, 0x00 },
{ 0x1e0, 0x00 },
{ 0x1e1, 0x02 },
{ 0x230, 0x00 },
{ 0x231, 0x00 },
{ 0x232, 0x00 },
}
};
python ./ad9510_convert_regs.py ertm_14_pll_main_dot050.stp > ertm_14_pll_main_dot050_config.h
\ No newline at end of file
#ifndef __AD9510_H
#define __AD9510_H
#include "board.h"
#include "gpio.h"
#include "spi.h"
#define BIT_DELAY 100
struct ad95xx_config_reg {
uint16_t addr;
uint8_t value;
};
struct ad95xx_config {
int n_regs;
struct ad95xx_config_reg regs[];
};
void ad9510_write(struct spi_bus *bus, uint32_t reg, uint32_t value);
uint32_t ad9510_read(struct spi_bus *bus, uint32_t reg);
int ad9510_configure(struct spi_bus *bus, struct ad95xx_config *cfg);
void ad9510_init();
#endif
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2013 CERN (www.cern.ch)
* Author: Theodor Stana <t.stana@cern.ch>
*
* Released according to the GNU LGPL, version 2.1 or any later version.
*/
#ifndef __FLASH_H_
#define __FLASH_H_
#include "types.h"
#define FLASH_BLOCKSIZE 65536
/* Flash interface functions */
void flash_init(void);
int flash_write(uint32_t addr, uint8_t *buf, int count);
int flash_read(uint32_t addr, uint8_t *buf, int count);
int flash_erase(uint32_t addr, int count);
void flash_serase(uint32_t addr);
void flash_berase(void);
uint8_t flash_rsr(void);
/* SDB flash interface functions */
int flash_sdb_check(void);
#endif // __FLASH_H_
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef __GPIO_H
#define __GPIO_H
#include <stdint.h>
#include "board.h"
struct GPIO_WB
{
uint32_t CODR; /*Clear output register*/
uint32_t SODR; /*Set output register*/
uint32_t DDR; /*Data direction register (1 means out)*/
uint32_t PSR; /*Pin state register*/
};
static volatile struct GPIO_WB *__gpio = (volatile struct GPIO_WB *) BASE_GPIO;
static inline void gpio_out(int pin, int val)
{
if(val)
__gpio->SODR = (1<<pin);
else
__gpio->CODR = (1<<pin);
}
static inline void gpio_dir(int pin, int val)
{
if(val)
__gpio->DDR |= (1<<pin);
else
__gpio->DDR &= ~(1<<pin);
}
static inline int gpio_in(int bank, int pin)
{
return __gpio->PSR & (1<<pin) ? 1: 0;
}
#endif
#ifndef __GPIO_H
#define __GPIO_H
#include "board.h"
struct gpio_pin;
typedef void (*set_dir_func)(const struct gpio_pin *, int);
typedef void (*set_out_func)(const struct gpio_pin *, int);
typedef int (*read_pin_func)(const struct gpio_pin *);
struct gpio_device
{
void* priv;
set_dir_func set_dir;
set_out_func set_out;
read_pin_func read_pin;
};
struct gpio_pin
{
const struct gpio_device *device;
int pin;
};
int wb_gpio_create( struct gpio_device *device, uint32_t base_addr );
void gen_gpio_set_dir(const struct gpio_pin *pin, int dir);
void gen_gpio_out(const struct gpio_pin *pin, int value);
int gen_gpio_in(const struct gpio_pin *pin);
#endif
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef __I2C_H
#define __I2C_H
uint8_t mi2c_devprobe(uint8_t i2cif, uint8_t i2c_addr);
void mi2c_init(uint8_t i2cif);
void mi2c_start(uint8_t i2cif);
void mi2c_repeat_start(uint8_t i2cif);
void mi2c_stop(uint8_t i2cif);
void mi2c_get_byte(uint8_t i2cif, unsigned char *data, uint8_t last);
unsigned char mi2c_put_byte(uint8_t i2cif, unsigned char data);
void mi2c_delay(uint32_t delay);
//void mi2c_scan(uint8_t i2cif);
#endif
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef __IRQ_H
#define __IRQ_H
#ifdef unix
static inline void clear_irq(void) {}
#else
static inline void clear_irq(void)
{
unsigned int val = 1;
asm volatile ("wcsr ip, %0"::"r" (val));
}
#endif
void disable_irq(void);
void enable_irq(void);
void _irq_entry(void);
#endif
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef __MINIC_H
#define __MINIC_H
#include "types.h"
#define ETH_HEADER_SIZE 14
#define ETH_ALEN 6
#define ETH_P_1588 0x88F7 /* IEEE 1588 Timesync */
#define WRPC_FID 0
#define WRF_DATA 0
#define WRF_OOB 1
#define WRF_STATUS 2
#define WRF_BYTESEL 3
#define TX_OOB 0x1000
void minic_init(void);
void minic_disable(void);
int minic_poll_rx(void);
void minic_get_stats(int *tx_frames, int *rx_frames);
struct wr_ethhdr {
uint8_t dstmac[6];
uint8_t srcmac[6];
uint16_t ethtype;
};
struct wr_ethhdr_vlan {
uint8_t dstmac[6];
uint8_t srcmac[6];
uint16_t ethtype;
uint16_t tag;
uint16_t ethtype_2;
};
struct wr_minic {
int tx_count, rx_count;
};
extern struct wr_minic minic;
int minic_rx_frame(struct wr_ethhdr *hdr, uint8_t * payload, uint32_t buf_size,
struct hw_timestamp *hwts);
int minic_tx_frame(struct wr_ethhdr_vlan *hdr, uint8_t * payload, uint32_t size,
struct hw_timestamp *hwts);
#endif
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef PERSISTENT_MAC_H
#define PERSISTENT_MAC_H
#define ONEWIRE_PORT 0
#define EEPROM_MAC_PAGE 0
#define MAX_DEV1WIRE 8
#define FOUND_DS18B20 0x01
void own_scanbus(uint8_t portnum);
int16_t own_readtemp(uint8_t portnum, int16_t * temp, int16_t * t_frac);
/* 0 = success, -1 = error */
int get_persistent_mac(uint8_t portnum, uint8_t * mac);
int set_persistent_mac(uint8_t portnum, uint8_t * mac);
#endif
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef __PPS_GEN_H
#define __PPS_GEN_H
#include <stdint.h>
#define PPSG_ADJUST_SEC 0x1
#define PPSG_ADJUST_NSEC 0x2
#define PPSG_SET_SEC 0x1
#define PPSG_SET_NSEC 0x2
#define PPSG_SET_ALL 0x3
/* Initializes the PPS Generator. 0 on success, negative on failure. */
void shw_pps_gen_init(void);
/* Adjusts the <counter> (PPSG_ADJUST_SEC/NSEC) by (how_much) seconds/nanoseconds */
int shw_pps_gen_adjust(int counter, int64_t how_much);
/* Returns 1 when the PPS is busy adjusting its time counters, 0 if PPS gen idle */
int shw_pps_gen_busy(void);
/* Enables/disables PPS Generator PPS output */
int shw_pps_gen_enable_output(int enable);
/* Masks/unmasks PPS output when link is down (useful in master mode) */
int shw_pps_gen_unmask_output(int unmask);
/* Reads the current time and stores at <seconds,nanoseconds>. */
void shw_pps_gen_get_time(uint64_t * seconds, uint32_t * nanoseconds);
/* Sets the time to <seconds,nanoseconds>. */
void shw_pps_gen_set_time(uint64_t seconds, uint32_t nanoseconds, int counter);
#endif
/*
* DSI Shield
*
* Copyright (C) 2013-2015 twl <twlostow@printf.cc>
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __SPI_H
#define __SPI_H
#include "gpio.h"
struct spi_bus
{
const struct gpio_pin *pin_cs;
const struct gpio_pin *pin_mosi;
const struct gpio_pin *pin_miso;
const struct gpio_pin *pin_sck;
int bit_delay;
int rd_falling_edge;
};
void spi_cs(struct spi_bus *bus, int cs);
void spi_delay(struct spi_bus *bus);
uint32_t spi_read(struct spi_bus *bus, int n_bits);
void spi_write(struct spi_bus *bus, uint32_t d, int n_bits);
int bb_spi_create( struct spi_bus *bus,
struct gpio_pin *pin_cs,
struct gpio_pin *pin_mosi,
struct gpio_pin *pin_miso,
struct gpio_pin *pin_sck,
int bit_delay
);
#endif
/*
* This work is part of the White Rabbit project
*
* Copyright (C) 2012 - 2015 CERN (www.cern.ch)
* Author: Grzegorz Daniluk <grzegorz.daniluk@cern.ch>
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef __SYSCON_H
#define __SYSCON_H
#include <inttypes.h>
#include <sys/types.h>
#include "board.h"
uint32_t timer_get_tics(void);
void timer_delay(uint32_t tics);
/* The following ones come from the kernel, but simplified */
#ifndef time_after
#define time_after(a,b) \
((long)(b) - (long)(a) < 0)
#define time_before(a,b) time_after(b,a)
#define time_after_eq(a,b) \
((long)(a) - (long)(b) >= 0)
#define time_before_eq(a,b) time_after_eq(b,a)
#endif
/* This can be used for up to 2^32 / TICS_PER_SECONDS == 42 seconds in wrs */
static inline void timer_delay_ms(int ms)
{
timer_delay(ms * TICS_PER_SECOND / 1000);
}
/* usleep.c */
extern void usleep_init(void);
#ifndef unix
extern int usleep(useconds_t usec);
#endif
#ifdef CONFIG_WR_NODE
#undef PACKED /* if we already included a regs file, we'd get a warning */
#include <hw/wrc_syscon_regs.h>
struct SYSCON_WB {
uint32_t RSTR; /*Syscon Reset Register */
uint32_t GPSR; /*GPIO Set/Readback Register */
uint32_t GPCR; /*GPIO Clear Register */
uint32_t HWFR; /*Hardware Feature Register */
uint32_t HWIR; /*Hardware Info Register */
uint32_t SDBFS; /*Flash SDBFS Info Register */
uint32_t TCR; /*Timer Control Register */
uint32_t TVR; /*Timer Counter Value Register */
uint32_t DIAG_INFO;
uint32_t DIAG_NW;
uint32_t DIAG_CR;
uint32_t DIAG_DAT;
uint32_t WDIAG_CTRL;
uint32_t WDIAG_SSTAT;
uint32_t WDIAG_PSTAT;
uint32_t WDIAG_PTPSTAT;
uint32_t WDIAG_ASTAT;
uint32_t WDIAG_TXFCNT;
uint32_t WDIAG_RXFCNT;
uint32_t WDIAG_SEC_MSB;
uint32_t WDIAG_SEC_LSB;
uint32_t WDIAG_NS;
uint32_t WDIAG_MU_MSB;
uint32_t WDIAG_MU_LSB;
uint32_t WDIAG_DMS_MSB;
uint32_t WDIAG_DMS_LSB;
uint32_t WDIAG_ASYM;
uint32_t WDIAG_CKO;
uint32_t WDIAG_SETP;
uint32_t WDIAG_UCNT;
uint32_t WDIAG_TEMP;
};
/*GPIO pins*/
#define GPIO_LED_LINK SYSC_GPSR_LED_LINK
#define GPIO_LED_STAT SYSC_GPSR_LED_STAT
#define GPIO_BTN1 SYSC_GPSR_BTN1
#define GPIO_BTN2 SYSC_GPSR_BTN2
#define GPIO_SFP_DET SYSC_GPSR_SFP_DET
#define GPIO_SPI_SCLK SYSC_GPSR_SPI_SCLK
#define GPIO_SPI_NCS SYSC_GPSR_SPI_NCS
#define GPIO_SPI_MOSI SYSC_GPSR_SPI_MOSI
#define GPIO_SPI_MISO SYSC_GPSR_SPI_MISO
#define WRPC_FMC_I2C 0
#define WRPC_SFP_I2C 1
#define FMC_I2C_DELAY 15
#define SFP_I2C_DELAY 300
struct s_i2c_if {
uint32_t scl;
uint32_t sda;
uint32_t loop_delay;
};
extern struct s_i2c_if i2c_if[2];
void timer_init(uint32_t enable);
extern volatile struct SYSCON_WB *syscon;
/****************************
* GPIO
***************************/
static inline void gpio_out(int pin, int val)
{
if (val)
syscon->GPSR = pin;
else
syscon->GPCR = pin;
}
static inline int gpio_in(int pin)
{
return syscon->GPSR & pin ? 1 : 0;
}
static inline int sysc_get_memsize(void)
{
return (SYSC_HWFR_MEMSIZE_R(syscon->HWFR) + 1) * 16;
}
#define HW_NAME_LENGTH 5 /* 4 letters + '\0' */
void get_hw_name(char *str);
void get_storage_info(int *memtype, uint32_t *sdbfs_baddr, uint32_t *blocksize);
#define DIAG_RW_BANK 0
#define DIAG_RO_BANK 1
void diag_read_info(uint32_t *id, uint32_t *ver, uint32_t *nrw, uint32_t *nro);
int diag_read_word(uint32_t adr, int bank, uint32_t *val);
int diag_write_word(uint32_t adr, uint32_t val);
void net_rst(void);
int wdiag_set_valid(int enable);
int wdiag_get_valid(void);
int wdiag_get_snapshot(void);
void wdiags_write_servo_state(int wr_mode, uint8_t servostate, uint64_t mu,
uint64_t dms, int32_t asym, int32_t cko,
int32_t setp, int32_t ucnt);
void wdiags_write_port_state(int link, int locked);
void wdiags_write_ptp_state(uint8_t ptpstate);
void wdiags_write_aux_state(uint32_t aux_states);
void wdiags_write_cnts(uint32_t tx, uint32_t rx);
void wdiags_write_time(uint64_t sec, uint32_t nsec);
void wdiags_write_temp(uint32_t temp);
#endif /* CONFIG_WR_NODE */
#endif
/*
* This work is part of the White Rabbit project
*
* Released according to the GNU GPL, version 2 or any later version.
*/
#ifndef __UART_H
#define __UART_H
void uart_init_hw(void);
void uart_write_byte(int b);
int uart_write_string(const char *s);
int puts(const char *s);
int uart_read_byte(void);
#endif
/*
* Onewire generic interface
* Alessandro Rubini, 2013 GNU GPL2 or later
*/
#ifndef __BATHOS_W1_H__
#define __BATHOS_W1_H__
#include <stdint.h>
#define W1_MAX_DEVICES 8 /* we have no alloc */
struct w1_dev {
struct w1_bus *bus;
uint64_t rom;
};
static inline int w1_class(struct w1_dev *dev)
{
return dev->rom & 0xff;
}
struct w1_bus {
unsigned long detail; /* gpio bit or whatever (driver-specific) */
struct w1_dev devs[W1_MAX_DEVICES];
};
/*
* The low-level driver is based on this set of operations. We expect to
* only have one set of such operations in each build. (i.e., no bus-specific
* operations, to keep the thing simple and small).
*/
struct w1_ops {
int (*reset)(struct w1_bus *bus); /* returns 1 on "present" */
int (*read_bit)(struct w1_bus *bus);
void (*write_bit)(struct w1_bus *bus, int bit);
};
/* Library functions */
extern int w1_scan_bus(struct w1_bus *bus);
extern void w1_write_byte(struct w1_bus *bus, int byte);
extern int w1_read_byte(struct w1_bus *bus);
extern void w1_match_rom(struct w1_dev *dev);
#define W1_CMD_SEARCH_ROM 0xf0
#define W1_CMD_READ_ROM 0x33
#define W1_CMD_MATCH_ROM 0x55
#define W1_CMD_SKIP_ROM 0xcc
#define W1_CMD_ASEARCH 0xec
/* commands for specific families */
#define W1_CMDT_CONVERT 0x44
#define W1_CMDT_W_SPAD 0x4e
#define W1_CMDT_R_SPAD 0xbe
#define W1_CMDT_CP_SPAD 0x48
#define W1_CMDT_RECALL 0xb8
#define W1_CMDT_R_PS 0xb4
/* EEPROM DS28EC20 */
#define W1_CMDR_W_SPAD 0x0f
#define W1_CMDR_R_SPAD 0xaa
#define W1_CMDR_C_SPAD 0x55
#define W1_CMDR_R_MEMORY 0xf0
#define W1_CMDR_EXT_R_MEMORY 0xa5
/* Temperature conversion takes time: by default wait, but allow flags */
#define W1_FLAG_NOWAIT 0x01 /* start conversion only*/
#define W1_FLAG_COLLECT 0x02 /* don't start, just get output */
/* These functions are dev-specific */
extern int32_t w1_read_temp(struct w1_dev *dev, unsigned long flags);
extern int w1_read_eeprom(struct w1_dev *dev,
int offset, uint8_t *buffer, int blen);
extern int w1_write_eeprom(struct w1_dev *dev,
int offset, const uint8_t *buffer, int blen);
extern int w1_erase_eeprom(struct w1_dev *dev, int offset, int blen);
/* These are generic, using the first suitable device in the bus */
extern int32_t w1_read_temp_bus(struct w1_bus *bus, unsigned long flags);
extern int w1_read_eeprom_bus(struct w1_bus *bus,
int offset, uint8_t *buffer, int blen);
extern int w1_write_eeprom_bus(struct w1_bus *bus,
int offset, const uint8_t *buffer, int blen);
extern int w1_erase_eeprom_bus(struct w1_bus *bus, int offset, int blen);
extern struct w1_ops wrpc_w1_ops;
extern struct w1_bus wrpc_w1_bus;
extern void wrpc_w1_init(void);
#endif /* __BATHOS_W1_H__ */
......@@ -62,7 +62,7 @@ static void wrc_initialize(void)
timer_init(1);
mprintf("Board low-level setup\n");
pp_printf("Board low-level setup\n");
ertm14_init();
get_hw_name(wrc_hw_name);
......
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