aboutsummaryrefslogtreecommitdiffhomepage
diff options
context:
space:
mode:
-rw-r--r--Makefile2
-rw-r--r--src/examples/empty/main.go11
-rw-r--r--src/machine/machine_attiny1616.go52
-rw-r--r--src/machine/machine_avr.go2
-rw-r--r--src/machine/machine_avrtiny.go60
-rw-r--r--src/runtime/runtime_avr.go2
-rw-r--r--src/runtime/runtime_avrtiny.go191
-rw-r--r--targets/attiny1616.json14
-rw-r--r--targets/avrtiny.S44
-rw-r--r--targets/avrtiny.json25
-rw-r--r--targets/avrtiny.ld58
-rwxr-xr-xtools/gen-device-avr/gen-device-avr.go13
12 files changed, 472 insertions, 2 deletions
diff --git a/Makefile b/Makefile
index 154816f4b..6766bca46 100644
--- a/Makefile
+++ b/Makefile
@@ -704,6 +704,8 @@ endif
@$(MD5SUM) test.hex
$(TINYGO) build -size short -o test.hex -target=arduino-nano examples/blinky1
@$(MD5SUM) test.hex
+ $(TINYGO) build -size short -o test.hex -target=attiny1616 examples/empty
+ @$(MD5SUM) test.hex
$(TINYGO) build -size short -o test.hex -target=digispark examples/blinky1
@$(MD5SUM) test.hex
$(TINYGO) build -size short -o test.hex -target=digispark -gc=leaking examples/blinky1
diff --git a/src/examples/empty/main.go b/src/examples/empty/main.go
new file mode 100644
index 000000000..3b9a0a8d5
--- /dev/null
+++ b/src/examples/empty/main.go
@@ -0,0 +1,11 @@
+package main
+
+import "time"
+
+// This is used for smoke tests for chips without an associated board.
+
+func main() {
+ for {
+ time.Sleep(time.Second)
+ }
+}
diff --git a/src/machine/machine_attiny1616.go b/src/machine/machine_attiny1616.go
new file mode 100644
index 000000000..55007ab78
--- /dev/null
+++ b/src/machine/machine_attiny1616.go
@@ -0,0 +1,52 @@
+//go:build attiny1616
+
+package machine
+
+import (
+ "device/avr"
+)
+
+const (
+ portA Pin = iota * 8
+ portB
+ portC
+)
+
+const (
+ PA0 = portA + 0
+ PA1 = portA + 1
+ PA2 = portA + 2
+ PA3 = portA + 3
+ PA4 = portA + 4
+ PA5 = portA + 5
+ PA6 = portA + 6
+ PA7 = portA + 7
+ PB0 = portB + 0
+ PB1 = portB + 1
+ PB2 = portB + 2
+ PB3 = portB + 3
+ PB4 = portB + 4
+ PB5 = portB + 5
+ PB6 = portB + 6
+ PB7 = portB + 7
+ PC0 = portC + 0
+ PC1 = portC + 1
+ PC2 = portC + 2
+ PC3 = portC + 3
+ PC4 = portC + 4
+ PC5 = portC + 5
+ PC6 = portC + 6
+ PC7 = portC + 7
+)
+
+// getPortMask returns the PORT peripheral and mask for the pin.
+func (p Pin) getPortMask() (*avr.PORT_Type, uint8) {
+ switch {
+ case p >= PA0 && p <= PA7: // port A
+ return avr.PORTA, 1 << uint8(p-portA)
+ case p >= PB0 && p <= PB7: // port B
+ return avr.PORTB, 1 << uint8(p-portB)
+ default: // port C
+ return avr.PORTC, 1 << uint8(p-portC)
+ }
+}
diff --git a/src/machine/machine_avr.go b/src/machine/machine_avr.go
index a1c6991cc..75252c371 100644
--- a/src/machine/machine_avr.go
+++ b/src/machine/machine_avr.go
@@ -1,4 +1,4 @@
-//go:build avr
+//go:build avr && !avrtiny
package machine
diff --git a/src/machine/machine_avrtiny.go b/src/machine/machine_avrtiny.go
new file mode 100644
index 000000000..02393700c
--- /dev/null
+++ b/src/machine/machine_avrtiny.go
@@ -0,0 +1,60 @@
+//go:build avrtiny
+
+package machine
+
+import "device/avr"
+
+const deviceName = avr.DEVICE
+
+const (
+ PinInput PinMode = iota
+ PinInputPullup
+ PinOutput
+)
+
+// Configure sets the pin to input or output.
+func (p Pin) Configure(config PinConfig) {
+ port, mask := p.getPortMask()
+
+ if config.Mode == PinOutput {
+ // set output bit
+ port.DIRSET.Set(mask)
+
+ // Note: if the pin was PinInputPullup before, it'll now be high.
+ // Otherwise it will be low.
+ } else {
+ // configure input: clear output bit
+ port.DIRCLR.Set(mask)
+
+ if config.Mode == PinInput {
+ // No pullup (floating).
+ // The transition may be one of the following:
+ // output high -> input pullup -> input (safe: output high and input pullup are similar)
+ // output low -> input -> input (safe: no extra transition)
+ port.OUTCLR.Set(mask)
+ } else {
+ // Pullup.
+ // The transition may be one of the following:
+ // output high -> input pullup -> input pullup (safe: no extra transition)
+ // output low -> input -> input pullup (possibly problematic)
+ // For the last transition (output low -> input -> input pullup),
+ // the transition may be problematic in some cases because there is
+ // an intermediate floating state (which may cause irratic
+ // interrupts, for example). If this is a problem, the application
+ // should set the pin high before configuring it as PinInputPullup.
+ // We can't do that here because setting it to high as an
+ // intermediate state may have other problems.
+ port.OUTSET.Set(mask)
+ }
+ }
+}
+
+// Set changes the value of the GPIO pin. The pin must be configured as output.
+func (p Pin) Set(high bool) {
+ port, mask := p.getPortMask()
+ if high {
+ port.OUTSET.Set(mask)
+ } else {
+ port.OUTCLR.Set(mask)
+ }
+}
diff --git a/src/runtime/runtime_avr.go b/src/runtime/runtime_avr.go
index bf9860ed0..a2e11104e 100644
--- a/src/runtime/runtime_avr.go
+++ b/src/runtime/runtime_avr.go
@@ -1,4 +1,4 @@
-//go:build avr
+//go:build avr && !avrtiny
package runtime
diff --git a/src/runtime/runtime_avrtiny.go b/src/runtime/runtime_avrtiny.go
new file mode 100644
index 000000000..63eb5943a
--- /dev/null
+++ b/src/runtime/runtime_avrtiny.go
@@ -0,0 +1,191 @@
+//go:build avrtiny
+
+// Runtime for the newer AVRs introduced since around 2016 that work quite
+// different from older AVRs like the atmega328p or even the attiny85.
+// Because of these large differences, a new runtime and machine implementation
+// is needed.
+// Some key differences:
+// * Peripherals are now logically separated, instead of all mixed together as
+// one big bag of registers. No PORTA/DDRA etc registers anymore, instead a
+// real PORT peripheral type with multiple instances.
+// * There is a real RTC now! No need for using one of the timers as a time
+// source, which then conflicts with using it as a PWM.
+// * Flash and RAM are now in the same address space! This avoids the need for
+// PROGMEM which couldn't (easily) be supported in Go anyway. Constant
+// globals just get stored in flash, like on Cortex-M chips.
+
+package runtime
+
+import (
+ "device/avr"
+ "runtime/interrupt"
+ "runtime/volatile"
+)
+
+type timeUnit int64
+
+//export main
+func main() {
+ // Initialize RTC.
+ for avr.RTC.STATUS.Get() != 0 {
+ }
+ avr.RTC.CTRLA.Set(avr.RTC_CTRLA_RTCEN | avr.RTC_CTRLA_RUNSTDBY)
+ avr.RTC.INTCTRL.Set(avr.RTC_INTCTRL_OVF) // enable overflow interrupt
+ interrupt.New(avr.IRQ_RTC_CNT, rtcInterrupt)
+
+ // Configure sleep:
+ // - enable sleep mode
+ // - set sleep mode to STANDBY (mode 0x1)
+ avr.SLPCTRL.CTRLA.Set(avr.SLPCTRL_CTRLA_SEN | 0x1<<1)
+
+ // Enable interrupts after initialization.
+ avr.Asm("sei")
+
+ run()
+ exit(0)
+}
+
+func initUART() {
+ // no UART configured
+}
+
+func putchar(b byte) {
+ // no-op
+}
+
+// ticksToNanoseconds converts RTC ticks (at 32768Hz) to nanoseconds.
+func ticksToNanoseconds(ticks timeUnit) int64 {
+ // The following calculation is actually the following, but with both sides
+ // reduced to reduce the risk of overflow:
+ // ticks * 1e9 / 32768
+ return int64(ticks) * 1953125 / 64
+}
+
+// nanosecondsToTicks converts nanoseconds to RTC ticks (running at 32768Hz).
+func nanosecondsToTicks(ns int64) timeUnit {
+ // The following calculation is actually the following, but with both sides
+ // reduced to reduce the risk of overflow:
+ // ns * 32768 / 1e9
+ return timeUnit(ns * 64 / 1953125)
+}
+
+// Sleep for the given number of timer ticks.
+func sleepTicks(d timeUnit) {
+ ticksStart := ticks()
+ sleepUntil := ticksStart + d
+
+ // Sleep until we're in the right 2-second interval.
+ for {
+ avr.Asm("cli")
+ overflows := rtcOverflows.Get()
+ if overflows >= uint32(sleepUntil>>16) {
+ // We're in the right 2-second interval.
+ // At this point we know that the difference between ticks() and
+ // sleepUntil is ≤0xffff.
+ avr.Asm("sei")
+ break
+ }
+ // Sleep some more, because we're not there yet.
+ avr.Asm("sei\nsleep")
+ }
+
+ // Now we know the sleep duration is small enough to fit in rtc.CNT.
+
+ // Update rtc.CMP (atomically).
+ cnt := uint16(sleepUntil)
+ low := uint8(cnt)
+ high := uint8(cnt >> 8)
+ avr.RTC.CMPH.Set(high)
+ avr.RTC.CMPL.Set(low)
+
+ // Disable interrupts, so we can change interrupt settings without racing.
+ avr.Asm("cli")
+
+ // Enable the CMP interrupt.
+ avr.RTC.INTCTRL.Set(avr.RTC_INTCTRL_OVF | avr.RTC_INTCTRL_CMP)
+
+ // Check whether we already reached CNT, in which case the interrupt may
+ // have triggered already (but maybe not, it's a race condition).
+ low2 := avr.RTC.CNTL.Get()
+ high2 := avr.RTC.CNTH.Get()
+ cnt2 := uint16(high2)<<8 | uint16(low2)
+ if cnt2 < cnt {
+ // We have not, so wait until the interrupt happens.
+ for {
+ // Sleep until the next interrupt happens.
+ avr.Asm("sei\nsleep\ncli")
+ if cmpMatch.Get() != 0 {
+ // The CMP interrupt occured, so we have slept long enough.
+ cmpMatch.Set(0)
+ break
+ }
+ }
+ }
+
+ // Disable the CMP interrupt, and restore things like they were before.
+ avr.RTC.INTCTRL.Set(avr.RTC_INTCTRL_OVF)
+ avr.Asm("sei")
+}
+
+// Number of RTC overflows, updated in the RTC interrupt handler.
+// The RTC is running at 32768Hz so an overflow happens every 2 seconds. A
+// 32-bit integer is large enough to run for about 279 years.
+var rtcOverflows volatile.Register32
+
+// Set to one in the RTC CMP interrupt, to signal the expected number of ticks
+// have passed.
+var cmpMatch volatile.Register8
+
+// Return the number of RTC ticks that happened since reset.
+func ticks() timeUnit {
+ var ovf uint32
+ var count uint16
+ for {
+ // Get the tick count and overflow value, in a 4-step process to avoid a
+ // race with the overflow interrupt.
+ mask := interrupt.Disable()
+
+ // 1. Get the overflow value.
+ ovf = rtcOverflows.Get()
+
+ // 2. Read the RTC counter.
+ // This way of reading is atomic (due to the TEMP register).
+ low := avr.RTC.CNTL.Get()
+ high := avr.RTC.CNTH.Get()
+
+ // 3. Get the interrupt flags.
+ intflags := avr.RTC.INTFLAGS.Get()
+
+ interrupt.Restore(mask)
+
+ // 4. Check whether an overflow happened somewhere in the last three
+ // steps. If so, just repeat the loop.
+ if intflags&avr.RTC_INTFLAGS_OVF == 0 {
+ count = uint16(high)<<8 | uint16(low)
+ break
+ }
+ }
+
+ // Create the 64-bit tick count, combining the two.
+ return timeUnit(ovf)<<16 | timeUnit(count)
+}
+
+// Interrupt handler for the RTC.
+// It happens every two seconds, and while sleeping using the CMP interrupt.
+func rtcInterrupt(interrupt.Interrupt) {
+ flags := avr.RTC.INTFLAGS.Get()
+ if flags&avr.RTC_INTFLAGS_OVF != 0 {
+ rtcOverflows.Set(rtcOverflows.Get() + 1)
+ }
+ if flags&avr.RTC_INTFLAGS_CMP != 0 {
+ cmpMatch.Set(1)
+ }
+ avr.RTC.INTFLAGS.Set(flags) // clear interrupts
+}
+
+func exit(code int) {
+ abort()
+}
+
+//export __vector_default
+func abort()
diff --git a/targets/attiny1616.json b/targets/attiny1616.json
new file mode 100644
index 000000000..38e645ae1
--- /dev/null
+++ b/targets/attiny1616.json
@@ -0,0 +1,14 @@
+{
+ "inherits": ["avrtiny"],
+ "cpu": "attiny1616",
+ "build-tags": ["attiny1616"],
+ "gc": "none",
+ "cflags": [
+ "-D__AVR_ARCH__=103"
+ ],
+ "linkerscript": "src/device/avr/attiny1616.ld",
+ "extra-files": [
+ "src/device/avr/attiny1616.s"
+ ],
+ "flash-command": "pymcuprog write -f {hex} --erase --verify -d attiny1616 -t uart -u {port}"
+}
diff --git a/targets/avrtiny.S b/targets/avrtiny.S
new file mode 100644
index 000000000..75f0c604f
--- /dev/null
+++ b/targets/avrtiny.S
@@ -0,0 +1,44 @@
+; TODO: remove these in LLVM 15
+#define __tmp_reg__ r16
+#define __zero_reg__ r17
+
+; Startup code
+.section .text.__vector_RESET
+.global __vector_RESET
+__vector_RESET:
+ clr __zero_reg__ ; this register is expected to be 0 by the C calling convention
+
+ ; Keep the stack pointer at the default location, which is RAMEND.
+
+; Initialize .data section.
+.section .text.__do_copy_data,"ax",@progbits
+.global __do_copy_data
+__do_copy_data:
+ ldi xl, lo8(__data_start)
+ ldi xh, hi8(__data_start)
+ ldi yl, lo8(__data_end)
+ ldi yh, hi8(__data_end)
+ ldi zl, lo8(__data_load_start)
+ ldi zh, hi8(__data_load_start)
+1: ; loop
+ cp xl, yl ; if x == y
+ cpc xh, yh
+ breq 2f ; goto end
+ ld r16, Z+ ; r0 = *(z++)
+ st X+, r16 ; *(x++) = r0
+ rjmp 1b ; goto loop
+2: ; end
+
+; Initialize .bss section.
+.section .text.__do_clear_bss,"ax",@progbits
+.global __do_clear_bss
+__do_clear_bss:
+ ldi xl, lo8(__bss_start)
+ ldi xh, hi8(__bss_start)
+ ldi yl, lo8(__bss_end)
+1: ; loop
+ cp xl, yl ; if x == y
+ breq 2f ; goto end
+ st X+, __zero_reg__ ; *(x++) = 0
+ rjmp 1b ; goto loop
+2: ; end
diff --git a/targets/avrtiny.json b/targets/avrtiny.json
new file mode 100644
index 000000000..7cb1581f9
--- /dev/null
+++ b/targets/avrtiny.json
@@ -0,0 +1,25 @@
+{
+ "llvm-target": "avr",
+ "build-tags": ["avr", "avrtiny", "baremetal", "linux", "arm"],
+ "goos": "linux",
+ "goarch": "arm",
+ "gc": "conservative",
+ "linker": "ld.lld",
+ "scheduler": "none",
+ "rtlib": "compiler-rt",
+ "libc": "picolibc",
+ "default-stack-size": 256,
+ "cflags": [
+ "-Werror"
+ ],
+ "ldflags": [
+ "-T", "targets/avrtiny.ld",
+ "--gc-sections"
+ ],
+ "extra-files": [
+ "src/internal/task/task_stack_avr.S",
+ "src/runtime/asm_avr.S",
+ "targets/avrtiny.S"
+ ],
+ "gdb": ["avr-gdb"]
+}
diff --git a/targets/avrtiny.ld b/targets/avrtiny.ld
new file mode 100644
index 000000000..60821cf8b
--- /dev/null
+++ b/targets/avrtiny.ld
@@ -0,0 +1,58 @@
+/* Linker script for AVRs with a unified flash and RAM address space. This
+ * includes the ATtiny10 and the ATtiny1616.
+ */
+
+MEMORY
+{
+ FLASH_TEXT (x) : ORIGIN = 0, LENGTH = __flash_size
+ FLASH_DATA (r) : ORIGIN = __mapped_flash_start, LENGTH = __flash_size
+ RAM (xrw) : ORIGIN = __ram_start, LENGTH = __ram_size
+}
+
+ENTRY(main)
+
+SECTIONS
+{
+ .text :
+ {
+ KEEP(*(.vectors))
+ *(.text.__vector_RESET)
+ KEEP(*(.text.__do_copy_data)) /* TODO: only use when __do_copy_data is requested */
+ KEEP(*(.text.__do_clear_bss))
+ KEEP(*(.text.main)) /* main must follow the reset handler */
+ *(.text)
+ *(.text.*)
+ } > FLASH_TEXT
+
+ /* Read-only data is stored in flash, but is read from an offset (0x4000 or
+ * 0x8000 depending on the chip). This requires some weird math to get it in
+ * the right place.
+ */
+ .rodata ORIGIN(FLASH_DATA) + ADDR(.text) + SIZEOF(.text):
+ {
+ *(.rodata)
+ *(.rodata.*)
+ } AT>FLASH_TEXT
+
+ /* The address to which the data section should be copied by the startup
+ * code.
+ */
+ __data_load_start = ORIGIN(FLASH_DATA) + LOADADDR(.data);
+
+ .data :
+ {
+ __data_start = .; /* used by startup code */
+ *(.data)
+ *(.data*)
+ __data_end = .; /* used by startup code */
+ } >RAM AT>FLASH_TEXT
+
+ .bss :
+ {
+ __bss_start = .; /* used by startup code */
+ *(.bss)
+ *(.bss*)
+ *(COMMON)
+ __bss_end = .; /* used by startup code */
+ } >RAM
+}
diff --git a/tools/gen-device-avr/gen-device-avr.go b/tools/gen-device-avr/gen-device-avr.go
index c660f8ca7..de32e3ed9 100755
--- a/tools/gen-device-avr/gen-device-avr.go
+++ b/tools/gen-device-avr/gen-device-avr.go
@@ -333,6 +333,15 @@ func readATDF(path string) (*Device, error) {
}
}
+ // Flash that is mapped into the data address space (attiny10, attiny1616,
+ // etc).
+ mappedFlashStart := int64(0)
+ for _, name := range []string{"MAPPED_PROGMEM", "MAPPED_FLASH"} {
+ if segment, ok := memorySizes["data"].Segments[name]; ok {
+ mappedFlashStart = segment.start
+ }
+ }
+
flashSize, err := strconv.ParseInt(memorySizes["prog"].Size, 0, 32)
if err != nil {
return nil, err
@@ -379,6 +388,7 @@ func readATDF(path string) (*Device, error) {
"flashSize": int(flashSize),
"ramStart": ramStart,
"ramSize": ramSize,
+ "mappedFlashStart": mappedFlashStart,
"numInterrupts": len(device.Interrupts),
},
interrupts: interrupts,
@@ -629,6 +639,9 @@ func writeLD(outdir string, device *Device) error {
/* Generated by gen-device-avr.go from {{.file}}, see {{.descriptorSource}} */
__flash_size = 0x{{printf "%x" .flashSize}};
+{{if .mappedFlashStart -}}
+__mapped_flash_start = 0x{{printf "%x" .mappedFlashStart}};
+{{end -}}
__ram_start = 0x{{printf "%x" .ramStart}};
__ram_size = 0x{{printf "%x" .ramSize}};
__num_isrs = {{.numInterrupts}};