lots of stuff i should back up now

This commit is contained in:
Triss 2021-11-02 23:06:01 +01:00
parent d4e34bb742
commit a15ba940f2
21 changed files with 1162 additions and 16 deletions

View File

@ -31,14 +31,21 @@ if(FAMILY STREQUAL "rp2040")
# Example source # Example source
target_sources(${PROJECT} PUBLIC target_sources(${PROJECT} PUBLIC
${CMAKE_CURRENT_SOURCE_DIR}/src/main.c ${CMAKE_CURRENT_SOURCE_DIR}/src/main.c
${CMAKE_CURRENT_SOURCE_DIR}/src/pio_sbw.c ${CMAKE_CURRENT_SOURCE_DIR}/src/msp430/pio_sbw.c
${CMAKE_CURRENT_SOURCE_DIR}/src/tap.c ${CMAKE_CURRENT_SOURCE_DIR}/src/msp430/tap.c
${CMAKE_CURRENT_SOURCE_DIR}/src/msp430dbg.c ${CMAKE_CURRENT_SOURCE_DIR}/src/msp430/msp430dbg.c
${CMAKE_CURRENT_SOURCE_DIR}/src/swim/swim_hw.c
${CMAKE_CURRENT_SOURCE_DIR}/src/tool78/tool78_hw_helpers.c
${CMAKE_CURRENT_SOURCE_DIR}/src/tool78/tool78_hw_test_uart2.c
${CMAKE_CURRENT_SOURCE_DIR}/src/test/piotest.c
) )
# Example include # Example include
target_include_directories(${PROJECT} PUBLIC target_include_directories(${PROJECT} PUBLIC
${CMAKE_CURRENT_SOURCE_DIR}/src/ ${CMAKE_CURRENT_SOURCE_DIR}/src/
${CMAKE_CURRENT_SOURCE_DIR}/src/msp430/
${CMAKE_CURRENT_SOURCE_DIR}/src/swim/
${CMAKE_CURRENT_SOURCE_DIR}/src/tool78/
) )
# Example defines # Example defines
@ -48,7 +55,10 @@ if(FAMILY STREQUAL "rp2040")
target_link_libraries(${PROJECT} pico_stdlib pico_unique_id target_link_libraries(${PROJECT} pico_stdlib pico_unique_id
hardware_pio hardware_dma hardware_pwm) hardware_pio hardware_dma hardware_pwm)
pico_generate_pio_header(${PROJECT} ${CMAKE_CURRENT_SOURCE_DIR}/src/sbw.pio) pico_generate_pio_header(${PROJECT} ${CMAKE_CURRENT_SOURCE_DIR}/src/msp430/sbw.pio)
pico_generate_pio_header(${PROJECT} ${CMAKE_CURRENT_SOURCE_DIR}/src/swim/swim.pio)
pico_generate_pio_header(${PROJECT} ${CMAKE_CURRENT_SOURCE_DIR}/src/tool78/tool78.pio)
pico_generate_pio_header(${PROJECT} ${CMAKE_CURRENT_SOURCE_DIR}/src/test/test.pio)
pico_add_extra_outputs(${PROJECT}) pico_add_extra_outputs(${PROJECT})
else() else()

View File

