Implemented base system for REV.A PCB.

This commit is contained in:
2018-11-11 14:13:02 +00:00
parent af7037db52
commit 9de6af996c
15 changed files with 543 additions and 60 deletions

View File

@@ -124,7 +124,6 @@ void Console::printMemory(uint16_t from, uint16_t to) {
}
void Console::loop() {
HardwareSerial * serial = this->serial;
uint32_t i;
switch(this->state) {
@@ -148,9 +147,7 @@ void Console::loop() {
this->stateActive();
break;
case CONSOLE_RUN:
if(this->vm->halted == false) {
vm_step(this->vm);
} else {
if(this->vm->halted) {
serial->print("VM Halted. PC=0x");
serial->print(this->vm->PC, HEX);
serial->println(". Registers:");
@@ -223,7 +220,9 @@ void Console::stateActive() {
serial->println("Console deactivated.");
this->state = CONSOLE_NONE;
} else if (this->inputBuffer->equals("r")) {
serial->println("VM Running...");
this->vm->halted = false;
this->vm->run = true;
this->state = CONSOLE_RUN;
} else if (this->inputBuffer->equals("s")) {
this->vm->halted = false;
@@ -365,6 +364,7 @@ void Console::stateExamine() {
}
}
} else {
serial->println(this->inputBuffer->c_str());
serial->println("Unknown command.");
}
if (this->state == CONSOLE_EXAMINE) {

176
arduino/Interface.cpp Normal file
View File

@@ -0,0 +1,176 @@
/*
Copyright 2018 Sam Stevens
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#include <Arduino.h>
#include "Interface.h"
#include "util.h"
Interface::Interface(VM *vm, Memory *mem, ShiftInput *input, ShiftOutput *disp, int regSwitchPin) {
this->vm = vm;
this->mem = mem;
this->input = input;
this->disp = disp;
//Inputs
this->regSwitchPin = regSwitchPin;
}
void Interface::init() {
pinMode(regSwitchPin, INPUT);
data = mem->read(addr);
//Lamp test
for(uint8_t i = 0; i < 16; i++) {
disp->output(i==0 ? 0xFF : 0x0);
disp->clockOutput();
delay(50);
}
for(uint8_t i = 0; i < 16; i++) {
disp->output(0xFF);
}
disp->clockOutput();
delay(500);
}
void Interface::loop() {
//Process inputs
uint8_t swLast = switchState;
if (input->updateInput()) {
uint8_t addrInputH = ~reverse8(input->getInput(0));
uint8_t addrInputL = ~reverse8(input->getInput(1));
uint8_t swInput = input->getInput(2);
uint16_t addrInput = (addrInputH << 8) + addrInputL;
//Check for buttons on rising edge
if ((swLast & SW_RUN) == 0 && (swInput & SW_RUN) == SW_RUN) {
if (vm->run) {
vm->run = false;
} else {
vm->run = true;
vm->halted = false;
}
}
else if ((swLast & SW_STEP) == 0 && (swInput & SW_STEP) == SW_STEP) {
if (vm->run == false) {
vm->halted = false;
vm_step(vm);
}
}
else if ((swLast & SW_RESET) == 0 && (swInput & SW_RESET) == SW_RESET) {
if (vm->run == false) {
vm_reset(vm);
}
}
else if ((swLast & SW_CLEAR) == 0 && (swInput & SW_CLEAR) == SW_CLEAR) {
if (vm->run == false) {
if (clearTimer == 0) {
clearTimer = millis() + 1000;
}
}
}
else if ((swLast & SW_CLEAR) == SW_CLEAR && (swInput & SW_CLEAR) == 0) {
clearTimer = 0;
}
else if ((swLast & SW_DEPOSIT) == 0 && (swInput & SW_DEPOSIT) == SW_DEPOSIT) {
data = addrInputH;
vm->writeAddr(addr, data);
}
else if ((swLast & SW_DEPOSIT_NEXT) == 0 && (swInput & SW_DEPOSIT_NEXT) == SW_DEPOSIT_NEXT) {
data = addrInputH;
vm->writeAddr(addr, data);
addr++;
}
else if ((swLast & SW_EXAMINE) == 0 && (swInput & SW_EXAMINE) == SW_EXAMINE) {
addr = addrInput;
data = mem->read(addr);
}
else if ((swLast & SW_EXAMINE_NEXT) == 0 && (swInput & SW_EXAMINE_NEXT) == SW_EXAMINE_NEXT) {
addr++;
data = mem->read(addr);
}
switchState = swInput;
}
if (vm->run) {
clearTimer = 0;
}
if (clearTimer > 0) {
if (clearTimer < millis()) {
vm_reset(vm);
disp->output16(0xFFFF);
for(uint8_t i = 0; i < 14; i++) {
disp->output((uint8_t)0);
}
disp->clockOutput();
mem->writeRange(0, 0, VM_MEM_SIZE);
addr = 0;
data = 0;
delay(500);
clearTimer = 0;
}
}
//Update Display
//Address
disp->output((uint8_t)(addr & 0xFF));
disp->output((uint8_t)(addr >> 8));
//Run/Halt
uint8_t status = 0;
if (vm->run) {
status |= 0x80;
}
if (vm->halted) {
status |= 0x40;
}
disp->output(status);
//Data
disp->output(data);
//Program counter and Instruction
uint16_t pc = vm->PC;
uint16_t instr = (mem->read(pc) << 8) + mem->read(pc + 1);
// disp->output((uint8_t)0xF);
// disp->output((uint8_t)0xF);
// disp->output((uint8_t)0xF);
// disp->output((uint8_t)0xF);
disp->output16(instr);
disp->output16(pc);
//Registers
// for(uint8_t i = 0; i < 8; i++) {
// disp->output((uint8_t)0);
// }
short int reg;
if (digitalRead(regSwitchPin) == HIGH) {
//Output 8-F
for(reg=0xF; reg >= 0x8; reg--) {
disp->output(vm->R[reg]);
}
} else {
//Output 0-F
for(reg=0x7; reg >= 0; reg--) {
disp->output(vm->R[reg]);
}
}
disp->clockOutput();
}

51
arduino/Interface.h Normal file
View File

@@ -0,0 +1,51 @@
/*
Copyright 2018 Sam Stevens
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#ifndef UVM_INTERFACE_H
#define UVM_INTERFACE_H
#define SW_RUN 0x40
#define SW_STEP 0x80
#define SW_RESET 0x10
#define SW_CLEAR 0x20
#define SW_DEPOSIT 0x02
#define SW_DEPOSIT_NEXT 0x01
#define SW_EXAMINE 0x08
#define SW_EXAMINE_NEXT 0x04
#include <stdint.h>
#include "VM.h"
#include "ShiftInput.h"
#include "ShiftOutput.h"
#include "Memory.h"
class Interface {
VM *vm;
Memory *mem;
ShiftInput *input;
ShiftOutput *disp;
int regSwitchPin = 0;
uint8_t switchState = 0;
uint16_t addr = 0;
uint8_t data = 0;
unsigned long int clearTimer = 0;
public:
Interface(VM *vm, Memory *mem, ShiftInput *input, ShiftOutput *disp, int regSwitchPin);
void init();
void loop();
};
#endif

View File

@@ -25,6 +25,7 @@ Memory::Memory(uint8_t csPin) {
this->memSize = 0xFFFF;
//Store spi setting
this->setting = SPISettings(20000000, MSBFIRST, SPI_MODE0);
SPI.begin();
}
void Memory::start() {
@@ -38,18 +39,23 @@ void Memory::end() {
bool Memory::init() {
//Set mode to sequential access (should be default mode)
this->start();
SPI.transfer(INSTR_WRMR);
SPI.transfer(MODE_SEQ);
this->end();
this->setMode(MODE_SEQ);
//Verify that it was set
return this->readMode() == MODE_SEQ;
}
void Memory::setMode(MemoryMode mode) {
this->start();
SPI.transfer(INSTR_WRMR);
SPI.transfer(mode);
this->end();
}
MemoryMode Memory::readMode() {
this->start();
SPI.transfer(INSTR_RDMR);
uint8_t mode = SPI.transfer(0);
MemoryMode mode = (MemoryMode)SPI.transfer(0);
this->end();
return mode == MODE_SEQ;
return mode;
}
uint16_t Memory::getSize() {
@@ -126,6 +132,12 @@ bool Memory::test() {
}
MemoryCache::MemoryCache(uint8_t cacheElements, Memory& memory) {
this->memory = &memory;
this->cache = (MemoryCacheItem*)calloc(cacheElements, sizeof(MemoryCacheItem));
this->cacheElements = cacheElements;
}
uint8_t MemoryCache::getSize() {
return this->cacheElements;
}
@@ -135,12 +147,6 @@ MemoryCacheItem* MemoryCache::getItem(uint8_t index) {
}
return NULL;
}
MemoryCache::MemoryCache(uint8_t cacheElements, Memory& memory) {
this->memory = &memory;
this->cache = (MemoryCacheItem*)calloc(cacheElements, sizeof(MemoryCacheItem));
this->cacheElements = cacheElements;
}
uint8_t MemoryCache::read(uint16_t addr) {
bool found = false;
uint8_t data = 0;
@@ -197,3 +203,9 @@ void MemoryCache::update(uint16_t addr, uint8_t data) {
}
}
void MemoryCache::clear() {
for(uint8_t i = 0; i < this->cacheElements; i++) {
this->cache[i].valid = false;
}
}

View File

@@ -46,6 +46,8 @@ class Memory {
Memory(uint8_t csPin);
uint16_t getSize();
void setSize(uint16_t memSize);
void setMode(MemoryMode mode);
MemoryMode readMode();
bool init();
uint8_t read(uint16_t addr);
void write(uint16_t addr, uint8_t data);
@@ -72,6 +74,7 @@ class MemoryCache {
MemoryCacheItem* getItem(uint8_t index);
uint8_t read(uint16_t addr);
void update(uint16_t addr, uint8_t data);
void clear();
};
#endif //UVM_MEMORY_H

View File

@@ -35,8 +35,11 @@ ShiftInput::ShiftInput(uint8_t chipCount, uint8_t loadPin, uint8_t clockPin, uin
}
}
uint8_t* ShiftInput::getInput() {
return this->input;
uint8_t ShiftInput::getInput(uint8_t chip) {
if (chip <= this->chipCount) {
return this->input[chip];
}
return 0;
}
uint8_t ShiftInput::getChipCount() {

View File

@@ -29,7 +29,7 @@ class ShiftInput {
public:
ShiftInput(uint8_t chipCount, uint8_t loadPin, uint8_t clockPin, uint8_t clockInhPin, uint8_t dataPin);
uint8_t getChipCount();
uint8_t *getInput();
uint8_t getInput(uint8_t chip);
bool updateInput();
};

59
arduino/ShiftOutput.cpp Normal file
View File

@@ -0,0 +1,59 @@
/*
Copyright 2018 Sam Stevens
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#include <Arduino.h>
#include "ShiftOutput.h"
ShiftOutput::ShiftOutput(uint8_t enablePin, uint8_t clkPin, uint8_t rClkPin, uint8_t dataPin) {
this->enablePin = enablePin;
this->clkPin = clkPin;
this->rClkPin = rClkPin;
this->dataPin = dataPin;
pinMode(enablePin, OUTPUT);
digitalWrite(enablePin, HIGH);
pinMode(clkPin, OUTPUT);
digitalWrite(clkPin, LOW);
pinMode(rClkPin, OUTPUT);
digitalWrite(rClkPin, LOW);
pinMode(dataPin, OUTPUT);
digitalWrite(dataPin, LOW);
}
void ShiftOutput::enable() {
digitalWrite(this->enablePin, LOW);
}
void ShiftOutput::disable() {
digitalWrite(this->enablePin, HIGH);
}
void ShiftOutput::output(uint8_t data, bool clockOutput) {
shiftOut(this->dataPin, this->clkPin, LSBFIRST, data);
if (clockOutput) {
this->clockOutput();
}
}
void ShiftOutput::output16(uint16_t data, bool clockOutput) {
shiftOut(this->dataPin, this->clkPin, LSBFIRST, data & 0xFF);
shiftOut(this->dataPin, this->clkPin, LSBFIRST, (data >> 8));
if (clockOutput) {
this->clockOutput();
}
}
void ShiftOutput::clockOutput() {
digitalWrite(this->rClkPin, HIGH);
digitalWrite(this->rClkPin, LOW);
}

42
arduino/ShiftOutput.h Normal file
View File

@@ -0,0 +1,42 @@
/*
Copyright 2018 Sam Stevens
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#ifndef UVM_SHIFTOUTPUT_H
#define UVM_SHIFTOUTPUT_H
#include <stdint.h>
class ShiftOutput {
uint8_t enablePin;
uint8_t clkPin;
uint8_t rClkPin;
uint8_t dataPin;
public:
ShiftOutput(uint8_t enablePin, uint8_t clkPin, uint8_t rClkPin, uint8_t dataPin);
void enable();
void disable();
inline void output(uint8_t data) {
output(data, false);
}
inline void output16(uint16_t data) {
output16(data, false);
}
void output(uint8_t data, bool rclk);
void output16(uint16_t data, bool rclk);
void clockOutput();
};
#endif //UVM_SHIFTOUTPUT_H

View File

@@ -31,6 +31,7 @@ void vm_reset(VM *vm) {
memset(vm->R, 0, sizeof(uint8_t) * VM_REG_SIZE);
vm->PC = 0;
vm->carry = 0;
vm->run = false;
vm->halted = false;
}
@@ -116,6 +117,7 @@ void vm_step(VM *vm) {
vm->error(VM_ERR_MISALIGN);
}
vm->halted = true;
vm->run = false;
return;
}
uint16_t raw = (vm->readAddr(PC, true) << 8) + vm->readAddr(PC + 1, true);
@@ -123,6 +125,7 @@ void vm_step(VM *vm) {
inst.op = (uint8_t) (raw >> 12);
if (vm->halted) {
vm->run = false;
return;
}
@@ -219,22 +222,25 @@ void vm_step(VM *vm) {
break;
case OP_JMP:
vm_decode_Q(&inst, raw);
vm->PC = vm_get_rx(vm, inst.rd);
rd = vm_get_rx(vm, inst.rd);
vm->PC = rd;
break;
case OP_JEQ:
vm_decode_S(&inst, raw);
rx = vm_get_r(vm, inst.rx);
ry = vm_get_r(vm, inst.ry);
rd = vm_get_rx(vm, inst.rd);
if (rx == ry) {
vm->PC = vm_get_rx(vm, inst.rd);
vm->PC = rd;
}
break;
case OP_JLT:
vm_decode_S(&inst, raw);
rx = vm_get_r(vm, inst.rx);
ry = vm_get_r(vm, inst.ry);
rd = vm_get_rx(vm, inst.rd);
if (rx < ry) {
vm->PC = vm_get_rx(vm, inst.rd);
vm->PC = rd;
}
break;
case OP_HLT:
@@ -248,4 +254,8 @@ void vm_step(VM *vm) {
break;
}
vm_put_r(vm, inst.rd, rd);
if (vm->halted) {
vm->run = false;
}
}

View File

@@ -61,6 +61,7 @@ struct VM_t {
uint8_t R[VM_REG_SIZE];
uint16_t PC;
uint8_t carry;
bool run;
bool halted;
uint8_t (*readAddr)(uint16_t addr, bool instruction);
void (*writeAddr)(uint16_t addr, uint8_t data);

View File

@@ -16,22 +16,31 @@ limitations under the License.
/**
* Example Programs
* Hello World: 0x311833021210c0323401411412103416e4203406d400000048656c6c6f20576f726c640a
* Hello World: 311833021210c0323401411412103416e4203406d400000048656c6c6f20576f726c640a
*/
//Options
//#define TEST_DESTRUCTIVE
#include "VM.h"
#include "Console.h"
#include "Memory.h"
#include "ShiftInput.h"
#include "ShiftOutput.h"
#include "Interface.h"
#include "pins.h"
#include "util.h"
//Expecting a Microchip 23LCV512 connected over MOSI/MISO/MCLK
Memory mem(PIN_MEMORY_SEL);
MemoryCache ICache(64, mem);
MemoryCache DCache(32, mem);
VM vm;
Console console(&vm);
ShiftInput buttons(1, 14, 15, 0, 16);
//Expecting a Microchip 23LCV512 connected over MOSI/MISO/MCLK
Memory mem(10);
MemoryCache ICache(64, mem);
MemoryCache DCache(32, mem);
ShiftInput inputs(3, PIN_INP_LOAD, PIN_INP_CLK, 0, PIN_INP_SER);
ShiftOutput disp(PIN_DISP_EN, PIN_DISP_CLK, PIN_DISP_RCLK, PIN_DISP_OUT);
Interface io(&vm, &mem, &inputs, &disp, PIN_SW_REG);
void setup() {
//Setup VM
@@ -41,15 +50,48 @@ void setup() {
vm.readAddr = vm_read_addr;
vm.writeAddr = vm_write_addr;
//Display
for(uint8_t i = 0; i < 16; i++) {
disp.output((uint8_t)0, true);
}
disp.clockOutput();
disp.enable();
//Interface
io.init();
//Disable input inhibit lines (Layout issue on Rev.A board)
pinMode(PIN_INP_ADDR_INH, OUTPUT);
pinMode(PIN_INP_SW_INH, OUTPUT);
digitalWrite(PIN_INP_ADDR_INH, LOW);
digitalWrite(PIN_INP_SW_INH, LOW);
//Start serial
Serial.begin(9600);
console.setSerial(&Serial);
//Speed control
pinMode(PIN_SPEED, INPUT);
//Init memory
SPI.begin();
mem.setSize(VM_MEM_SIZE);
if (!mem.init()) {
Serial.println("Memory failed to init!");
Serial.print("Tried to set MODE_SEQ. Current mode is ");
switch(mem.readMode()) {
case MODE_BYTE:
Serial.println("MODE_BYTE");
break;
case MODE_PAGE:
Serial.println("MODE_PAGE");
break;
case MODE_SEQ:
Serial.println("MODE_SEQ");
break;
default:
Serial.println(mem.readMode());
break;
}
} else {
#ifdef TEST_DESTRUCTIVE
Serial.print("Testing ");
@@ -68,19 +110,25 @@ void setup() {
}
}
void loop() {
console.loop();
unsigned long int nextRun = 0;
if (buttons.updateInput()) {
uint8_t *input = buttons.getInput();
for(uint8_t i = 0; i < buttons.getChipCount(); i++) {
Serial.print("Button Group ");
Serial.print(i);
Serial.print(" = ");
Serial.print(input[i], BIN);
Serial.println();
void loop() {
if (vm.run) {
if (nextRun == 0 || nextRun < millis()) {
vm_step(&vm);
int delayTime = analogRead(PIN_SPEED);
if (delayTime < 10) {
nextRun = 0;
} else {
nextRun = millis() + delayTime;
}
}
} else {
nextRun = 0;
}
console.loop();
io.loop();
}
void vm_print_error(uint8_t err) {
@@ -140,22 +188,3 @@ void vm_write_addr(uint16_t addr, uint8_t data) {
DCache.update(addr, data);
}
void print_cache_state(MemoryCache& cache) {
for(uint8_t i = 0; i < cache.getSize(); i++) {
MemoryCacheItem* item = cache.getItem(i);
Serial.print(i);
Serial.print(": ");
if (item->valid) {
Serial.print(item->addr, HEX);
Serial.print("=");
Serial.print(item->data, HEX);
Serial.print(" TTL ");
Serial.print(item->ttl);
Serial.println("");
} else {
Serial.println("Nil");
}
}
}

41
arduino/pins.h Normal file
View File

@@ -0,0 +1,41 @@
/*
Copyright 2018 Sam Stevens
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#ifndef UVM_PINS_H
#define UVM_PINS_H
//Display / Shift register output
#define PIN_DISP_EN 8
#define PIN_DISP_CLK 16
#define PIN_DISP_RCLK 17
#define PIN_DISP_OUT 15
//Inputs
#define PIN_SPEED 14
#define PIN_SW_REG 7
#define PIN_INP_SER 2
#define PIN_INP_CLK 3
#define PIN_INP_ADDR_INH 4
#define PIN_INP_SW_INH 5
#define PIN_INP_LOAD 6
//I/O
#define PIN_IO_INT 9
//Memory
#define PIN_MEMORY_SEL 10
#endif

24
arduino/util.c Normal file
View File

@@ -0,0 +1,24 @@
/*
Copyright 2018 Sam Stevens
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#include "util.h"
uint8_t reverse8(register uint8_t b) {
b = (b & 0xF0) >> 4 | (b & 0x0F) << 4;
b = (b & 0xCC) >> 2 | (b & 0x33) << 2;
b = (b & 0xAA) >> 1 | (b & 0x55) << 1;
return b;
}

32
arduino/util.h Normal file
View File

@@ -0,0 +1,32 @@
/*
Copyright 2018 Sam Stevens
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#ifndef UVM_UTIL_H
#define UVM_UTIL_H
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
uint8_t reverse8(uint8_t b);
#ifdef __cplusplus
}
#endif
#endif