Example code for the simulavrxx<->verilog interface. Signed-off-by: Onno Kortmann <[email protected]> --- examples/verilog/Makefile | 39 +++++ examples/verilog/README | 11 ++ examples/verilog/baretest.sav | 6 + examples/verilog/baretest.v | 60 ++++++++ examples/verilog/csinglepincomm.c | 200 ++++++++++++++++++++++++++ examples/verilog/csinglepincomm.h | 53 +++++++ examples/verilog/left-unit.c | 39 +++++ examples/verilog/loop.c | 29 ++++ examples/verilog/loop.sav | 9 ++ examples/verilog/loop.v | 38 +++++ examples/verilog/right-unit.s | 51 +++++++ examples/verilog/singlepincomm.h | 134 ++++++++++++++++++ examples/verilog/singlepincomm.s | 278 +++++++++++++++++++++++++++++++++++++ examples/verilog/spc.sav | 18 +++ examples/verilog/spc.v | 102 ++++++++++++++ examples/verilog/toggle.c | 28 ++++ 16 files changed, 1095 insertions(+), 0 deletions(-) create mode 100644 examples/verilog/Makefile create mode 100644 examples/verilog/README create mode 100644 examples/verilog/baretest.sav create mode 100644 examples/verilog/baretest.v create mode 100644 examples/verilog/csinglepincomm.c create mode 100644 examples/verilog/csinglepincomm.h create mode 100644 examples/verilog/left-unit.c create mode 100644 examples/verilog/loop.c create mode 100644 examples/verilog/loop.sav create mode 100644 examples/verilog/loop.v create mode 100644 examples/verilog/right-unit.s create mode 100644 examples/verilog/singlepincomm.h create mode 100644 examples/verilog/singlepincomm.s create mode 100644 examples/verilog/spc.sav create mode 100644 examples/verilog/spc.v create mode 100644 examples/verilog/toggle.c
diff --git a/examples/verilog/Makefile b/examples/verilog/Makefile new file mode 100644 index 0000000..7d175db --- /dev/null +++ b/examples/verilog/Makefile @@ -0,0 +1,39 @@ +AVR_PROGRAMS= toggle.elf loop.elf left-unit.elf right-unit.elf +AVRS= ../../src/verilog/ + +all: $(AVR_PROGRAMS) \ + baretest.run \ + loop.run \ + spc.run + +%.o: %.c + avr-gcc -mmcu=attiny2313 -c -Os $^ -o $@ + +%.o: %.s + avr-gcc -c -Wa,-gstabs -x assembler-with-cpp -o $@ $< + +left-unit.elf: left-unit.o csinglepincomm.o + +right-unit.elf: right-unit.o singlepincomm.o + avr-ld -e _start $^ -o $@ + + +%.elf: %.o + avr-gcc -mmcu=attiny2313 $^ -o $@ + +%.vvp: %.v + iverilog $^ -s test -v -I. $(AVRS)/avr.v $(AVRS)/avr_ATtiny15.v $(AVRS)/avr_ATtiny2313.v -o $@ + +%.run: %.vvp + vvp -M../../src -mavr $^ + +%.view: %.vcd %.sav + gtkwave -a $*.sav $*.vcd & +clean: + rm -f *.vvp *~ *.o $(AVR_PROGRAMS) *.vcd avr.vpi *.trace + +# +# trace VPI with: +# $ export VPI_TRACE=log.txt + +# \ No newline at end of file diff --git a/examples/verilog/README b/examples/verilog/README new file mode 100644 index 0000000..d6e8036 --- /dev/null +++ b/examples/verilog/README @@ -0,0 +1,11 @@ +This directory contains some examples of how one can use +the VERILOG simulavrxx interface. Just call + +> make + +and after that, use + +> make <file>.view + +with the base name one of the example files (such as baretest.v -> +make baretest.view), to view the results in gtkwave. diff --git a/examples/verilog/baretest.sav b/examples/verilog/baretest.sav new file mode 100644 index 0000000..e08b2f1 --- /dev/null +++ b/examples/verilog/baretest.sav @@ -0,0 +1,6 @@ +[size] 1672 994 +[pos] -1 -1 +*-12.000000 2 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 +...@28 +test.clk +test.pb0 diff --git a/examples/verilog/baretest.v b/examples/verilog/baretest.v new file mode 100644 index 0000000..afac2fc --- /dev/null +++ b/examples/verilog/baretest.v @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2007 Onno Kortmann <[email protected]> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. + * + */ + +/* + Bare simulavrxx AVR<->verilog interface 'testbench' without using any of + the gluecode in avr.v + */ +`timescale 1ns / 1ns + +module test; + + integer hd; + reg clk; + + + initial begin + // $display("%h",dfdf); + $dumpfile("baretest.vcd"); + $dumpvars(0, test); + hd=8'h01; + #1 hd=8'h02; + #1 hd=8'h03; + hd=$avr_create("AT4433", "toggle.elf"); + $avr_reset(hd); + #100_000 $avr_destroy(hd); + $finish; + end + + integer val; + // Pin state LOW is zero + wire pb0=val!=1'b0; + + + always @(posedge clk) begin + #10 $avr_tick(hd); + #10 val=$avr_get_pin(hd, "B0"); + end + + always begin + #125 clk<=0; //125000 -> 4MHz clock + #125 clk<=1; + end +endmodule // test + diff --git a/examples/verilog/csinglepincomm.c b/examples/verilog/csinglepincomm.c new file mode 100644 index 0000000..640eb7a --- /dev/null +++ b/examples/verilog/csinglepincomm.c @@ -0,0 +1,200 @@ +// Copyright (C) 2009 Onno Kortmann <[email protected]> +// +// This program is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +//----------------------------------------------------------------------------- +// +// IMPORTANT NOTE: This file is only to illustrate the simulavrxx<->verilog +// interface and is by no means any reference for anything whatsoever! It +// probably contains lots of bugs! As already stated above, there is no +// warranty! +// +//----------------------------------------------------------------------------- +#include <avr/io.h> +#include <avr/interrupt.h> +#include "csinglepincomm.h" +#define F_CPU 12000000 +// Port definition for SPC +// NOTE: DO NOT CHANGE THESE EASILY, THE TIMER OUTPUT PINS ARE USED +// SO CHANGING THE PINS IS USUALLY NOT AN OPTION! +#define SPC_PORT PORTB +#define SPC_DDR DDRB +#define SPC_PIN PINB +#define SPC_BIT PB3 + +// Constant to delay the short delay (t_s), initial value. In clock ticks */ +#define SPC_INITIAL_DELAY 1500 + +// Initial multiplier N to go from t_s to t_l: t_l=N*t_s */ + #define SPC_LONG_DELAY 3 + +// loop cycles to wait for receive signal +#define SPC_RX_TIMEOUT 20000 + +// minimum distance between the high and the low count, in number of counts of +// the smaller value +#define SPC_MINIMUM_DISTANCE 2 + +// Interrupt blocking? +#if SPC_CLISEI +#define NCLI cli() +#define NSEI sei() +#else +#define NCLI +#define NSEI +#endif + +uint16_t spc_delay=SPC_INITIAL_DELAY; +uint8_t spc_multiplier=SPC_LONG_DELAY; +uint8_t spc_mindistance=SPC_MINIMUM_DISTANCE; + +void spc_init() { + // enable pull up + SPC_PORT|=_BV(SPC_BIT); +} + +uint8_t spc_trx_bit(uint8_t bit) { + uint16_t timeout, high_time, low_time; + uint16_t spc_long_delay=spc_delay * spc_multiplier; + // ------------------------------------------------------------ + // --- TRANSMIT --- + // ------------------------------------------------------------ + NCLI; + TCCR1B=0; // stop counter + // timer preparation + + // force compare-match into high state + TCCR1A=_BV(COM1A1)|_BV(COM1A0); // set PB3 on compare match + TCCR1C=_BV(FOC1A); // force output compare + // set high state of comp.match on output (should be just pullup before) + SPC_DDR|=_BV(SPC_BIT); + TCCR1A=_BV(COM1A1); // clear PB3 on compare match + TIFR|=_BV(OCF1A); // clear comp.match + + // set time until zero + if (bit) + OCR1A=spc_long_delay; + else + OCR1A=spc_delay; + + // reset counter + TCNT1=0; + + // and apply full system clock timer1 + TCCR1B=_BV(CS10); + NSEI; + + // wait until high part has been sent + while (! (TIFR & _BV(OCF1A))); + + NCLI; + TCCR1B=0; // stop counter + TCCR1A=_BV(COM1A1)|_BV(COM1A0); // set PB3 on compare match + TIFR|=_BV(OCF1A); // clear comp.match + + // set time until one + if (bit) + OCR1A=spc_delay; + else + OCR1A=spc_long_delay; + + // reset counter + TCNT1=0; + + TCCR1B=_BV(CS10); // start counter + NSEI; + + // wait until low part has been sent + while (! (TIFR & _BV(OCF1A))); + NCLI; + //TIFR|=_BV(OCF1A); // clear comp.match + // ------------------------------------------------------------ + // --- RECEIVE --- + // ------------------------------------------------------------ + // go back to normal port mode on PB3 + TCCR1A=0; + SPC_DDR&=~_BV(SPC_BIT); + + OCR1A=0x0000; // 'disable' OCR1A + + NSEI; + + /* stop and clear counter, set noise canceler bit, + get ready for input capture. */ + TCNT1=0; + TIFR|=_BV(ICF1); + TCCR1B=_BV(CS10)|_BV(ICNC1); + NSEI; + + // wait for falling edge + timeout=0; + while (! (TIFR & _BV(ICF1))) { + if (timeout == SPC_RX_TIMEOUT) + return 2; + timeout++; + } + NCLI; + high_time=ICR1; // read that value + // get ready for another round, raising edge now + TCCR1B=_BV(CS10)|_BV(ICNC1)|_BV(ICES1); + TIFR|=_BV(ICF1); + NSEI; + + // wait for rising edge + timeout=0; + while (! (TIFR & _BV(ICF1))) { + if (timeout == SPC_RX_TIMEOUT) + return 2; + timeout++; + } + + NCLI; + low_time=ICR1-high_time; // read that value, too + NSEI; + + if (high_time>low_time) { + if (high_time<low_time * spc_mindistance) + return 2; + else return 1; + } else { + if (low_time<high_time * spc_mindistance) + return 2; + else return 0; + } +} + + +uint16_t spc_trx(uint8_t val) { + uint8_t res; + uint8_t i; + uint8_t rxbit; + + // send start bit + i=spc_trx_bit(0); + + if (i) // timeout or 'one' bit? + return 0x100 * i; + + // main TRX loop + res=0; + for (i=0; i < 8; i++) { + rxbit=spc_trx_bit(val & 0x01); + if (rxbit>1) + return 0x100 * rxbit; // timeout or framing error! + if (rxbit) res|=1<<i; + val>>=1; + } + return res; +} diff --git a/examples/verilog/csinglepincomm.h b/examples/verilog/csinglepincomm.h new file mode 100644 index 0000000..b216ce6 --- /dev/null +++ b/examples/verilog/csinglepincomm.h @@ -0,0 +1,53 @@ +//----------------------------------------------------------------------------- +// Copyright (C) 2009 Onno Kortmann <[email protected]> +// +// This program is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +//----------------------------------------------------------------------------- +// +// IMPORTANT NOTE: This file is only to illustrate the simulavrxx<->verilog +// interface and is by no means any reference for anything whatsoever! It +// probably contains lots of bugs! As already stated above, there is no +// warranty! +// +//----------------------------------------------------------------------------- +#ifndef __SINGLEPINCOMM_H +#define __SINGLEPINCOMM_H +//----------------------------------------------------------------------------- +//! Initialize SPC interface +/* The SPC interface uses the 16bit timer counter1 */ +void spc_init(); + +//! TRX one byte +/* Does not block any interrupts and works through the timer/counter1 + interface and its interrupts. + + Returns the received byte in the low byte. + If the high byte is non-zero, an error has occured. + */ +uint16_t spc_trx(uint8_t val); + +//! Send/receive single bits +uint8_t spc_trx_bit(uint8_t bit); + +//! Value for producing delays +extern uint16_t spc_delay; +//! Multiplier value +extern uint8_t spc_multiplier; +/*! Minimum distance (in smaller counts) to the larger plateau before + signalling an error. */ +extern uint8_t spc_mindistance; +//----------------------------------------------------------------------------- +#endif diff --git a/examples/verilog/left-unit.c b/examples/verilog/left-unit.c new file mode 100644 index 0000000..9af36aa --- /dev/null +++ b/examples/verilog/left-unit.c @@ -0,0 +1,39 @@ +/* + * Copyright (C) 2007 Onno Kortmann <[email protected]> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. + * + */ +#include <avr/io.h> +#define F_CPU 12000000 +#include <util/delay.h> +#include "csinglepincomm.h" + +int main() { + // wait until other side is ready + _delay_us(200); + spc_init(); + spc_trx(0x03); // flash read + spc_trx(0x01); // adr L + spc_trx(0x00); // adr H + + /* Flash @ word 0x0001: 0xc0. This should appear in simsend in the gtkwave + window! */ + + /* read byte and place into memory location where it + can be read by by the verilog code... yes, this is very crude! */ + *(unsigned char*)(0x70)=spc_trx(0x00); + return 0; +} diff --git a/examples/verilog/loop.c b/examples/verilog/loop.c new file mode 100644 index 0000000..4c7128a --- /dev/null +++ b/examples/verilog/loop.c @@ -0,0 +1,29 @@ +/* + * Copyright (C) 2007 Onno Kortmann <[email protected]> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. + * + */ +/* Set PB0 high once and + then feed PB1 through to PB0. */ +#include <avr/io.h> + +int main() { + DDRB=0xff; + PORTB=1; + while(1) { + PORTB=PINB<<1; + } +} diff --git a/examples/verilog/loop.sav b/examples/verilog/loop.sav new file mode 100644 index 0000000..8f55f48 --- /dev/null +++ b/examples/verilog/loop.sav @@ -0,0 +1,9 @@ +[size] 1672 994 +[pos] -1 -1 +*-13.000000 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 +[treeopen] test. +[treeopen] test.avr. +...@28 +test.clock.clk +...@22 +test.avr.PB[7:0] diff --git a/examples/verilog/loop.v b/examples/verilog/loop.v new file mode 100644 index 0000000..8b7c9b5 --- /dev/null +++ b/examples/verilog/loop.v @@ -0,0 +1,38 @@ +/* + * Copyright (C) 2007 Onno Kortmann <[email protected]> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. + * + */ + +/* Simple input-output combined test. */ + +`timescale 1ns / 1ns + +module test; + + wire clk; + wire [7:0] pa, pb, pd; + + defparam avr.progfile="loop.elf"; + ATtiny2313 avr(clk, pa, pb, pd); + avr_clock clock(clk); + + initial begin + $dumpfile("loop.vcd"); + $dumpvars(0, test); + #100_000 $finish; + end +endmodule \ No newline at end of file diff --git a/examples/verilog/right-unit.s b/examples/verilog/right-unit.s new file mode 100644 index 0000000..0d4c787 --- /dev/null +++ b/examples/verilog/right-unit.s @@ -0,0 +1,51 @@ +// Copyright (C) 2009 Onno Kortmann <[email protected]> +// +// This program is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +.arch ATTiny15 +#define __SFR_OFFSET 0 + +#define __AVR_ATtiny15__ 1 +#include <avr/io.h> + +#include "singlepincomm.h" + +.section .text +.global _start +_start: +reset_vec: + rjmp reset +ext_int0_vec: + reti +pin_change_vec: + reti +tim1_cmp_vec: + reti +tim1_ovf_vec: + reti +tim0_ovf_vec: + reti +ee_rdy_vec: + reti +ana_comp_vec: + reti +adc_vec: + reti +reset: + ldi temp0, 0x10 + mov spc_delay, temp0 +l: + spc_slave_menu + rjmp l diff --git a/examples/verilog/singlepincomm.h b/examples/verilog/singlepincomm.h new file mode 100644 index 0000000..2d0b2a0 --- /dev/null +++ b/examples/verilog/singlepincomm.h @@ -0,0 +1,134 @@ +#ifndef SINGLEPINCOMM_REGISTERS +#define SINGLEPINCOMM_REGISTERS +//----------------------------------------------------------------------------- +// Copyright (C) 2009 Onno Kortmann <[email protected]> +// +// This program is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +//----------------------------------------------------------------------------- +// +// IMPORTANT NOTE: This file is only to illustrate the simulavrxx<->verilog +// interface and is by no means any reference for anything whatsoever! It +// probably contains lots of bugs! As already stated above, there is no +// warranty! +// +//----------------------------------------------------------------------------- +; used by the low level parts +#if SPC_16BIT_TIME +#define lowcntl r0 +#define highcntl r1 +#endif + +#define lowcnth r20 +#define highcnth r21 + +#define temp0 r16 +#define temp1 r17 +#define trxbyte r18 +#define bitcnt r19 + +// Register which may be used for the configurable software delay +#define spc_delay r2 +//----------------------------------------------------------------------------- +// Port definition for SPC +#define SPC_PORT PORTB +#define SPC_DDR DDRB +#define SPC_PIN PINB +#define SPC_BIT PB2 + +// Debugging? +#define SPC_DEBUG 0 + +// Iff true, take the software-configurable delay from register spc_delay +#define SPC_SWDELAY 1 + +// Constant to delay the short delay (t_s) */ +#define SPC_TSVALUE 150 +// Multiplier N to go from t_s to t_l: t_l=N*t_s */ +#define SPC_N 3 + +// Iff true, enclose all timing sensitive parts in CLI/SEI pairs. +#define SPC_CLISEI 0 + +// Iff true, implement reading of the flash space through command 0x03 in the menu +#define SPC_FLASH_READ 1 + +// timeout in high-byte loop cycles for RX bit (0=> 256*256 cycles) +#define SPC_RX_TIMEOUT 0 + +// Iff true, wait for the line to be high first for each bit +#define SPC_RX_WAIT_INITIAL_HIGH 0 + +/// Iff true, use 16bit registers for timing +#define SPC_16BIT_TIME 0 +//----------------------------------------------------------------------------- +/* Simple menu for the slave. + Call it to allow the master to read/write the RAM. */ + +.macro spc_slave_menu + clr trxbyte + rcall spc_trx_slave + brts ssm_end ; timeout! + cpi trxbyte, 0x01 ; ram read? + breq ssm_read + cpi trxbyte, 0x02 ; ram write? + breq ssm_write +#if SPC_FLASH_READ + cpi trxbyte, 0x03 ; flash read? + breq ssm_flash_read +#endif + brne ssm_end ; something unknown... +ssm_read: + rcall spc_trx_slave ; read low byte for location + brts ssm_end + mov r30, trxbyte + + rcall spc_trx_slave ; and high byte + brts ssm_end + mov r31, trxbyte + + ld trxbyte, Z ; load byte to transmit + rcall spc_trx_slave ; and send it! + rjmp ssm_end + +ssm_write: + rcall spc_trx_slave ; read low byte for location + brts ssm_end + mov r30, trxbyte + + rcall spc_trx_slave ; and high byte + brts ssm_end + mov r31, trxbyte + + rcall spc_trx_slave ; and byte to write! + brts ssm_end + st Z, trxbyte +#if SPC_FLASH_READ +ssm_flash_read: + rcall spc_trx_slave ; read low byte for location + brts ssm_end + mov r30, trxbyte + + rcall spc_trx_slave ; and high byte + brts ssm_end + mov r31, trxbyte + + lpm ; load byte to transmit! + mov trxbyte, r0 ; r0 can be used, is lowcnt + rcall spc_trx_slave ; and send it! +#endif +ssm_end: +.endm +//----------------------------------------------------------------------------- +#endif diff --git a/examples/verilog/singlepincomm.s b/examples/verilog/singlepincomm.s new file mode 100644 index 0000000..e86efc4 --- /dev/null +++ b/examples/verilog/singlepincomm.s @@ -0,0 +1,278 @@ +//----------------------------------------------------------------------------- +// Copyright (C) 2009 Onno Kortmann <[email protected]> +// +// This program is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +//----------------------------------------------------------------------------- +// +// IMPORTANT NOTE: This file is only to illustrate the simulavrxx<->verilog +// interface and is by no means any reference for anything whatsoever! It +// probably contains lots of bugs! As already stated above, there is no +// warranty! +// +//----------------------------------------------------------------------------- +.arch ATTiny15 +#define __AVR_ATtiny15__ 1 +#define __SFR_OFFSET 0 +#include <avr/io.h> +#include "singlepincomm.h" + +#if SPC_DEBUG + +// some random TRX debugging... ;-) +.macro dbg1on + sbi PORTB, PB3 + sbi DDRB, PB3 +.endm + +.macro dbg1off + cbi PORTB, PB3 + sbi DDRB, PB3 +.endm + +.macro dbg2on + sbi PORTB, PB4 + sbi DDRB, PB4 +.endm + +.macro dbg2off + cbi PORTB, PB4 + sbi DDRB, PB4 +.endm +#else + +.macro dbg1on +.endm +.macro dbg1off +.endm +.macro dbg2on +.endm +.macro dbg2off +.endm + +#endif + +#include "singlepincomm.h" + +#if SPC_CLISEI +#define CLI cli +#define SEI sei +#else +#define CLI +#define SEI +#endif + +/* Receive one 'bit': + 0. Switch to input + 1. Wait for high state (no timeout) + 2. Wait for low state, count this as highcnt + 3. Wait for high state again, count this as lowcnt + 4. Result is: + C=0 for a received zero (low phase longer than high phase) + C=1 otherwise + T=0 for everything ok + T=1 for timeout + + */ +.global spc_recv_bit +spc_rx_bit: + dbg1on + clt + cbi SPC_DDR, SPC_BIT + +#if SPC_RX_WAIT_INITIAL_HIGH +#if SPC_16BIT_TIME + clr lowcntl +#endif + clr lowcnth + + ;; wait for high (timeout when line is shorted to ground) +srb_waitinit: + sbic SPC_PIN, SPC_BIT + rjmp srb_waitinit_ready +#if SPC_16BIT_TIME + inc lowcntl + brne srb_waitinit +#endif + inc lowcnth + cpi lowcnth, SPC_RX_TIMEOUT + breq srb_timeout + rjmp srb_waitinit + +srb_waitinit_ready: +#endif +#if SPC_16BIT_TIME + clr lowcntl +#endif + clr lowcnth +#if SPC_16BIT_TIME + clr highcntl +#endif + clr highcnth + + ;; wait for low +srb_wait0: + sbis SPC_PIN, SPC_BIT + rjmp srb_wait0_ready +#if SPC_16BIT_TIME + inc highcntl + brne srb_wait0 +#endif + inc highcnth + cpi highcnth, SPC_RX_TIMEOUT + breq srb_timeout + rjmp srb_wait0 +srb_wait0_ready: + + ;; wait for high +srb_wait1: + sbic SPC_PIN, SPC_BIT + rjmp srb_wait1_ready +#if SPC_16BIT_TIME + inc lowcntl + brne srb_wait1 +#endif + inc lowcnth + cpi lowcnth, SPC_RX_TIMEOUT + breq srb_timeout + rjmp srb_wait1 +srb_wait1_ready: + ;; compare both times + cp lowcnth, highcnth +#if SPC16BIT_TIME + breq srb_compare_low +#endif + dbg1off + ret +#if SPC16BIT_TIME +srb_compare_low: + cp lowcntl, highcntl +#endif + dbg1off + ret +srb_timeout: + dbg1off + set + ret + +.macro spc_short_delay +#if SPC_SWDELAY + mov temp0, spc_delay +#else + ldi temp0, SPC_TSVALUE +#endif +ll\@: + dec temp0 + brne ll\@ +.endm + +/* Send one bit from carry. */ +.global spc_tx_bit +spc_tx_bit: + dbg2on + ;; start with transmission of high state + sbi SPC_PORT, SPC_BIT + sbi SPC_DDR, SPC_BIT + brcs tx1 +tx0: + spc_short_delay + cbi SPC_PORT, SPC_BIT + ldi temp1, SPC_N +tx0l: + spc_short_delay + dec temp1 + brne tx1l + ;; high again - and input +spc_tx_end: + sbi SPC_PORT, SPC_BIT + cbi SPC_DDR, SPC_BIT + dbg2off + ret +tx1: + ldi temp1, SPC_N +tx1l: + spc_short_delay + dec temp1 + brne tx1l + ;; low + cbi SPC_PORT, SPC_BIT + spc_short_delay + ;; and high again - and input + rjmp spc_tx_end + + +// FIXME: Combine spc_trx_master and spc_trx_slave into one procedure! + +/* Do a complete transmit/receive for one byte as the master. This means + synchronizing with the slave (sending and receiving one start-zero) and + transmitting/receiving the content from/into trxbyte. */ +.section .text.spc_trx_master +.global spc_trx_master +spc_trx_master: + CLI + + ;; send start zero + clc + rcall spc_tx_bit + + ;; receive start zero + rcall spc_rx_bit + brts mspc_trx_end ; T=1 -> timeout ->failure + + ldi bitcnt, 8 + +mtrxloop: + ;; fetch next bit from trxbyte and send it + lsr trxbyte + rcall spc_tx_bit + rcall spc_rx_bit + brts mspc_trx_end ; handle timeouts + brcc mtrx_looptail ; zero received -> nothing to do + ori trxbyte, 0x80 ; push one into highest bit.. will rotate through to lower bits +mtrx_looptail: + dec bitcnt + brne mtrxloop +mspc_trx_end: + SEI + ret + +/* Do a complete transmit/receive for one byte as the slaver. This means + synchronizing with the master (receiving and sending one start-zero) and + transmitting/receiving the content from/into trxbyte. */ +.section .text.spc_trx_slave +.global spc_trx_slave +spc_trx_slave: + CLI + + ;; receive start zero + rcall spc_rx_bit + brts sspc_trx_end ; -> failure + + ;; send start zero + clc + rcall spc_tx_bit + + ldi bitcnt, 8 +strxloop: + rcall spc_rx_bit + brts sspc_trx_end ; handle timeouts + ror trxbyte ; stuff it into the trxbyte + rcall spc_tx_bit ; and transmit what fell out of the register at the other end + + dec bitcnt + brne strxloop +sspc_trx_end: + SEI + ret diff --git a/examples/verilog/spc.sav b/examples/verilog/spc.sav new file mode 100644 index 0000000..3058224 --- /dev/null +++ b/examples/verilog/spc.sav @@ -0,0 +1,18 @@ +[size] 1000 600 +[pos] -1 -1 +*-24.000000 362 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 +[treeopen] test. +[treeopen] test.lavr. +[treeopen] test.ravr. +...@28 +test.lclock.clk +test.rclock.clk +test.lrconn +...@22 +test.lavr.core.PCb[16:0] +test.ravr.core.PCb[16:0] +...@28 +test.lavr.pb3.output_active +test.ravr.pb2.output_active +...@22 +test.simsend[7:0] diff --git a/examples/verilog/spc.v b/examples/verilog/spc.v new file mode 100644 index 0000000..d8059a6 --- /dev/null +++ b/examples/verilog/spc.v @@ -0,0 +1,102 @@ +// Copyright (C) 2009 Onno Kortmann <[email protected]> +// +// This program is free software; you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation; either version 2 of the License, or +// (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +// IMPORTANT NOTE: This file is only to illustrate the simulavrxx<->verilog +// interface and is by no means any reference for anything whatsoever! It +// probably contains lots of bugs! As already stated above, there is no +// warranty! +//----------------------------------------------------------------------------- +/* Simple test with two units communicating with each other. + One unit is named 'left', the other unit is named right. + The left unit controls the right unit. The left unit runs at + 12MHz the right one only at 1.6MHz. + */ + +`timescale 1ns / 1ns + +module test; + wire lclk, rclk; + wire [7:0] leftpba, leftpb, leftpd; + wire [7:0] rightpb; + + defparam lavr.progfile="left-unit.elf"; + ATtiny2313 lavr(lclk, leftpba, leftpb, leftpd); + + defparam ravr.progfile="right-unit.elf"; + ATtiny15 ravr(rclk, rightpb); + + defparam lclock.FREQ=12_000_000; + defparam rclock.FREQ=1_600_000; + avr_clock lclock(lclk), rclock(rclk); + + + /* The following is the complete wiring between the two AVRs. Connects + the output-compare pin as well as the input-capture pin of the tiny2313 + to PB2 on the right tiny15l, and then puts a pullup on that connection. */ + wire lrconn; + assign lrconn=leftpb[3]; + assign lrconn=rightpb[2]; + assign lrconn=leftpd[6]; + + // put pull-up on single wire comm link + // note that this is slightly inaccurate as the pullups are formed + // from the switched AVR ones! + assign (strong0, weak1) lrconn=1; + + initial begin + $dumpfile("spc.vcd"); + $dumpvars(0, test); + + // enable this for too much output :) + //$avr_trace("spc.trace"); + + #40_000_000 ; + $finish; + end + + + reg[7:0] l_trxbyte; + reg[7:0] r_trxbyte; + + reg[15:0] l_lowcnt; + reg[15:0] r_lowcnt; + + reg[15:0] l_highcnt; + reg[15:0] r_highcnt; + + reg [7:0] simsend; + reg [7:0] simsend_clk; + reg [7:0] tcntl; + reg [7:0] tcnth; + + always @(lrconn) begin + $display("LRCONN %d", lrconn); + end + + always @(negedge lclk) begin + /* This connects directly to RAM location 0x70 in the left AVR to read + some useful information from that unit. */ + simsend=$avr_get_rw(lavr.core.handle, 'h0070); + // WARNING: Reading these registers would count as a 16bit read from the AVR!!! + //tcntl=$avr_get_rw(lavr.core.handle, 76); + //tcnth=$avr_get_rw(lavr.core.handle, 77); + end + always @(negedge rclk) begin + r_trxbyte=$avr_get_rw(ravr.core.handle, 18); + r_lowcnt=$avr_get_rw(ravr.core.handle, 0)+256*$avr_get_rw(ravr.core.handle, 20); + r_highcnt=$avr_get_rw(ravr.core.handle, 1)+256*$avr_get_rw(ravr.core.handle, 21); + end +endmodule // test diff --git a/examples/verilog/toggle.c b/examples/verilog/toggle.c new file mode 100644 index 0000000..819720b --- /dev/null +++ b/examples/verilog/toggle.c @@ -0,0 +1,28 @@ +/* + * Copyright (C) 2007 Onno Kortmann <[email protected]> + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. + * + */ +/* Simply toggle PB0. */ +#include <avr/io.h> + +int main() { + DDRB=1; + while(1) { + PORTB=1; + PORTB=0; + } +} -- 1.5.6.5 _______________________________________________ Simulavr-devel mailing list [email protected] http://lists.nongnu.org/mailman/listinfo/simulavr-devel