@ -8,8 +8,11 @@
#include "pio_sbw.h" #include "pio_sbw.h"
#include "tap.h" #include "tap.h"
#include "msp430dbg.h" #include "msp430dbg.h"
#include "tool78_hw.h"
static uint16_t DATA_text[0x24] = { void piotest(void);
/*static uint16_t DATA_text[0x24] = {
0xc232,0x43c2,0x0000,0x4031,0x02fe,0x40f2,0x00ff,0x002a,0x40b2,0x5a10,0x0120, 0xc232,0x43c2,0x0000,0x4031,0x02fe,0x40f2,0x00ff,0x002a,0x40b2,0x5a10,0x0120,
0x43d2,0x0000,0xd232,0xd032,0x0018,0x3ffd,0xc3d2,0x0002,0xd3d2,0x0000,0xe3d2, 0x43d2,0x0000,0xd232,0xd032,0x0018,0x3ffd,0xc3d2,0x0002,0xd3d2,0x0000,0xe3d2,
0x0029,0x4130,0x1300,0x1300,0x1300,0x1300,0x1300,0x1300,0x12b0,0xf822,0x1300, 0x0029,0x4130,0x1300,0x1300,0x1300,0x1300,0x1300,0x1300,0x12b0,0xf822,0x1300,
@ -22,21 +25,19 @@ static uint16_t DATA_vectors[0x10] = {
// 2k/8k flash, 256b RAM // 2k/8k flash, 256b RAM
static uint16_t dumpmem_ram[256>>1]; static uint16_t dumpmem_ram[256>>1];
static uint16_t dumpmem_flash[8192>>1]; static uint16_t dumpmem_flash[8192>>1];*/
int main() { static void test_sbw(void) {
gpio_init(PINOUT_SBW_TCK); gpio_init(PINOUT_SBW_TCK);
gpio_set_function(PINOUT_SBW_TCK, GPIO_FUNC_SIO); gpio_set_function(PINOUT_SBW_TCK, GPIO_FUNC_SIO);
gpio_set_dir(PINOUT_SBW_TCK, true); gpio_set_dir(PINOUT_SBW_TCK, true);
gpio_put(PINOUT_SBW_TCK, true); gpio_put(PINOUT_SBW_TCK, true);
stdio_init_all(); sbw_preinit();
/*sbw_preinit();
printf("%s\n", "preinited"); printf("%s\n", "preinited");
bool s = sbw_init(); bool s = sbw_init();
printf("%s\n", s ? "inited" : "failure");*/ printf("%s\n", s ? "inited" : "failure");
/*uint8_t tdi = 0x0f, tdo = 0; /*uint8_t tdi = 0x0f, tdo = 0;
sbw_sequence(8, true, &tdi, &tdo); sbw_sequence(8, true, &tdi, &tdo);
@ -60,9 +61,9 @@ int main() {
printf("done.\n");*/ printf("done.\n");*/
/*sbw_tap_reset(); /*sbw_tap_reset();
sbw_check_fuse(); sbw_check_fuse();*/
uint8_t id = sbw_tap_shift_ir(msp430_ir_bypass); /*uint8_t id = sbw_tap_shift_ir(msp430_ir_bypass);
printf("JTAG ID=%02x\n", id); printf("JTAG ID=%02x\n", id);
sbw_tap_shift_ir(msp430_ir_ctrl_sig_16bit); sbw_tap_shift_ir(msp430_ir_ctrl_sig_16bit);
@ -150,6 +151,33 @@ int main() {
msp430_memory_write8(0x0029, 0x01); // P2OUT=0x01 (P2.0 hi)*/ msp430_memory_write8(0x0029, 0x01); // P2OUT=0x01 (P2.0 hi)*/
msp430_device_release(0xfffe/*0xf800*/); msp430_device_release(0xfffe/*0xf800*/);
}
return 0;
static uint8_t buf[32];
static void tool78_testtest() {
struct tool78_hw* thw = &tool78_hw_test_uart2;
printf("initing...\n");
bool r = thw->init();
printf("init: %s\n", r ? "ok" : "nope");
size_t rrr = thw->send(7, (const uint8_t*)"hello\r\n", 0);
printf("sent %zu\n", rrr);
while (true) {
size_t n = thw->recv(31, buf, 0);
buf[n] = 0;
if (n) {
printf("got %zu: '%s'\n", n, (const char*)buf);
thw->send(n, buf, 0);
}
}
}
int main() {
stdio_init_all();
tool78_testtest();
//piotest();
return 0;
} }

160
src/swim/swim.pio Normal file
View File

@ -0,0 +1,160 @@
.program swim_tx
.side_set 1 pindirs
; Pin assignments:
; - SWIM is out/set/side pin 0
; NOTE: pin needs pullup, either input(+pullup) or output+drivezero => use set pindirs AND sideset is direction!
;
; Autopush and autopull must be enabled, set to 8
start:
pull side 0
out x, 32 side 0
; TODO: can we somehow sleep for a variable amount of cycles in an easier
; way?
iter:
out y, 1 side 0 ; get next bit
jmp !y, bit_0 side 0
bit_1:
nop side 1 [2]
PUBLIC bit_1_delay_long:
nop side 0 [10] ; or 4
nop side 0 [10] ; or 4
jmp iter_next side 0
bit_0:
PUBLIC bit_0_delay_long:
nop side 1 [10] ; or 4
nop side 1 [10] ; or 4
nop side 0 [2]
iter_next:
jmp x--, iter side 0
;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
.program swim_rx
; Pin assignments:
; - SWIM is in pin 0
; NOTE: pin needs pullup, either input(+pullup) or output+drivezero
;
; Autopush and autopull must be enabled, set to 8
start:
pull
out x, 32
iter:
; wait for pin to go low (device tx), and wait until the middle of the
; interval (5 or 11 cyc). note that the WAIT insn has a one cycle delay
; (and sometimes up to two), so we subtract a cycle here
; WAIT <polarity> PIN <in-pinidx>
PUBLIC wait_delay:
wait 0 pin 0 [10] ; or 4
; now sample the line in the middle (UM0470 recommends this)
in pins, 1
wait 1 pin 0 ; wait until pin goes high again (to not auto-fallthru to
jmp x--, iter ; multiple iterations per low phase)
push
;;;; 19 instructions total
% c-sdk {
// SWIM defaults to low-speed mode
static inline void swim_tx_pio_init(PIO pio, uint sm, uint prog_offs,
float swim_clock_freq, uint pin_swim) {
pio_sm_set_enabled(pio, sm, false);
pio_sm_config c = swim_tx_program_get_default_config(prog_offs);
sm_config_set_out_pins(&c, pin_swim, 1);
sm_config_set_set_pins(&c, pin_swim, 1);
sm_config_set_sideset_pins(&c, pin_swim);
sm_config_set_out_shift(&c, false, true, 8);
sm_config_set_clkdiv(&c, (float)clock_get_hz(clk_sys) / swim_clock_freq);
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
pio_sm_init(pio, sm, prog_offs, &c);
// initially set to input (i.e. pullup) as default bus state
pio_sm_set_pindirs_with_mask(pio, sm, 0, (1u << pin_swim));
// output should drive zero, sideset sets direction to select between
// drive-zero and pullup
pio_sm_exec(pio, sm, pio_encode_set(pio_pins, 0) | pio_encode_sideset(1, 0));
// SWIM is asynchronous!
hw_clear_bits(&pio->input_sync_bypass, 1u << pin_swim);
gpio_set_pulls(pin_swim, true, false); // SWIM is pullup if input
pio_sm_set_enabled(pio, sm, true);
// set padsbank func to PIO *after* initing PIO, otherwise a glitch occurs
pio_gpio_init(pio, pin_swim);
}
static inline void swim_tx_set_speed(PIO pio, uint sm, uint prog_offs,
bool en, float swim_clock_freq, bool fast) {
pio_sm_set_enabled(pio, sm, false);
pio_sm_set_clkdiv(pio, sm, (float)clock_get_hz(clk_sys) / swim_clock_freq);
pio->instr_mem[prog_offs + swim_tx_offset_bit_1_delay_long + 0] = pio_encode_nop()
| pio_encode_sideset(1, 0) | pio_encode_delay(fast ? 4 : 10);
pio->instr_mem[prog_offs + swim_tx_offset_bit_1_delay_long + 1] = pio_encode_nop()
| pio_encode_sideset(1, 0) | pio_encode_delay(fast ? 4 : 10);
pio->instr_mem[prog_offs + swim_tx_offset_bit_0_delay_long + 0] = pio_encode_nop()
| pio_encode_sideset(1, 1) | pio_encode_delay(fast ? 4 : 10);
pio->instr_mem[prog_offs + swim_tx_offset_bit_0_delay_long + 1] = pio_encode_nop()
| pio_encode_sideset(1, 1) | pio_encode_delay(fast ? 4 : 10);
pio_sm_set_enabled(pio, sm, en);
}
// SWIM defaults to low-speed mode
static inline void swim_rx_pio_init(PIO pio, uint sm, uint prog_offs,
float swim_clock_freq, uint pin_swim) {
pio_sm_set_enabled(pio, sm, false);
pio_sm_config c = swim_rx_program_get_default_config(prog_offs);
sm_config_set_in_pins(&c, pin_swim);
sm_config_set_clkdiv(&c, (float)clock_get_hz(clk_sys) / swim_clock_freq);
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX);
pio_sm_init(pio, sm, prog_offs, &c);
// SWIM pin is pure input
pio_sm_set_pindirs_with_mask(pio, sm, 0, (1u << pin_swim));
// SWIM is asynchronous!
hw_clear_bits(&pio->input_sync_bypass, 1u << pin_swim);
pio_sm_set_enabled(pio, sm, true);
pio_gpio_init(pio, pin_swim);
}
static inline void swim_rx_set_speed(PIO pio, uint sm, uint prog_offs,
bool en, float swim_clock_freq, bool fast) {
pio_sm_set_enabled(pio, sm, false);
pio_sm_set_clkdiv(pio, sm, (float)clock_get_hz(clk_sys) / swim_clock_freq);
pio->instr_mem[prog_offs + swim_rx_offset_wait_delay]
= pio_encode_wait_pin(false, 0) | pio_encode_delay(fast ? 4 : 10);
pio_sm_set_enabled(pio, sm, en);
}
%}

156
src/swim/swim_hw.c Normal file
View File

@ -0,0 +1,156 @@
#include <hardware/clocks.h>
#include <hardware/gpio.h>
#include <hardware/pio.h>
#include <hardware/timer.h>
#include "swim_hw.h"
#include "swim.pio.h"
#define PINOUT_SWIM_PIO pio0
#define PINOUT_SWIM 22
int swim_tx_sm = -1, swim_rx_sm = -1, swim_tx_off = -1, swim_rx_off = -1;
void swim_preinit(void) {
// TODO:
// * init GPIO (pulls, dir, out, function)
// * do entry sequence (~8 phases?)
}
bool swim_init(void) {
// TODO:
// for each rx, tx:
// * allocate PIO program space
// * allocate PIO SMs
// * init PIO SM program & stuff
return false;
}
void swim_deinit(void) {
// TODO:
// * disable PIO SMs
// * deallocate PIO SMs
// * deallocate PIO program space
}
void swim_set_speed(float swim_clock_freq, bool fast) {
swim_tx_set_speed(PINOUT_SWIM_PIO, swim_tx_sm, swim_tx_off, true,
swim_clock_freq, fast);
swim_tx_set_speed(PINOUT_SWIM_PIO, swim_rx_sm, swim_rx_off, true,
swim_clock_freq, fast);
}
// SWIM only sends up to 10 bits at once before changing direction (for an ack)
void swim_tx_bits(uint32_t nbits, uint16_t bits) {
// TODO:
// * init PIO SM stuff
// * send length
// * send data
// * wait for tx fifo empty
// * wait until finished? (use IRQ?? prolly best sync mechanism)
}
uint16_t swim_rx_bits(uint32_t nbits) {
uint16_t r = 0;
// TODO:
// * init PIO SM stuff
// * send length
// * read data (incl. wait until finished)
return r;
}
static uint8_t bitswap(uint8_t in) {
static const uint8_t lut[16] = {
0x0, 0x8, 0x4, 0xc, 0x2, 0xa, 0x6, 0xe,
0x1, 0x9, 0x5, 0xd, 0x3, 0xb, 0x7, 0xf
};
return (lut[in&0xf] << 4) | lut[in>>4];
}
bool swim_tx_command(uint8_t cmd, size_t datasize, const uint8_t* data) {
// cmd is 0 bit, 3 data bits, parity bit, responded by an ack bit
uint16_t r = 0, v = (0<<15) | ((cmd&1)<<14) | ((cmd&2)<<12) | ((cmd&4)<<10);
// add parity bit
v |= (((cmd>>0)^(cmd>>1)^(cmd>>2)) & 1) << 11;
for (size_t i = 0; i < 10; ++i) {
swim_tx_bits(5, v);
r = swim_rx_bits(1); // ack bit
if (r) break;
}
if (!r) {
// oops, no ack!
return false;
}
// start sending data bits
for (size_t i = 0; i < datasize; ++i) {
// calculate parity
for (size_t j = 0; j < 8; ++j) v ^= data[i] >> j;
v = (v & 1) << 6;
// and value bits
v |= (0 << 15) | ((uint16_t)bitswap(data[i]) << 7);
for (size_t j = 0; j < 10; ++j) {
swim_tx_bits(10, v);
r = swim_rx_bits(1); // ack bit
if (r) break;
}
if (!r) {
// oops, no ack!
return false;
}
}
return true;
}
bool swim_rx_data(size_t datasize, uint8_t* data) {
uint16_t v = 0, r = 0;
for (size_t i = 0; i < datasize; ++i) {
for (size_t j = 0; j < 10; ++j) {
v = swim_rx_bits(10);
if (!(v & 0x8000)) { // should be a device->host cmd
swim_tx_bits(1, 0); // send NAK
continue;
}
// calculate parity
r = 0;
for (size_t k = 7; k < 15; ++k) r ^= v >> k;
if (((v >> 6) & 1) != (r & 1)) {
// parity mismatch!
r = 0;
swim_tx_bits(1, 0); // send NAK
continue;
}
// send ACK
swim_tx_bits(1, 0x8000);
data[i] = bitswap(v >> 7);
r = 1;
break;
}
if (!r) {
// oops, something went wrong
return false;
}
}
return true;
}

28
src/swim/swim_hw.h Normal file
View File

@ -0,0 +1,28 @@
#ifndef SWIM_HW_H_
#define SWIM_HW_H_
#include <stdint.h>
#include <stdbool.h>
// perform entry sequence
void swim_preinit(void);
bool swim_init(void);
void swim_deinit(void);
// 'swim_clock_freq' is the frequency of the underlying SWIM clock,
// *NOT* the baudrate! in the STM8 device being debugged, this is usually
// HSI/2 = 8 MHz
void swim_set_speed(float swim_clock_freq, bool fast);
// SWIM only sends up to 10 bits at once before changing direction (for an ack)
// bits are transferred most-significant-bit first (for both functions here)
void swim_tx_bits(uint32_t nbits, uint16_t bits);
uint16_t swim_rx_bits(uint32_t nbits);
bool swim_tx_command(uint8_t cmd, size_t datasize, const uint8_t* data);
bool swim_rx_data(size_t datasize, uint8_t* data);
#endif

45
src/test/piotest.c Normal file
View File

@ -0,0 +1,45 @@
#include <hardware/gpio.h>
#include <hardware/pio.h>
#include <hardware/timer.h>
#include "test.pio.h"
#define PIN_T2_OUT 2
#define PIN_T1_IN 3
#define PIN_T1_OUT 4
#define PIN_T1_SIDE 5
static volatile uint delay;
void piotest(void) {
uint off1 = pio_add_program(pio0, &test1_program),
off2 = pio_add_program(pio0, &test2_program);
float freq = 1/*0.05f*/ * 1000 * 1000;
uint sm1 = 0, sm2 = 1;
uint smmask = (1u << sm1) | (1u << sm2);
test1_program_init(pio0, sm1, off1, PIN_T1_IN, PIN_T1_OUT, PIN_T1_SIDE, freq, false);
test2_program_init(pio0, sm2, off2, PIN_T2_OUT, freq, false);
delay = (uint)((0.85/*phase percentage*/ * 1000*1000/*microseconds*/) / freq);
asm volatile("":::"memory"); // make sure delay is computed *before* enabling both SMs
// reset and enable both at once
pio_restart_sm_mask(pio0, smmask);
pio_clkdiv_restart_sm_mask(pio0, smmask);
//pio_sm_clkdiv_restart(pio0, sm2);
///*busy_wait_us_32(0);*/busy_wait_us_32(delay);
//pio_sm_clkdiv_restart(pio0, sm1);
/*pio_sm_set_enabled(pio0, sm1, true);
pio_sm_set_enabled(pio0, sm2, true);*/
pio_set_sm_mask_enabled(pio0, smmask, true);
while(1);
}

70
src/test/test.pio Normal file
View File

@ -0,0 +1,70 @@
.program test1
.side_set 1
_start:
wait 1 pin 0 side 1 ; input pin
set pins, 1 side 0 ; set pin
set pins, 0 side 0
set pins, 1 side 0
set pins, 0 side 0
set pins, 1 side 0
set pins, 0 side 0
set pins, 1 side 0
set pins, 0 side 0
set pins, 1 side 0 [15] ; set pin
set pins, 0 side 0 [15]
.program test2
_start:
nop [31]
set pins, 1 [16] ; set pin
set pins, 0 [16] ; set pin
% c-sdk {
#include <hardware/clocks.h>
static inline void test1_program_init(PIO pio, uint sm, uint offset, uint pinin,
uint pinout, uint pinside, float freq, bool en) {
pio_gpio_init(pio, pinin );
pio_gpio_init(pio, pinout);
pio_gpio_init(pio, pinside);
pio_sm_set_consecutive_pindirs(pio, sm, pinin , 1, false);
pio_sm_set_consecutive_pindirs(pio, sm, pinout, 1, true );
pio_sm_set_consecutive_pindirs(pio, sm, pinside, 1, true );
pio_sm_config c = test1_program_get_default_config(offset);
sm_config_set_in_pins(&c, pinin);
sm_config_set_out_pins(&c, pinout, 1);
sm_config_set_set_pins(&c, pinout, 1);
sm_config_set_sideset_pins(&c, pinside);
float div = clock_get_hz(clk_sys) / freq;
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio->input_sync_bypass = (1u<<pinin);
pio_sm_set_enabled(pio, sm, en);
}
static inline void test2_program_init(PIO pio, uint sm, uint offset, uint pinout,
float freq, bool en) {
pio_gpio_init(pio, pinout);
pio_sm_set_consecutive_pindirs(pio, sm, pinout, 1, true);
pio_sm_config c = test2_program_get_default_config(offset);
sm_config_set_out_pins(&c, pinout, 1);
sm_config_set_set_pins(&c, pinout, 1);
float div = clock_get_hz(clk_sys) / freq;
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, en);
}
%}

174
src/tool78/tool78.pio Normal file
View File

@ -0,0 +1,174 @@
; 5+10+3 insns = 18 insns
; technially there are 5 or 6 physical layer protocols across 3 device
; generations, but data transfers (not entry sequences & pinout) can be grouped
; in 3 categories: SPI (78k0/Kx2), two-wire UART (78k/Kx2 and RL78), and
; single-wire UART (78K0R/Kx3-L and RL78). UART has a small peculiarity: MCU to
; host transfers use 8n1 formatting, while host to MCU transfers are 8n2.
;
; furthermore, we can unify the single-wire and two-wire UARTs by doing the
; following:
; * TX, RX lines pullup
; * TX: set pin drive value to 0, but change pin direction for writing
; * RX: the usual
.program tool78_uart_tx
.side_set 1 opt pindirs
; 8n2
; no autopull
; uses both out pin and sideset pin
; bit period = 1/8 PIO cycle period
; here we use side=1 to drive a pin high, and side=0 to drive it low,
; as well as using out to set the line.
; however, these are direction values and not output values, 1 would be
; "output" and 0 is "input"/"default to pullup/pulldown". output is fixed
; to a low level, so the code below would invert things... to fix this, we
; invert the output enable setting in the IO multiplexer padsbank stuff
nop side 1 [7] ; first stop bit
pull side 1 [7] ; second stop bit, only continue when data is there
set x, 7 side 0 [7] ; start bit
loop:
out pindirs, 1 ; output a single bit
jmp x-- loop [6]
% c-sdk {
#include <hardware/clocks.h>
static inline void tool78_uart_tx_program_init(PIO pio, uint sm, uint offset,
uint pin, uint baudrate, bool en) {
// needs to work on a one-wire half-duplex line:
// * use internal pullup
// * drive output low, always
// * use pin direction setting to send data
// * default to hiZ/pullup after initc
pio_sm_set_pins_with_mask(pio, sm, 0u << pin, 1u << pin);
pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, false); // pin is input by default (i.e. pullup)
pio_gpio_init(pio, pin);
gpio_pull_up(pin);
gpio_set_oeover(pin, GPIO_OVERRIDE_INVERT); // see note in PIO code
pio_sm_config c = tool78_uart_tx_program_get_default_config(offset);
// no autopull, shifting out MSb first
sm_config_set_out_shift(&c, false, false, 8);
// only need an output FIFO
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
sm_config_set_out_pins(&c, pin, 1);
sm_config_set_sideset_pins(&c, pin);
float div = (float)clock_get_hz(clk_sys) / (8*baudrate);
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, en);
}
%}
.program tool78_uart_rx
; 8n1
; no autopush
; uses in and jmp pin for rx
; bit period = 1/8 PIO cycle period
start:
wait 0 pin 0 ; wait for start bit
set x, 7 [10] ; 8 data bits. delay until middle of data bit period
loop:
in pins, 1 ; read the bit
jmp x-- loop [ 6]
jmp pin stop_ok ; if pin high (stop bit): all is ok
irq 4 rel ; set sticky flag due to missing stop bit
mov isr, null ; clear shift reg as the data is nonsense
wait 1 pin 0 ; wait until line goes idle/high again
jmp start ; restart
stop_ok:
push
% c-sdk {
static inline void tool78_uart_rx_program_init(PIO pio, uint sm, uint offset,
uint pin, uint baudrate, bool en) {
pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, false); // pin is input now
pio_gpio_init(pio, pin);
gpio_pull_up(pin);
pio_sm_config c = tool78_uart_rx_program_get_default_config(offset);
sm_config_set_in_pins(&c, pin);
sm_config_set_jmp_pin(&c, pin);
// no autopull, MSb first
sm_config_set_in_shift(&c, false, false, 8);
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX);
float div = (float)clock_get_hz(clk_sys) / (8*baudrate);
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, en);
}
// TODO: IRQ handling!
%}
.program tool78_spi
.side_set 1
; nSCK: side-set pin
; MOSI: out pin
; MISO: in pin
; CPHA1: set on falling edge, read on rising edge. clk high when idle
; CPOL1: can do this in IO muxing controls: GPIOx_CTRL.OUTOVER = 1
; => gpio_set_outover(pin, GPIO_OVERRIDE_INVERT)
; this means we have to write out code such that it reads/samples on the
; "falling" edge, i.e. code it as if we're doing CPHA1 CPOL0
out x, 1 side 0
mov pins, x side 1 [1]
in pins, 1 side 0
% c-sdk {
static inline void tool78_spi_program_init(PIO pio, uint sm, uint offset,
uint pin_nsck, uint pin_mosi, uint pin_miso, uint freq, bool en) {
// clock deafults to high, let's not care about the rest yet
pio_sm_set_pins_with_mask(pio, sm, 0u << pin_nsck, 1u << pin_nsck);
gpio_set_outover(pin_nsck, GPIO_OVERRIDE_INVERT); // see note in PIO code
// SPI is clocked & synchronous, so we can bypass this
hw_set_bits(&pio->input_sync_bypass, 1u << pin_miso);
pio_gpio_init(pio, pin_nsck);
pio_gpio_init(pio, pin_mosi);
pio_gpio_init(pio, pin_miso);
pio_sm_config c = tool78_spi_program_get_default_config(offset);
sm_config_set_out_pins(&c, pin_mosi, 1);
sm_config_set_in_pins (&c, pin_miso);
sm_config_set_sideset_pins(&c, pin_nsck);
// MSb first, 8 bit, autopush & autopull
sm_config_set_out_shift(&c, false, true, 8);
sm_config_set_in_shift (&c, false, true, 8);
float div = (float)clock_get_hz(clk_sys) / freq;
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, en);
}
%}

3
src/tool78/tool78_cmds.h Normal file
View File

@ -0,0 +1,3 @@
// big TODO (implement separate commands & handle MCU differences)

159
src/tool78/tool78_defs.h Normal file
View File

@ -0,0 +1,159 @@
#ifndef TOOL78_DEFS_H_
#define TOOL78_DEFS_H_
#include <stddef.h>
#include <stdint.h>
#define PINOUT_TOOL78_PIO pio1
#define PINOUT_TOOL78_nRESET 16
#define PINOUT_TOOL78_78K0_FLMD0 17
#define PINOUT_TOOL78_78K0_TXMOSI 18
#define PINOUT_TOOL78_78K0_RXMISO 19
#define PINOUT_TOOL78_78K0_CLOCK 20
#define PINOUT_TOOL78_78K0R_FLMD0 17
#define PINOUT_TOOL78_78K0R_TOOL0 18
#define PINOUT_TOOL78_RL78_TOOL0 17
#define PINOUT_TOOL78_RL78_TX 18
#define PINOUT_TOOL78_RL78_RX 19
enum tool78_target {
tool78k0_kx2_uart2 = 0x12,
tool78k0_kx2_spi = 0x13,
tool78k0_kx2_uart2_extclk = 0x14,
tool78k0r_kx3l_uart1 = 0x21,
tool78rl_uart1 = 0x31,
tool78rl_uart2 = 0x32,
tool78rl_ocd = 0x38, // FIXME: do this in a better way
tool78_mcu_mask = 0xf0,
tool78_mcu_78k0_kx2 = 0x10,
tool78_mcu_78k0r_kx3l = 0x20,
tool78_mcu_rl78 = 0x30,
tool78_phy_mask = 0x0f,
tool78_phy_uart1 = 0x01,
tool78_phy_uart2 = 0x02,
tool78_phy_spi = 0x03,
tool78_phy_uart2_extclk = 0x04,
tool78_phy_rlocd = 0x08, // FIXME: do this in a better way
};
enum tool78_entry {
// FLMD0 pulse numbers
tool78_entry_78k0_uart2 = 0,
tool78_entry_78k0_uart2_extclk = 3,
tool78_entry_78k0_spi = 8,
// FLMD0 pulse numbers
// TODO: or is it the byte sent over TOOL0?
tool78_entry_78k0r_uart1 = 0,
// TOOL0 initial byte values
tool78_entry_rl78_uart1 = 0x3a,
tool78_entry_rl78_uart2 = 0x00,
tool78_entry_rl78_ocd = 0xc5
};
// TODO: initial baudrates? 9600 for 78k, 115.2k for RL78
enum tool78_cmd {
// only used in UART comms (i.e. not in 78k0/Kx2 SPI)
tool78_cmd_reset = 0x00,
tool78_cmd_verify = 0x13,
// undocumented, RL78 only?
tool78_cmd_verify_internal = 0x19,
tool78_cmd_chip_erase = 0x20,
// not available on RL78
tool78_cmd_block_erase = 0x22,
tool78_cmd_block_blank_check = 0x32,
tool78_cmd_programming = 0x40,
// 78k0/Kx2 SPI only
tool78_cmd_status = 0x70,
// 78k0/Kx2 only
tool78_cmd_osc_freq_set = 0x90,
// not on 78k0/Kx2. arguments are different for 78K0R/Kx3-L and RL78!
tool78_cmd_baud_rate_set = 0x9a,
// 78K0R/Kx3-L and RL78: also sets flash shield window
tool78_cmd_security_set = 0xa0,
// RL78 only
tool78_cmd_security_get = 0xa1,
tool78_cmd_checksum = 0xb0,
// response format & length differ between all MCU versions!
// length & first few bytes can be used to discern between MCUs
// EXCEPT: osc freq set/baudrate set cmd required as first after reset??
tool78_cmd_silicon_signature = 0xc0,
// not on RL78. same response for 78k0/Kx2 and 78K0R/Kx3-L, so kinda useless
tool78_cmd_version_get = 0xc5,
};
enum tool78_stat {
tool78_stat_cmd_not_supported = 0x04,
tool78_stat_parameter_error = 0x05,
tool78_stat_ack = 0x06,
tool78_stat_checksum_error = 0x07,
tool78_stat_verify_error = 0x0f,
// can't do command due to protection settings
tool78_stat_protect_error = 0x10,
tool78_stat_nak = 0x15,
tool78_stat_mrg10_erase_verif_error = 0x1a,
tool78_stat_mrg11_internal_verif_error = 0x1b,
tool78_stat_write_error = 0x1c,
// 78k0/Kx2 only. security related?
tool78_stat_read_error = 0x20,
// 78k0/Kx2 SPI only
tool78_stat_busy = 0xff
};
// TODO: only known for RL78 from fail0overflow. verify!
// these commands use a checksum that is the bitwise complement from the usual
// checksum (used in the flash programming protocol)
enum tool78ocd_cmd {
tool78ocd_cmd_reset = 0x00,
tool78ocd_cmd_version = 0x90, // also called "ping"
// also called "unlock", as it *always* required a 10-byte passphrase (but
// not always checked, depending on protection status)
tool78ocd_cmd_connect = 0x91,
// read from memory?
tool78ocd_cmd_read = 0x92,
// write to memory (2 bytes addr, 1 byte len, data)
tool78ocd_cmd_write = 0x93,
// execute code at 0xf07e0 (TODO: verify addr across versions)
tool78ocd_cmd_exec = 0x94,
tool78ocd_cmd_exit_reti = 0x95, // TODO: what is this?
tool78ocd_cmd_exit_ram = 0x97, // TODO: what is this?
};
enum tool78_frame {
// first byte of command
tool78_frame_soh = 0x01,
tool78_frame_cmd = 0x01,
// first byte of data or response status
tool78_frame_stx = 0x02,
tool78_frame_dat = 0x02,
// end of command or final data/resp commandframe
tool78_frame_etx = 0x03,
tool78_frame_end = 0x03,
// end of data/resp for non-final commandframe
tool78_frame_etb = 0x17,
tool78_frame_eot = 0x17,
};
static inline uint8_t tool78_calc_checksum8(size_t len, const uint8_t* data) {
uint8_t r = 0;
for (size_t i = 0; i < len; ++i) r = r - data[i];
return r;
}
static inline uint8_t tool78_calc_ocd_checksum8(size_t len, const uint8_t* data) {
return ~tool78_calc_checksum8(len, data);
}
// TODO: 16bit checksum (cf. command B0 Checksum)
#endif

43
src/tool78/tool78_hw.h Normal file
View File

@ -0,0 +1,43 @@
#ifndef TOOL78_HW_H_
#define TOOL78_HW_H_
#include <stddef.h>
#include <stdint.h>
#include <stdbool.h>
#include "tool78_defs.h"
struct tool78_hw {
const enum tool78_target target;
// performs entry sequence + initial handshake (RESET or similar stuff, eg.
// UART needs extra null bytes in the beginning)
bool (*init)(void);
void (*deinit)(void);
// returns -1 if an rx overrun occurred
int (*has_available)(void);
// timeout:
// * infinitely blocking: < 0
// * not blocking at all: = 0
// retval: negative if an rx overrun occurred
int (*recv)(int len, uint8_t* data, int32_t timeout_ms);
int (*send)(int len, const uint8_t* data, int32_t timeout_ms);
};
extern struct tool78_hw
tool78_hw_test_uart2, // for testing DMA buffer logic & PIO stuff
tool78_hw_78k0_uart2,
tool78_hw_78k0_uart2_extclk,
tool78_hw_78k0_spi,
tool78_hw_78k0r_uart1,
tool78_hw_rl78_uart1,
tool78_hw_rl78_uart2;
#endif

View File

@ -0,0 +1,164 @@
#include <hardware/gpio.h>
#include <hardware/pio.h>
#include <pico/time.h>
#include <pico/timeout_helper.h>
#include "tool78_defs.h"
#include "tool78_hw.h"
#include "tool78_hw_helpers.h"
static uint8_t bitswap(uint8_t in) {
static const uint8_t lut[16] = {
0x0, 0x8, 0x4, 0xc, 0x2, 0xa, 0x6, 0xe,
0x1, 0x9, 0x5, 0xd, 0x3, 0xb, 0x7, 0xf
};
return (lut[in&0xf] << 4) | lut[in>>4];
}
bool tool78_hw_init_help(const pio_program_t* prgm_tx,
const pio_program_t* prgm_rx, struct tool78_pio_vars* vars) {
uint txoff = ~(uint)0, rxoff = ~(uint)0;
int smtx = -1, smrx = -1;
if (!prgm_tx && !prgm_rx) return false;
if (prgm_rx) {
if (!pio_can_add_program(PINOUT_TOOL78_PIO, prgm_rx))
goto error;
rxoff = pio_add_program(PINOUT_TOOL78_PIO, prgm_rx);
}
if (prgm_tx) {
if (!pio_can_add_program(PINOUT_TOOL78_PIO, prgm_tx))
goto error;
txoff = pio_add_program(PINOUT_TOOL78_PIO, prgm_tx);
}
if (prgm_tx) {
smtx = pio_claim_unused_sm(PINOUT_TOOL78_PIO, false);
if (smtx == -1) goto error;
}
if (prgm_rx) {
smrx = pio_claim_unused_sm(PINOUT_TOOL78_PIO, false);
if (smrx == -1) goto error;
}
vars->txoff = txoff;
vars->rxoff = rxoff;
vars->smtx = smtx;
vars->smrx = smrx;
return true; // all is well!
error:
if (!~txoff) pio_remove_program(PINOUT_TOOL78_PIO, prgm_tx, txoff);
if (!~rxoff) pio_remove_program(PINOUT_TOOL78_PIO, prgm_rx, rxoff);
if (smtx >= 0) pio_sm_unclaim(PINOUT_TOOL78_PIO, smtx);
if (smrx >= 0) pio_sm_unclaim(PINOUT_TOOL78_PIO, smrx);
return false;
}
void tool78_hw_deinit_help(const pio_program_t* prgm_tx,
const pio_program_t* prgm_rx, const struct tool78_pio_vars* vars) {
if (vars->smrx >= 0) {
pio_sm_set_enabled(PINOUT_TOOL78_PIO, vars->smrx, false);
pio_sm_unclaim(PINOUT_TOOL78_PIO, vars->smrx);
}
if (vars->smtx >= 0) {
pio_sm_set_enabled(PINOUT_TOOL78_PIO, vars->smtx, false);
pio_sm_unclaim(PINOUT_TOOL78_PIO, vars->smtx);
}
if (~vars->rxoff) pio_remove_program(PINOUT_TOOL78_PIO, prgm_rx, vars->rxoff);
if (~vars->txoff) pio_remove_program(PINOUT_TOOL78_PIO, prgm_tx, vars->txoff);
}
bool tool78_hw_help_check_overrun(const struct tool78_pio_vars* vars) {
if (vars->smrx < 0 || !~vars->rxoff) return false;
// check if an RX overrun happened. if so, reset some stuff
uint rxstall_flg = ((1u << vars->smrx) << PIO_FDEBUG_RXSTALL_LSB);
if (PINOUT_TOOL78_PIO->fdebug & rxstall_flg) {
pio_sm_set_enabled(PINOUT_TOOL78_PIO, vars->smrx, false);
pio_sm_clear_fifos(PINOUT_TOOL78_PIO, vars->smrx);
PINOUT_TOOL78_PIO->fdebug = rxstall_flg;
pio_sm_restart(PINOUT_TOOL78_PIO, vars->smrx);
pio_sm_exec(PINOUT_TOOL78_PIO, vars->smrx, pio_encode_jmp(vars->rxoff));
pio_sm_set_enabled(PINOUT_TOOL78_PIO, vars->smrx, true);
return true;
}
return false;
}
int tool78_hw_has_available_help(const struct tool78_pio_vars* vars) {
if (tool78_hw_help_check_overrun(vars)) return -1;
return pio_sm_get_rx_fifo_level(PINOUT_TOOL78_PIO, vars->smrx);
}
int tool78_hw_help_recv(const struct tool78_pio_vars* vars,
int len, uint8_t* data, int32_t timeout_us) {
bool overrun = tool78_hw_help_check_overrun(vars);
bool blockinf = timeout_us < 0;
int i = 0;
absolute_time_t at = make_timeout_time_us(timeout_us);
timeout_state_t ts = {0};
check_timeout_fn ct = NULL;
if (!blockinf) ct = init_single_timeout_until(&ts, at);
for (; i < len && (!pio_sm_is_rx_fifo_empty(PINOUT_TOOL78_PIO, vars->smrx)
|| blockinf); ++i) {
while (pio_sm_is_rx_fifo_empty(PINOUT_TOOL78_PIO, vars->smrx)) {
if (!blockinf && ct(&ts)) goto end; // whoops, timeout
// TODO: sleep a bit? idk
}
data[i] = bitswap(*(volatile uint8_t*)&PINOUT_TOOL78_PIO->rxf[vars->smrx]);
}
end:
return overrun ? -i : i;
}
int tool78_hw_help_send(const struct tool78_pio_vars* vars, uint32_t sleep_us_between_bytes,
int len, const uint8_t* data, int32_t timeout_us) {
if (vars->exclusive)
pio_sm_set_enabled(PINOUT_TOOL78_PIO, vars->smrx, false);
bool blockinf = timeout_us < 0;
absolute_time_t at = make_timeout_time_us(timeout_us);
timeout_state_t ts = {0};
check_timeout_fn ct = NULL;
if (!blockinf) ct = init_single_timeout_until(&ts, at);
int i = 0;
for (; i < len; ++i) {
while (pio_sm_is_tx_fifo_full(PINOUT_TOOL78_PIO, vars->smtx)) {
if (!blockinf && ct(&ts)) goto end; // whoops, timeout
}
*(volatile uint8_t*)&PINOUT_TOOL78_PIO->txf[vars->smtx] = bitswap(data[i]);
if (sleep_us_between_bytes) busy_wait_us_32(sleep_us_between_bytes);
}
end:
if (vars->exclusive) {
// wait until everything is sent before reenabling the RX SM again
while (!pio_sm_is_tx_fifo_empty(PINOUT_TOOL78_PIO, vars->smtx))
; // wait until FIFO is clear
while (!(PINOUT_TOOL78_PIO->fdebug & ((1u << vars.smtx) << PIO_FDEBUG_TXSTALL_LSB)))
; // now wait for the SM to hang on the next 'pull'
pio_sm_set_enabled(PINOUT_TOOL78_PIO, vars->smrx, true);
}
return i;
}

View File

@ -0,0 +1,39 @@
#ifndef TOOL78_HW_HELPERS_H_
#define TOOL78_HW_HELPERS_H_
#include <stdint.h>
#include <stdbool.h>
#include <hardware/pio.h>
struct tool78_pio_vars {
uint txoff, rxoff;
int smtx, smrx;
// temporarily disable rx when doing tx (typically desired when doing
// single-wire UART, as otherwise the data would be echoing back)
bool exclusive;
};
// claims and inits program space & state machines, saves the offsets & SMs
// in a struct. returns true if successful.
// still needs to be done: initing & enabling the PIO SMs
bool tool78_hw_init_help(const pio_program_t* prgm_tx,
const pio_program_t* prgm_rx, struct tool78_pio_vars* vars);
// disables the SM, deallocates the program & SM
// still nees to be done: changing the SM pin functions to something/NULL
void tool78_hw_deinit_help(const pio_program_t* prgm_tx,
const pio_program_t* prgm_rx, const struct tool78_pio_vars* vars);
bool tool78_hw_help_check_overrun(const struct tool78_pio_vars* vars);
int tool78_hw_has_available_help(const struct tool78_pio_vars* vars);
int tool78_hw_help_recv(const struct tool78_pio_vars* vars,
int len, uint8_t* data, int32_t timeout_us);
int tool78_hw_help_send(const struct tool78_pio_vars* vars, uint32_t sleep_us_between_bytes,
int len, const uint8_t* data, int32_t timeout_us);
#endif

View File

@ -0,0 +1,67 @@
#include <hardware/dma.h>
#include <hardware/gpio.h>
#include <hardware/irq.h>
#include <hardware/pio.h>
#include <pico/time.h>
#include <pico/timeout_helper.h>
#include "tool78_defs.h"
#include "tool78_hw_helpers.h"
#include "tool78.pio.h"
#include "tool78_hw.h"
static struct tool78_pio_vars vars;
static bool test_init(void) {
if (!tool78_hw_init_help(&tool78_uart_tx_program, &tool78_uart_rx_program,
&vars)) return false;
vars.exclusive = false;
// TODO: entry sequence here
tool78_uart_tx_program_init(PINOUT_TOOL78_PIO, vars.smtx, vars.txoff,
PINOUT_TOOL78_RL78_TX, 115200, true);
tool78_uart_rx_program_init(PINOUT_TOOL78_PIO, vars.smrx, vars.rxoff,
PINOUT_TOOL78_RL78_RX, 115200, true);
// TODO: magic initial not-really-commands
return true; // all is well!
}
static void test_deinit(void) {
tool78_hw_deinit_help(&tool78_uart_tx_program, &tool78_uart_rx_program,
&vars);
// keep pullups
gpio_set_function(PINOUT_TOOL78_78K0_TXMOSI, GPIO_FUNC_NULL);
gpio_set_function(PINOUT_TOOL78_78K0_RXMISO, GPIO_FUNC_NULL);
}
static int test_has_available(void) {
return tool78_hw_has_available_help(&vars);
}
static int test_recv(int len, uint8_t* data, int32_t timeout_us) {
return tool78_hw_help_recv(&vars, len, data, timeout_us);
}
static int test_send(int len, const uint8_t* data, int32_t timeout_us) {
return tool78_hw_help_send(&vars, 0/*inter-byte delay*/,
len, data, timeout_us);
}
struct tool78_hw tool78_hw_test_uart2 = {
.target = tool78k0_kx2_uart2,
.init = test_init,
.deinit = test_deinit,
.has_available = test_has_available,
.recv = test_recv,
.send = test_send
};