Add board_clock_7seg project
authorNick Downing <nick@ndcode.org>
Thu, 24 Mar 2022 07:49:07 +0000 (18:49 +1100)
committerNick Downing <nick@ndcode.org>
Thu, 24 Mar 2022 07:49:15 +0000 (18:49 +1100)
.gitignore
examples/board_clock_7seg/Makefile [new file with mode: 0644]
examples/board_clock_7seg/README [new file with mode: 0644]
examples/board_clock_7seg/atmega168_clock_7seg.c [new file with mode: 0644]
examples/board_clock_7seg/atmega168_clock_7seg.h [new file with mode: 0644]
examples/board_clock_7seg/clock_7seg.c [new file with mode: 0644]
examples/board_clock_7seg/led_17seg.py [new file with mode: 0755]
examples/board_clock_7seg/led_17seg.svg [new file with mode: 0644]
examples/board_clock_7seg/led_8seg.py [new file with mode: 0755]
examples/board_clock_7seg/led_8seg.svg [new file with mode: 0644]
n.sh [new file with mode: 0755]

index 0ebc297..7b2b74a 100644 (file)
@@ -18,3 +18,4 @@ callgrind.out.*
 perf.data
 .DS_Store
 .make.options*
+/examples/board_clock_7seg/*.inc
diff --git a/examples/board_clock_7seg/Makefile b/examples/board_clock_7seg/Makefile
new file mode 100644 (file)
index 0000000..06154f9
--- /dev/null
@@ -0,0 +1,56 @@
+# 
+#      Copyright 2008, 2009 Michel Pollet <buserror@gmail.com>
+#
+#      This file is part of simavr.
+#
+#      simavr is free software: you can redistribute it and/or modify
+#      it under the terms of the GNU General Public License as published by
+#      the Free Software Foundation, either version 3 of the License, or
+#      (at your option) any later version.
+#
+#      simavr 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 simavr.  If not, see <http://www.gnu.org/licenses/>.
+
+target=        clock_7seg
+firm_src = ${wildcard at*${target}.c}
+firmware = ${firm_src:.c=.axf}
+simavr = ../../
+
+IPATH = .
+IPATH += ../parts
+IPATH += ${simavr}/include
+IPATH += ${simavr}/simavr/sim
+
+VPATH = .
+VPATH += ../parts
+
+LDFLAGS += -lpthread
+
+include ../Makefile.opengl
+
+all: obj ${firmware} ${target}
+
+include ${simavr}/Makefile.common
+
+board = ${OBJ}/${target}.elf
+
+${board} : ${OBJ}/button.o
+${board} : ${OBJ}/hc595.o
+${board} : ${OBJ}/${target}.o
+
+led_8seg.inc: led_8seg.py
+       ./led_8seg.py >$@
+
+led_17seg.inc: led_17seg.py
+       ./led_17seg.py >$@
+
+${target}: ${board}
+       @echo $@ done
+
+clean: clean-${OBJ}
+       rm -rf *.a *.axf ${target} *.vcd *.hex
diff --git a/examples/board_clock_7seg/README b/examples/board_clock_7seg/README
new file mode 100644 (file)
index 0000000..226cd63
--- /dev/null
@@ -0,0 +1,21 @@
+
+clock_7seg
+(C) 2006-2009 Michel Pollet <buserror@gmail.com>
+
+This is a real life project, see enclosed JPEG.
+
+At atmega168 drives 4 74HC595 shift registers to drive 64 LEDs. 3 Buttons
+provide an interface for "start", "stop" and "reset" of the timer.
+
+The timer handles multiple days by switching to display "hours + minutes"
+instead of "minutes + seconds" after an hour.
+
+The LED brightness changes if you stop the timer.
+
+The interest of this in simavr is the ease of making a "fake peripheral"
+that simulates the 4 shift registers, recover the PWM duty cycle and
+send button events.
+
+Also, make sure to record a "wave file" to display in gtkwave, you will
+see the Interupt flags, the shift register being filled, the latch pins,
+and even the PWM duty cycle.
diff --git a/examples/board_clock_7seg/atmega168_clock_7seg.c b/examples/board_clock_7seg/atmega168_clock_7seg.c
new file mode 100644 (file)
index 0000000..0df5299
--- /dev/null
@@ -0,0 +1,526 @@
+/*
+  atmega168_clock_7seg.c
+  
+  Copyright 2008, 2009 Michel Pollet <buserror@gmail.com>
+
+   This file is part of simavr.
+
+  simavr is free software: you can redistribute it and/or modify
+  it under the terms of the GNU General Public License as published by
+  the Free Software Foundation, either version 3 of the License, or
+  (at your option) any later version.
+
+  simavr 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 simavr.  If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+#include <util/delay.h>
+#include <avr/sleep.h>
+
+#include "atmega168_clock_7seg.h"
+
+// for linker, emulator, and programmer's sake
+#include "avr_mcu_section.h"
+AVR_MCU(F_CPU, "atmega168");
+
+PIN_DEFINE(SRESET, D, PD4, 1);
+//PIN_DEFINE(SOE, D, PD6, 1);    // pwm AIN0/OC0A
+PIN_DEFINE(SLATCH, D, PD7, 1);
+
+PIN_DEFINE(BSTART, C, PC0, 1);  // PCI6
+PIN_DEFINE(BSTOP, B, PB1, 1);  // PCI1
+PIN_DEFINE(BRESET, B, PB0, 1);  // PCI0
+
+
+#define  TICK_HZ          4
+
+enum {
+  TICK_SECOND      = TICK_HZ,
+  TICK_250MS      = (TICK_SECOND / 4),
+  TICK_500MS      = (TICK_SECOND / 2),
+  TICK_750MS      = (TICK_500MS + TICK_250MS),
+  TICK_MAX      = 0x7f,
+
+  TICK_TIMER_DISABLED    = 0xff
+};
+
+volatile uint32_t tickCount;
+struct tick_t {
+  uint8_t  delay;
+  void (*callback)(struct tick_t *);
+};
+
+enum EDelayIndex {
+        delay_Second    = 0,
+        delay_Update,
+        delay_DisplayChange,
+        delay_StopFade,
+
+        timer_MAX
+};
+
+struct tick_t timer[timer_MAX];
+
+#define tick_timer_fired(_t) (timer[(_t)].delay == 0)
+#define tick_timer_reset(_t, _v) timer[(_t)].delay = (_v)
+
+ISR(TIMER2_COMPA_vect)    // handler for Output Compare 1 overflow interrupt
+{
+  sei();
+  tickCount++;
+
+  // decrement delay lines
+  for (char i = 0; i < timer_MAX; i++)
+    if (timer[(int)i].delay && timer[(int)i].delay != TICK_TIMER_DISABLED) {
+      timer[(int)i].delay--;
+      if (timer[(int)i].delay == 0 && timer[(int)i].callback)
+        timer[(int)i].callback(&timer[(int)i]);
+    }
+}
+
+
+void tick_init()
+{
+  /*
+    Timer 2 as RTC
+   */
+  // needs to do that before changing the timer registers
+  // ASYNC timer using a 32k crystal
+  ASSR |= (1 << AS2);
+    TCCR2A = (1 << WGM21);
+    TCCR2B = (3 << CS20);
+    OCR2A = 127;
+    TIMSK2  |= (1 << OCIE2A);
+}
+
+
+enum EKEYS {
+  KEY_RESET = 0,  // 0x01
+  KEY_STOP,    // 0x02
+  KEY_START,    // 0x04
+  KEY_MAX
+};
+
+enum EState {
+  state_ShowTime = 0,
+  state_ShowHour,
+  state_Sleep,
+  
+  state_IncrementTime = (1 << 7),
+  
+  state_MAX
+} ;
+
+uint8_t state = state_ShowTime | state_IncrementTime;
+uint8_t  digits[4];
+
+enum EDecimal {
+  d_second = 0, d_10second, d_minute, d_10minute, d_hour, d_10hour, d_100hour, d_MAX
+};
+const uint8_t decimal_max[d_MAX] = { 10, 6, 10, 6, 10, 10, 10 };
+uint8_t decimal[d_MAX] = {0,0,0,0,0,0,0};
+uint8_t decimalChanged = 0;
+
+uint8_t keyState;// = 0x7;
+uint8_t keyEvent = 0;
+uint8_t keyDebounce[KEY_MAX];
+uint8_t lastKeyValue; // = 0; // use to detect which pin(s) triggered the interupt
+
+#define PWM_MAX_DUTY_CYCLE 0xFF
+
+#define STANDBY_DELAY  60
+
+uint8_t pwmRunning = PWM_MAX_DUTY_CYCLE - (PWM_MAX_DUTY_CYCLE >> 4);
+uint8_t pwmStopped = PWM_MAX_DUTY_CYCLE - (PWM_MAX_DUTY_CYCLE >> 6);
+uint16_t stopTimerCount;
+
+void pwmInit(void)
+{
+    /* 
+       Start Timer 0 with no clock prescaler and phase correct 
+       fast PWM mode. Output on PD6 (OC0A). 
+    */
+    TCCR0A =  (1<<COM0A1)|(0<<COM0A0)|(0<<COM0B1)|(0<<COM0B0)
+             |(1<<WGM01) |(1<<WGM00);
+    TCCR0B =  (0<<FOC0A) |(0<<FOC0B) |(0<<WGM02)
+             |(0<<CS01)  |(1<<CS00);
+//  TIMSK0 = (1 << OCIE0A);
+  
+    // Reset counter
+    TCNT0 = 0;
+
+    // Set duty cycle to 1/16th duty
+//    OCR0A  = PWM_MAX_DUTY_CYCLE - (PWM_MAX_DUTY_CYCLE >> 4);
+  OCR0A = pwmRunning;
+}
+
+static inline void pwmSet(uint8_t pwm)
+{
+  OCR0A = pwm;
+}
+
+
+void decimalInc()
+{
+  for (uint8_t in = 0; in < d_MAX; in++) {
+    decimal[in]++;
+    decimalChanged |= (1 << in);
+    if (decimal[in] == decimal_max[in]) {
+      decimal[in] = 0;
+    } else
+      break;
+  }
+}
+
+//   A
+// F   B
+//   G
+// E   C
+//   D   DP
+const uint8_t  digits2led[10]= {
+  0b00111111, // 0
+  0b00000110, // 1
+  0b01011011, // 2
+  0b01001111, // 3
+  0b01100110, // 4
+  0b01101101, // 5
+  0b01111101, // 6
+  0b00000111, // 7
+  0b01111111, // 8
+  0b01100111, // 9
+};
+
+struct {
+  uint8_t b[16];  
+  uint8_t in : 4;
+  uint8_t out : 4;  
+} spi;
+
+void spi_init()
+{
+  spi.in = spi.out = 0;
+    
+  SPCR =   (1 << SPIE) | (1 << SPE) | (0 << DORD) | (1 << MSTR) | 
+      (0 << CPOL) | (0 << CPHA) | (0 << SPR0);
+  SPSR =  (0 << SPI2X);
+}
+
+void spi_start()
+{
+  uint8_t b;
+  if (spi.in != spi.out) {
+    b = spi.b[spi.in++];
+    SPDR = b;
+  }    
+}
+
+/*
+ * SPI FIFO and it's interupt function. The function just pushes the
+ * 'next' byte into the SPI register, and if there are no more bytes, it
+ * toggles the 'latch' PIN of the 74H595 to update all the LEDS in one go.
+ *
+ * There is a potential small race condition here where 2 sets of four bytes
+ * are sent in sequence, but the probability is that 64 bits will be sent 
+ * before the latch trigges instead of 32; and if they were /that/ close it
+ * doesn'nt make a difference anyway.
+ * One way to solve that would be to have a 'terminator' or 'flush' signal
+ * queued along the byte stream.
+ */
+
+ISR(SPI_STC_vect)
+{
+  uint8_t b;
+  if (spi.in != spi.out) {
+    b = spi.b[spi.in++];
+    SPDR = b;
+  } else {
+    // fifo is empty, tell the 74hc595 to latch the shift register
+    SET_SLATCH();
+    CLR_SLATCH();
+  }
+}
+
+void startShowTime()
+{
+  state = (state & ~0xf) | state_ShowTime;
+}
+
+void startShowHours(uint8_t timeout /*= 4 * TICK_SECOND*/)
+{
+  if (timer[delay_DisplayChange].delay != TICK_TIMER_DISABLED)
+    tick_timer_reset(delay_DisplayChange, timeout);
+  state = (state & ~0xf) | state_ShowHour;
+}
+
+void updateTimer();
+void sleepTimer();
+void wakeTimer();
+int startTimer();
+int stopTimer();
+void resetTimer();
+
+void sleepTimer()
+{
+  state = state_Sleep;
+  tick_timer_reset(delay_Second, 0);
+  tick_timer_reset(delay_Update, 0);
+  pwmSet(0xff);    // stop the LEDs completely
+}
+
+void wakeTimer()
+{
+  stopTimerCount = 0;
+  if (state == state_Sleep) {
+    startShowTime();
+    tick_timer_reset(delay_Second, TICK_SECOND);
+    tick_timer_reset(delay_Update, 1);
+    pwmSet(pwmRunning);
+    updateTimer();
+  } else
+    pwmSet(pwmRunning);
+}
+
+int startTimer()
+{
+  if (state & state_IncrementTime)
+    return 0;
+  wakeTimer();
+  tick_timer_reset(delay_Second, TICK_SECOND);
+  tick_timer_reset(delay_Update, 1);
+  state |= state_IncrementTime;
+  return 1;
+}
+
+int stopTimer()
+{
+  wakeTimer();
+  if (!(state & state_IncrementTime))
+    return 0;
+  state &= ~state_IncrementTime;
+  stopTimerCount = 0;
+  tick_timer_reset(delay_StopFade, 10 * TICK_SECOND);
+  return 1;
+}
+
+void resetTimer()
+{
+  wakeTimer();
+  startShowTime();
+  tick_timer_reset(delay_Second, TICK_SECOND);
+  tick_timer_reset(delay_Update, 1);
+  for (uint8_t bi = 0; bi < d_MAX; bi++)
+    decimal[bi] = 0;
+}
+
+void updateTimer()
+{
+  if (OCR0A == 0xff)  // if the display is off, don't update anything
+    return;
+  if (!(state & state_IncrementTime) || timer[delay_Second].delay <= 2) {
+    switch (state & ~state_IncrementTime) {
+      case state_ShowTime:
+        //digits[1] |= 0x80;
+        digits[2] |= 0x80;
+        break;
+      case state_ShowHour:
+        if (state & state_IncrementTime)
+          digits[0] |= 0x80;
+        break;
+    }
+  }       
+  cli();
+  // interupts are stopped here, so there is no race condition
+  int restart = spi.out == spi.in;
+  for (uint8_t bi = 0; bi < 4; bi++)
+    spi.b[spi.out++] = digits[bi];
+  if (restart)
+    spi_start();
+  sei();
+}
+
+void updateTimerDisplay()
+{
+  do {
+    switch (state & ~state_IncrementTime) {
+      case state_ShowTime: {
+        if (decimalChanged & (1 << d_hour)) {
+          startShowHours(4 * TICK_SECOND);
+          break;
+        }
+        decimalChanged = 0;
+        for (uint8_t bi = 0; bi < 4; bi++)
+          digits[bi] = digits2led[decimal[bi]];
+
+        if (!(state & state_IncrementTime)) {
+          //digits[1] |= 0x80;
+          digits[2] |= 0x80;          
+        }
+      }  break;
+      case state_ShowHour: {
+        if (tick_timer_fired(delay_DisplayChange)) {
+          decimalChanged = 1;
+          startShowTime();
+          break;
+        }
+        decimalChanged = 0;
+        for (uint8_t bi = 0; bi < 4; bi++)
+          digits[bi] = 0;
+        
+        if (decimal[d_100hour]) {
+          digits[3] = digits2led[decimal[d_100hour]];
+          digits[2] = digits2led[decimal[d_10hour]];
+          digits[1] = digits2led[decimal[d_hour]];
+        } else if (decimal[d_10hour]) {
+          digits[3] = digits2led[decimal[d_10hour]];
+          digits[2] = digits2led[decimal[d_hour]];          
+        } else {
+          digits[2] = digits2led[decimal[d_hour]];          
+        }
+        digits[0] = 116; // 'h'
+      }  break;
+  //    case state_Sleep: {
+        /* nothing to do */
+  //    }  break;
+    }
+  } while (decimalChanged);
+}
+
+/*
+ * Called every seconds to update the visuals
+ */
+void second_timer_callback(struct tick_t *t)
+{
+  t->delay = TICK_SECOND;
+  
+  if (state & state_IncrementTime) {
+    pwmSet(pwmRunning);
+    decimalInc();
+  } else {
+    if (tick_timer_fired(delay_StopFade)) {
+      stopTimerCount++;
+      if (stopTimerCount >= STANDBY_DELAY) {
+        if (OCR0A < 0xff) {
+          if ((stopTimerCount & 0xf) == 0) // very gradualy fade out to zero (notch every 8 secs)
+            OCR0A++;
+        } else
+          sleepTimer(); // this will stop the one second timer
+      } else {
+        if (OCR0A != pwmStopped) {
+          if (OCR0A > pwmStopped)
+            OCR0A--;
+          else
+            OCR0A++;
+        }
+      }
+    }      
+  }
+  updateTimerDisplay();
+}
+
+/*
+ * Called every tick, to push the four bytes of the counter into the shift registers
+ */
+void update_timer_callback(struct tick_t *t)
+{
+  t->delay = 1;
+  updateTimer();
+}
+
+static void updateKeyValues()
+{
+  uint8_t keyValue = (PINB & 3) | ((PINC & 1) << 2);
+  
+  for (uint8_t ki = 0; ki < KEY_MAX; ki++)
+    if ((keyValue & (1 << ki)) != (lastKeyValue & (1 << ki)))
+      keyDebounce[ki] = 0;
+    
+  lastKeyValue = keyValue;
+}
+
+// pin change interupt
+ISR(PCINT0_vect)    { updateKeyValues(); }
+ISR(PCINT1_vect)    { updateKeyValues(); }
+
+int main(void)
+{
+  PORTD = 0;
+  DDRD = 0xff;
+
+  // set power reduction register, disable everything we don't need
+  PRR = (1 << PRTWI) | (1 << PRTIM1) | (1 << PRUSART0) | (1 << PRADC);
+
+  DDRB = ~3; PORTB = 3; // pullups on PB0/PB1
+  DDRC = ~1; PORTC = 1; // pullups on PC0
+  PCMSK0 = (1 << PCINT1) | (1 << PCINT0);  // enable interupt for these pins
+  PCMSK1 = (1 << PCINT8);          // enable interupt for these pins
+  PCICR = (1 << PCIE0) | (1 << PCIE1);  // PCIE0 enable pin interupt PCINT7..0.
+
+  tick_init();
+
+  startShowHours(4 * TICK_SECOND);
+  
+  timer[delay_Second].callback = second_timer_callback;
+  timer[delay_Update].callback = update_timer_callback;
+  second_timer_callback(&timer[delay_Second]);  // get started
+  update_timer_callback(&timer[delay_Update]);  // get started
+
+    startTimer();
+    updateKeyValues();
+    keyState = lastKeyValue;
+    
+  SET_SRESET();
+
+  spi_init();
+  pwmInit();
+    
+    sei();
+  
+    for (;;) {    /* main event loop */
+      /* If our internal ideal of which keys are down is different from the one that has been
+      updated via the interrupts, we start counting. If the 'different' key(s) stays the same for
+      50ms, we declare it an 'event' and update the internal key state
+     */
+      if (keyState != lastKeyValue) {
+        for (uint8_t ki = 0; ki < KEY_MAX; ki++)
+          if ((keyState & (1 << ki)) != (lastKeyValue & (1 << ki))) {
+            if (keyDebounce[ki] < 50) {
+                keyDebounce[ki]++;
+                if (keyDebounce[ki] == 50) {
+                  keyEvent |= (1 << ki);
+                  keyState =   (keyState & ~(1 << ki)) | (lastKeyValue & (1 << ki)); 
+                }
+            }
+          }
+        /*
+         * if a Key changed state, let's check it out
+         */
+        if (keyEvent) {
+          if ((keyEvent & (1 << KEY_START)) &&  (keyState & (1 << KEY_START)) == 0) {
+            if (!startTimer())
+              startShowHours(4 * TICK_SECOND);
+          }
+          if ((keyEvent & (1 << KEY_STOP)) && (keyState & (1 << KEY_STOP)) == 0) {
+            if (!stopTimer())
+              startShowHours(4 * TICK_SECOND);
+          }
+          if ((keyEvent & (1 << KEY_RESET)) && (keyState & (1 << KEY_RESET)) == 0) {
+            resetTimer();
+          }
+          keyEvent = 0;
+          updateTimerDisplay();
+          updateTimer();
+        }
+        delay_ms(1);
+      } else {
+        sleep_mode();
+      }
+    }
+    return 0;
+}
diff --git a/examples/board_clock_7seg/atmega168_clock_7seg.h b/examples/board_clock_7seg/atmega168_clock_7seg.h
new file mode 100644 (file)
index 0000000..715b78a
--- /dev/null
@@ -0,0 +1,62 @@
+/*
+       atmega168_clock_7seg.h
+       
+       Copyright 2008, 2009 Michel Pollet <buserror@gmail.com>
+
+       This file is part of simavr.
+
+       simavr is free software: you can redistribute it and/or modify
+       it under the terms of the GNU General Public License as published by
+       the Free Software Foundation, either version 3 of the License, or
+       (at your option) any later version.
+
+       simavr 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 simavr.  If not, see <http://www.gnu.org/licenses/>.
+ */
+#ifndef __COMMON_H__
+#define __COMMON_H__
+
+
+#include <util/delay.h>
+#include <avr/io.h>
+#include <stdint.h>
+#include <stdio.h>
+
+static inline void delay_ms(uint16_t millis)
+{
+ // uint16_t loop;
+  while ( millis-- )
+       _delay_ms(1);
+}
+
+#include <avr/pgmspace.h>
+
+#define printf(format, ...) printf_P(PSTR(format), ## __VA_ARGS__)
+#define sprintf(wh, format, ...) sprintf_P(wh, PSTR(format), ## __VA_ARGS__)
+
+/*!
+       Define pin accessors.
+       given a pin name, port, bit number and mask (how many bits it takes) this macro
+       defines a set of inline accessors to set/clear/read the pin
+ */
+#define PIN_DEFINE(__name, __port, __pin, __mask) \
+       enum { __name##_PIN = (__pin), __name##_MASK = (__mask << __pin) }; \
+       /* toggle pin in PORT */static inline void TOG_##__name() { PIN##__port ^= __mask << __pin; } \
+       /* Clear Pin */                 static inline void CLR_##__name() { PORT##__port &= ~(__mask << __pin); } \
+       /* Set pin to 1 */              static inline void SET_##__name() { PORT##__port |= (__mask << __pin); } \
+       /* Set pin to 0/1 */    static inline void SET_##__name##_V(uint8_t __val) { PORT##__port = (PORT##__port & ~(__mask << __pin)) | (__val << __pin); } \
+       /* Get pin value */             static inline uint8_t GET##__name() { return (PIN##__port >> __pin) & __mask; } \
+       /* Set pin direction */ static inline void DDR_##__name(uint8_t __val) { DDR##__port = (DDR##__port & ~(__mask << __pin)) | (__val << __pin); }
+
+#if VERBOSE
+#define V(w) w
+#else
+#define V(w)
+#endif
+
+#endif // __COMMON_H__
diff --git a/examples/board_clock_7seg/clock_7seg.c b/examples/board_clock_7seg/clock_7seg.c
new file mode 100644 (file)
index 0000000..370cab1
--- /dev/null
@@ -0,0 +1,348 @@
+/*
+  clock_7seg.c
+  
+  Copyright 2008, 2009 Michel Pollet <buserror@gmail.com>
+
+   This file is part of simavr.
+
+  simavr is free software: you can redistribute it and/or modify
+  it under the terms of the GNU General Public License as published by
+  the Free Software Foundation, either version 3 of the License, or
+  (at your option) any later version.
+
+  simavr 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 simavr.  If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <math.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <libgen.h>
+#if __APPLE__
+#include <GLUT/glut.h>
+#else
+#include <GL/glut.h>
+#endif
+#include <pthread.h>
+
+#include "sim_avr.h"
+#include "avr_ioport.h"
+#include "avr_spi.h"
+#include "avr_timer.h"
+#include "sim_elf.h"
+#include "sim_gdb.h"
+#include "sim_vcd_file.h"
+
+#include "button.h"
+#include "hc595.h"
+
+#define N_DIGITS 4
+#define ORIGIN_X 50.f
+#define ORIGIN_Y 50.f
+#define PITCH_X 320.f
+#define PITCH_Y 450.f
+#define WINDOW_X (ORIGIN_X + N_DIGITS * PITCH_X)
+#define WINDOW_Y (ORIGIN_Y + PITCH_Y)
+
+enum {
+  B_START = 0, B_STOP, B_RESET,
+  B_MAX
+};
+button_t button[B_MAX]; // Start/Stop/Reset
+volatile int do_button_press[B_MAX] = {0};
+avr_t * avr = NULL;
+avr_vcd_t vcd_file;
+hc595_t shifter;
+
+int display_flag = 0;
+volatile uint32_t  display_bits = 0;
+volatile uint8_t  display_pwm = 0;
+
+int window;
+
+#include "led_8seg.inc"
+#include "led_17seg.inc"
+
+/*
+ * called when the AVR has latched the 595
+ */
+void hc595_changed_hook(struct avr_irq_t * irq, uint32_t value, void * param)
+{
+  display_bits = value;
+  display_flag++;
+}
+
+/*
+ * called when the AVR has changed the display brightness
+ */
+void pwm_changed_hook(struct avr_irq_t * irq, uint32_t value, void * param)
+{
+  display_pwm = value;
+  display_flag++;
+}
+
+void displayCB(void)    /* function called whenever redisplay needed */
+{
+  // OpenGL rendering goes here...
+  //glClearColor(0.f, 0.f, 0.f, 0.f);
+  glClear(GL_COLOR_BUFFER_BIT);
+
+  //uint8_t pixel[4];
+  //glReadPixels(0, 0, 1, 1, GL_RGBA, GL_UNSIGNED_BYTE, pixel);
+  //printf("%d %d %d %d\n", pixel[0], pixel[1], pixel[2], pixel[3]);
+
+  // Set up modelview matrix
+  glMatrixMode(GL_MODELVIEW); // Select modelview matrix
+  glLoadIdentity(); // Start with an identity matrix
+
+  float color_on = (float)(0xff - display_pwm) / 15.0f;
+  float color_off = 0.1;
+  if (color_on < color_off)
+    color_on = color_off;
+
+  for (int di = 0; di < 4; di++) {
+    uint8_t digit = display_bits >> (di * 8);
+    
+    for (int i = 0; i < 8; i++) {  
+      glColor3f(0.f, digit & (1 << i) ? color_on : color_off, 0.f);
+      float x = ORIGIN_X + di * PITCH_X;
+      float y = ORIGIN_Y;
+
+      glBegin(GL_POLYGON); //GL_LINE_STRIP);
+      int end = led_8seg_ptr[i + 1];
+      for (int j = led_8seg_ptr[i]; j < end; ++j)
+        glVertex2f(x + led_8seg[j][0], y + led_8seg[j][1]);
+      glEnd();
+    }
+  }
+
+  glutSwapBuffers();
+  //glFlush();        /* Complete any pending operations */
+}
+
+void keyCB(unsigned char key, int x, int y)  /* called on key press */
+{
+  if (key == 'q')
+    exit(0);
+  //static uint8_t buf[64];
+  switch (key) {
+    case 'q':
+    case 0x1f: // escape
+      exit(0);
+      break;
+    case '1' ... '3':
+      printf("Press %d\n", key-'1');
+      do_button_press[key-'1']++; // pass the message to the AVR thread
+      break;
+    case 'r':
+      printf("Starting VCD trace\n");
+      avr_vcd_start(&vcd_file);
+      break;
+    case 's':
+      printf("Stopping VCD trace\n");
+      avr_vcd_stop(&vcd_file);
+      break;
+  }
+}
+
+// gl timer. if the pin have changed states, refresh display
+void timerCB(int i)
+{
+  static int oldstate = -1;
+  // restart timer
+  glutTimerFunc(1000/64, timerCB, 0);
+
+  if (oldstate != display_flag) {
+    oldstate = display_flag;
+    glutPostRedisplay();
+  }
+}
+
+static void * avr_run_thread(void * ignore)
+{
+  int b_press[3] = {0};
+  
+  while (1) {
+    avr_run(avr);
+
+    for (int i = 0; i < 3; i++) {
+      if (do_button_press[i] != b_press[i]) {
+        b_press[i] = do_button_press[i];
+        printf("Button pressed %d\n", i);
+        button_press(&button[i], 100000);
+      }
+    }
+  }
+  return NULL;
+}
+
+
+int main(int argc, char *argv[])
+{
+  elf_firmware_t f;
+  const char * fname =  "atmega168_clock_7seg.axf";
+  //char path[256];
+
+//  sprintf(path, "%s/%s", dirname(argv[0]), fname);
+  //printf("Firmware pathname is %s\n", path);
+  elf_read_firmware(fname, &f);
+
+  printf("firmware %s f=%d mmcu=%s\n", fname, (int)f.frequency, f.mmcu);
+
+  avr = avr_make_mcu_by_name(f.mmcu);
+  if (!avr) {
+    fprintf(stderr, "%s: AVR '%s' not known\n", argv[0], f.mmcu);
+    exit(1);
+  }
+  avr_init(avr);
+  avr_load_firmware(avr, &f);
+
+  //
+  // initialize our 'peripherals'
+  //
+  hc595_init(avr, &shifter);
+  
+  button_init(avr, &button[B_START], "button.start");
+  avr_connect_irq(
+    button[B_START].irq + IRQ_BUTTON_OUT,
+    avr_io_getirq(avr, AVR_IOCTL_IOPORT_GETIRQ('C'), 0));
+  button_init(avr, &button[B_STOP], "button.stop");
+  avr_connect_irq(
+    button[B_STOP].irq + IRQ_BUTTON_OUT,
+    avr_io_getirq(avr, AVR_IOCTL_IOPORT_GETIRQ('B'), 1));
+  button_init(avr, &button[B_RESET], "button.reset");
+  avr_connect_irq(
+    button[B_RESET].irq + IRQ_BUTTON_OUT,
+    avr_io_getirq(avr, AVR_IOCTL_IOPORT_GETIRQ('B'), 0));
+
+  // connects the fake 74HC595 array to the pins
+  avr_irq_t * i_mosi = avr_io_getirq(avr, AVR_IOCTL_SPI_GETIRQ(0), SPI_IRQ_OUTPUT),
+      * i_reset = avr_io_getirq(avr, AVR_IOCTL_IOPORT_GETIRQ('D'), 4),
+      * i_latch = avr_io_getirq(avr, AVR_IOCTL_IOPORT_GETIRQ('D'), 7);
+  avr_connect_irq(i_mosi, shifter.irq + IRQ_HC595_SPI_BYTE_IN);
+  avr_connect_irq(i_reset, shifter.irq + IRQ_HC595_IN_RESET);
+  avr_connect_irq(i_latch, shifter.irq + IRQ_HC595_IN_LATCH);
+
+  avr_irq_t * i_pwm = avr_io_getirq(avr, AVR_IOCTL_TIMER_GETIRQ('0'), TIMER_IRQ_OUT_PWM0);
+  avr_irq_register_notify(
+    i_pwm,
+    pwm_changed_hook, 
+    NULL);  
+  avr_irq_register_notify(
+    shifter.irq + IRQ_HC595_OUT,
+    hc595_changed_hook, 
+    NULL);
+
+  // even if not setup at startup, activate gdb if crashing
+  avr->gdb_port = 1234;
+  if (0) {
+    //avr->state = cpu_Stopped;
+    avr_gdb_init(avr);
+  }
+
+  /*
+   *  VCD file initialization
+   *  
+   *  This will allow you to create a "wave" file and display it in gtkwave
+   *  Pressing "r" and "s" during the demo will start and stop recording
+   *  the pin changes
+   */
+  avr_vcd_init(avr, "gtkwave_output.vcd", &vcd_file, 10000 /* usec */);
+
+  avr_vcd_add_signal(&vcd_file, 
+    avr_get_interrupt_irq(avr, 7), 1 /* bit */ ,
+    "TIMER2_COMPA" );
+  avr_vcd_add_signal(&vcd_file, 
+    avr_get_interrupt_irq(avr, 17), 1 /* bit */ ,
+    "SPI_INT" );
+  avr_vcd_add_signal(&vcd_file, 
+    i_mosi, 8 /* bits */ ,
+    "MOSI" );
+
+  avr_vcd_add_signal(&vcd_file, 
+    i_reset, 1 /* bit */ ,
+    "595_RESET" );
+  avr_vcd_add_signal(&vcd_file, 
+    i_latch, 1 /* bit */ ,
+    "595_LATCH" );
+  avr_vcd_add_signal(&vcd_file, 
+    button[B_START].irq + IRQ_BUTTON_OUT, 1 /* bits */ ,
+    "start" );
+  avr_vcd_add_signal(&vcd_file, 
+    button[B_STOP].irq + IRQ_BUTTON_OUT, 1 /* bits */ ,
+    "stop" );
+  avr_vcd_add_signal(&vcd_file, 
+    button[B_RESET].irq + IRQ_BUTTON_OUT, 1 /* bits */ ,
+    "reset" );
+
+  avr_vcd_add_signal(&vcd_file, 
+    shifter.irq + IRQ_HC595_OUT, 32 /* bits */ ,
+    "HC595" );
+  avr_vcd_add_signal(&vcd_file, 
+    i_pwm, 8 /* bits */ ,
+    "PWM" );
+
+  // 'raise' it, it's a "pullup"
+  avr_raise_irq(button[B_START].irq + IRQ_BUTTON_OUT, 1);
+  avr_raise_irq(button[B_STOP].irq + IRQ_BUTTON_OUT, 1);
+  avr_raise_irq(button[B_RESET].irq + IRQ_BUTTON_OUT, 1);
+
+  printf( "Demo : This is a real world firmware, a 'stopwatch'\n"
+      "   timer that can count up to 99 days. It features a PWM control of the\n"
+      "   brightness, blinks the dots, displays the number of days spent and so on.\n\n"
+      "   Press '1' to press the 'start' button\n"
+      "   Press '2' to press the 'stop' button\n"
+      "   Press '3' to press the 'reset' button\n"
+      "   Press 'q' to quit\n\n"
+      "   Press 'r' to start recording a 'wave' file - with a LOT of data\n"
+      "   Press 's' to stop recording\n"
+      "  + Make sure to watch the brightness dim once you stop the timer\n\n"
+      );
+
+  /*
+   * OpenGL init, can be ignored
+   */
+  glutInit(&argc, argv);    /* initialize GLUT system */
+
+#if 1
+  glutInitDisplayMode(GLUT_RGBA | GLUT_DOUBLE);
+  glutInitWindowSize((int)roundf(WINDOW_X), (int)roundf(WINDOW_Y));
+  window = glutCreateWindow("Press 0, 1, 2 or q");  /* create window */
+#else
+  glutInitDisplayMode(GLUT_RGBA | GLUT_ALPHA | GLUT_DOUBLE);
+  glutInitWindowSize((int)roundf(WINDOW_X), (int)roundf(WINDOW_Y));
+  window = glutCreateWindow("Press 0, 1, 2 or q");  /* create window */
+
+  glEnable(GL_BLEND);
+  //glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
+  glBlendFunc(GL_SRC_ALPHA_SATURATE, GL_ONE);
+  glDisable(GL_DEPTH_TEST);
+  //glEnable(GL_LINE_SMOOTH);
+  //glHint(GL_LINE_SMOOTH_HINT, GL_NICEST);
+  //glLineWidth(4.f);
+  glEnable(GL_POLYGON_SMOOTH);
+  glHint(GL_POLYGON_SMOOTH_HINT, GL_NICEST);
+#endif
+
+  // Set up projection matrix
+  glMatrixMode(GL_PROJECTION); // Select projection matrix
+  glLoadIdentity(); // Start with an identity matrix
+  glOrtho(0.f, WINDOW_X, 0.f, WINDOW_Y, 0.f, 10.f);
+  //glScalef(1.f, -1.f, 1.f);
+  //glTranslatef(0.f, -WINDOW_Y, 0.f);
+
+  glutDisplayFunc(displayCB);    /* set window's display callback */
+  glutKeyboardFunc(keyCB);    /* set window's key callback */
+  glutTimerFunc(1000 / 24, timerCB, 0);
+
+  // the AVR run on it's own thread. it even allows for debugging!
+  pthread_t run;
+  pthread_create(&run, NULL, avr_run_thread, NULL);
+
+  glutMainLoop();
+}
diff --git a/examples/board_clock_7seg/led_17seg.py b/examples/board_clock_7seg/led_17seg.py
new file mode 100755 (executable)
index 0000000..5990677
--- /dev/null
@@ -0,0 +1,63 @@
+#!/usr/bin/env python3
+
+import math
+import svg.path
+
+# extract the following from the idiotic header that inkscape puts in the svg:
+#   width="200"
+#   height="400"
+#   viewBox="0 0 52.916666 105.83333"
+scale_x = 200. / 52.916666
+scale_y = -400. / 105.83333
+origin_x = 0.
+origin_y = 400.
+
+# extract below using:
+#   sed -ne 's/.* d=\(.*\)/  \1,/p' <led_17seg.svg
+# then reorder segments manually
+paths = [
+  "m 25.135417,47.625005 v 10.58333 H 6.6145817 L -1.6000005e-6,52.916665 6.6145817,47.625005 Z",
+  "M 31.75,7.9375003 V 44.979167 H 21.166667 V 7.9375003 Z",
+  "M 25.135417,-5.2916657 V 5.2916673 H 7.27604 l -7.9374999,-7.9375 1.0583333,-1.058333 1.0583333,-0.79375 1.0583332,-0.529167 1.0583333,-0.264583 z",
+  "m -2.6458348,-0.6614577 7.9374998,7.9375 V 44.979167 l -7.6067707,6.085417 -1.3229167,-1.05833 -0.8598958,-1.05834 -0.5291666,-1.32291 -0.2645834,-1.058338 2e-7,-42.9947907 0.2645833,-1.058333 0.5291667,-1.058334 0.7937499,-1.058333 z",
+  "M 9.5249976,7.9375003 18.520832,26.458332 v 18.520833 h -1.5875 l -8.9958342,-18.520833 2e-7,-18.5208317 z",
+  "m 27.781248,47.625007 v 10.58333 h 18.520834 l 6.614582,-5.29167 -6.614582,-5.29166 z",
+  "m 27.781248,-5.2916637 v 10.583333 h 17.859376 l 7.937499,-7.9375 -1.058333,-1.058333 -1.058334,-0.79375 -1.058332,-0.529167 -1.058333,-0.264583 z",
+  "m 55.562498,-0.6614557 -7.937499,7.9375 V 44.979169 l 7.60677,6.085417 1.322916,-1.058329 0.859896,-1.05834 0.529167,-1.32291 0.264583,-1.058338 V 3.5718773 l -0.264583,-1.058333 -0.529167,-1.058334 -0.79375,-1.058333 z",
+  "M 43.391666,7.9375023 34.395833,26.458334 v 18.520833 h 1.587499 L 44.979166,26.458334 V 7.9375023 Z",
+  "M 31.75,97.895828 V 60.854166 H 21.166667 v 37.041662 z",
+  "M 25.135417,111.12499 V 100.54166 H 7.2760392 l -7.9375,7.9375 1.058333,1.05833 1.058334,0.79375 1.058333,0.52917 1.058333,0.26458 z",
+  "m -2.6458358,106.49478 7.9375,-7.937495 V 60.854166 l -7.606771,-6.085417 -1.322916,1.05833 -0.859896,1.05834 -0.529167,1.32291 -0.264583,1.058337 v 42.994784 l 0.264583,1.05833 0.529167,1.05834 0.79375,1.05833 z",
+  "m 9.5249976,97.895828 8.9958344,-18.52083 v -18.52083 h -1.5875 l -8.9958348,18.52083 v 18.52083 z",
+  "m 27.781248,111.12499 v -10.58333 h 17.859376 l 7.937499,7.93749 -1.058333,1.05834 -1.058334,0.79375 -1.058332,0.52916 -1.058333,0.26459 z",
+  "M 55.562498,106.49478 47.624999,98.557283 V 60.854164 l 7.60677,-6.085417 1.322916,1.05833 0.859896,1.05834 0.529167,1.32291 0.264583,1.058337 v 42.994786 l -0.264583,1.05833 -0.529167,1.05833 -0.79375,1.05834 z",
+  "m 43.391666,97.895826 -8.995833,-18.52083 v -18.52083 h 1.587499 l 8.995834,18.52083 v 18.52083 z",
+  "m 69.849999,100.54166 1.852083,0.79375 1.5875,1.5875 0.79375,1.85209 v 2.11666 l -0.79375,1.85209 -1.5875,1.5875 -1.852083,0.79375 -2.116667,0 -1.852083,-0.79375 -1.5875,-1.5875 -0.79375,-1.85209 0,-2.11666 0.79375,-1.85208 1.5875,-1.5875 1.852083,-0.79376 z",
+]
+
+led_17seg = []
+led_17seg_ptr = [0]
+slant = math.tan(10. * math.pi / 180.)
+for i in paths:
+  for j in svg.path.parse_path(i):
+    p = j.point(1.)
+    x = round(origin_x + p.real * scale_x, 2)
+    y = round(origin_y + p.imag * scale_y, 2)
+    x += slant * y
+    led_17seg.append((x, y))
+  led_17seg_ptr.append(len(led_17seg))
+
+print(
+  'float led_17seg[][2] = {{{0:s}\n}};'.format(
+    ','.join(
+      [f'\n  {{{x:.8f}f, {y:.8f}f}}' for x, y in led_17seg]
+    )
+  )
+)
+print(
+  'int led_17seg_ptr[] = {{{0:s}}};'.format(
+    ', '.join(
+      [str(i) for i in led_17seg_ptr]
+    )
+  )
+)
diff --git a/examples/board_clock_7seg/led_17seg.svg b/examples/board_clock_7seg/led_17seg.svg
new file mode 100644 (file)
index 0000000..1b20c79
--- /dev/null
@@ -0,0 +1,150 @@
+<?xml version="1.0" encoding="UTF-8" standalone="no"?>
+<!-- Created with Inkscape (http://www.inkscape.org/) -->
+
+<svg
+   width="200"
+   height="400"
+   viewBox="0 0 52.916666 105.83333"
+   version="1.1"
+   id="svg5"
+   inkscape:version="1.1.2 (1:1.1+202202050950+0a00cf5339)"
+   sodipodi:docname="led_17seg.svg"
+   xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
+   xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
+   xmlns="http://www.w3.org/2000/svg"
+   xmlns:svg="http://www.w3.org/2000/svg">
+  <sodipodi:namedview
+     id="namedview7"
+     pagecolor="#ffffff"
+     bordercolor="#666666"
+     borderopacity="1.0"
+     inkscape:pageshadow="2"
+     inkscape:pageopacity="0.0"
+     inkscape:pagecheckerboard="0"
+     inkscape:document-units="mm"
+     showgrid="true"
+     units="px"
+     width="100px"
+     inkscape:zoom="0.73940795"
+     inkscape:cx="252.90504"
+     inkscape:cy="387.47217"
+     inkscape:window-width="1920"
+     inkscape:window-height="1009"
+     inkscape:window-x="0"
+     inkscape:window-y="0"
+     inkscape:window-maximized="1"
+     inkscape:current-layer="layer1">
+    <inkscape:grid
+       type="xygrid"
+       id="grid824"
+       spacingx="0.26458333"
+       spacingy="0.26458333"
+       empspacing="4" />
+  </sodipodi:namedview>
+  <defs
+     id="defs2" />
+  <g
+     inkscape:label="Layer 1"
+     inkscape:groupmode="layer"
+     id="layer1">
+    <ellipse
+       style="fill:#ff000f;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       id="path10970"
+       ry="5.2916627"
+       rx="5.291666"
+       cy="105.83332"
+       cx="68.791672" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 25.135417,47.625005 v 10.58333 H 6.6145817 L -1.6000005e-6,52.916665 6.6145817,47.625005 Z"
+       id="path928"
+       sodipodi:nodetypes="cccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="M 31.75,7.9375003 V 44.979167 H 21.166667 V 7.9375003 Z"
+       id="path928-93"
+       sodipodi:nodetypes="ccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="M 25.135417,-5.2916657 V 5.2916673 H 7.27604 l -7.9374999,-7.9375 1.0583333,-1.058333 1.0583333,-0.79375 1.0583332,-0.529167 1.0583333,-0.264583 z"
+       id="path928-9"
+       sodipodi:nodetypes="ccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m -2.6458348,-0.6614577 7.9374998,7.9375 V 44.979167 l -7.6067707,6.085417 -1.3229167,-1.05833 -0.8598958,-1.05834 -0.5291666,-1.32291 -0.2645834,-1.058338 2e-7,-42.9947907 0.2645833,-1.058333 0.5291667,-1.058334 0.7937499,-1.058333 z"
+       id="path928-3-7"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="M 9.5249976,7.9375003 18.520832,26.458332 v 18.520833 h -1.5875 l -8.9958342,-18.520833 2e-7,-18.5208317 z"
+       id="path928-3-7-5-6-1-8"
+       sodipodi:nodetypes="ccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 27.781248,47.625007 v 10.58333 h 18.520834 l 6.614582,-5.29167 -6.614582,-5.29166 z"
+       id="path928-3"
+       sodipodi:nodetypes="cccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 27.781248,-5.2916637 v 10.583333 h 17.859376 l 7.937499,-7.9375 -1.058333,-1.058333 -1.058334,-0.79375 -1.058332,-0.529167 -1.058333,-0.264583 z"
+       id="path928-9-7"
+       sodipodi:nodetypes="ccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 55.562498,-0.6614557 -7.937499,7.9375 V 44.979169 l 7.60677,6.085417 1.322916,-1.058329 0.859896,-1.05834 0.529167,-1.32291 0.264583,-1.058338 V 3.5718773 l -0.264583,-1.058333 -0.529167,-1.058334 -0.79375,-1.058333 z"
+       id="path928-3-7-5"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="M 43.391666,7.9375023 34.395833,26.458334 v 18.520833 h 1.587499 L 44.979166,26.458334 V 7.9375023 Z"
+       id="path928-3-7-5-6-1-8-3"
+       sodipodi:nodetypes="ccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="M 31.75,97.895828 V 60.854166 H 21.166667 v 37.041662 z"
+       id="path928-93-6"
+       sodipodi:nodetypes="ccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="M 25.135417,111.12499 V 100.54166 H 7.2760392 l -7.9375,7.9375 1.058333,1.05833 1.058334,0.79375 1.058333,0.52917 1.058333,0.26458 z"
+       id="path928-9-2"
+       sodipodi:nodetypes="ccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m -2.6458358,106.49478 7.9375,-7.937495 V 60.854166 l -7.606771,-6.085417 -1.322916,1.05833 -0.859896,1.05834 -0.529167,1.32291 -0.264583,1.058337 v 42.994784 l 0.264583,1.05833 0.529167,1.05834 0.79375,1.05833 z"
+       id="path928-3-7-9"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 9.5249976,97.895828 8.9958344,-18.52083 v -18.52083 h -1.5875 l -8.9958348,18.52083 v 18.52083 z"
+       id="path928-3-7-5-6-1-8-1"
+       sodipodi:nodetypes="ccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 27.781248,111.12499 v -10.58333 h 17.859376 l 7.937499,7.93749 -1.058333,1.05834 -1.058334,0.79375 -1.058332,0.52916 -1.058333,0.26459 z"
+       id="path928-9-7-7"
+       sodipodi:nodetypes="ccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="M 55.562498,106.49478 47.624999,98.557283 V 60.854164 l 7.60677,-6.085417 1.322916,1.05833 0.859896,1.05834 0.529167,1.32291 0.264583,1.058337 v 42.994786 l -0.264583,1.05833 -0.529167,1.05833 -0.79375,1.05834 z"
+       id="path928-3-7-5-0"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 43.391666,97.895826 -8.995833,-18.52083 v -18.52083 h 1.587499 l 8.995834,18.52083 v 18.52083 z"
+       id="path928-3-7-5-6-1-8-3-9"
+       sodipodi:nodetypes="ccccccc" />
+    <ellipse
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       id="path10968"
+       cx="69.717712"
+       cy="107.8177"
+       rx="0.92604166"
+       ry="1.984375" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 69.849999,100.54166 1.852083,0.79375 1.5875,1.5875 0.79375,1.85209 v 2.11666 l -0.79375,1.85209 -1.5875,1.5875 -1.852083,0.79375 -2.116667,0 -1.852083,-0.79375 -1.5875,-1.5875 -0.79375,-1.85209 0,-2.11666 0.79375,-1.85208 1.5875,-1.5875 1.852083,-0.79376 z"
+       id="path928-6-5-6"
+       sodipodi:nodetypes="ccccccccccccccccc" />
+  </g>
+</svg>
diff --git a/examples/board_clock_7seg/led_8seg.py b/examples/board_clock_7seg/led_8seg.py
new file mode 100755 (executable)
index 0000000..16bcf8b
--- /dev/null
@@ -0,0 +1,54 @@
+#!/usr/bin/env python3
+
+import math
+import svg.path
+
+# extract the following from the idiotic header that inkscape puts in the svg:
+#   width="200"
+#   height="400"
+#   viewBox="0 0 52.916666 105.83333"
+scale_x = 200. / 52.916666
+scale_y = -400. / 105.83333
+origin_x = 0.
+origin_y = 400.
+
+# extract below using:
+#   sed -ne 's/.* d=\(.*\)/  \1,/p' <led_8seg.svg
+# then reorder segments manually
+paths = [
+  "m 49.344789,-5.2916664 1.058333,0.2645833 1.058334,0.5291667 1.058333,0.7937499 1.058333,1.0583333 -7.937499,7.9374996 -38.364583,9e-7 -7.9374999,-7.9375 1.0583333,-1.058333 1.0583333,-0.79375 1.0583332,-0.529167 1.0583333,-0.264583 z", # A
+  "m 55.562498,-0.6614557 -7.937499,7.9375 V 44.979169 l 7.60677,6.085417 1.322916,-1.058329 0.859896,-1.05834 0.529167,-1.32291 0.264583,-1.058338 V 3.5718773 l -0.264583,-1.058333 -0.529167,-1.058334 -0.79375,-1.058333 z", # B
+  "M 55.562498,106.49478 47.624999,98.557283 V 60.854164 l 7.60677,-6.085417 1.322916,1.05833 0.859896,1.05834 0.529167,1.32291 0.264583,1.058337 v 42.994786 l -0.264583,1.05833 -0.529167,1.05833 -0.79375,1.05834 z", # C
+  "m 49.344789,111.12499 1.058333,-0.26458 1.058334,-0.52917 1.058333,-0.79375 1.058333,-1.05833 -7.937499,-7.9375 c 0,0 -30.138854,0 -38.3645838,0 l -7.9375,7.9375 1.058333,1.05833 1.058334,0.79375 1.058333,0.52917 1.058333,0.26458 z", # D
+  "m -2.6458358,106.49478 7.9375,-7.937495 V 60.854166 l -7.606771,-6.085417 -1.322916,1.05833 -0.859896,1.05834 -0.529167,1.32291 -0.264583,1.058337 v 42.994784 l 0.264583,1.05833 0.529167,1.05834 0.79375,1.05833 z", # E
+  "m -2.6458348,-0.6614577 7.9374998,7.9375 V 44.979167 l -7.6067707,6.085417 -1.3229167,-1.05833 -0.8598958,-1.05834 -0.5291666,-1.32291 -0.2645834,-1.058338 2e-7,-42.9947907 0.2645833,-1.058333 0.5291667,-1.058334 0.7937499,-1.058333 z", # F
+  "m 46.302082,47.624999 6.614584,5.291667 -6.614584,5.291663 -39.6875003,6e-6 L -1.6000005e-6,52.916665 6.6145817,47.625005 Z", # G
+  "m 69.849999,100.54166 1.852083,0.79375 1.5875,1.5875 0.79375,1.85209 v 2.11666 l -0.79375,1.85209 -1.5875,1.5875 -1.852083,0.79375 -2.116667,0 -1.852083,-0.79375 -1.5875,-1.5875 -0.79375,-1.85209 0,-2.11666 0.79375,-1.85208 1.5875,-1.5875 1.852083,-0.79376 z", # DP
+]
+
+led_8seg = []
+led_8seg_ptr = [0]
+slant = math.tan(10. * math.pi / 180.)
+for i in paths:
+  for j in svg.path.parse_path(i):
+    p = j.point(1.)
+    x = round(origin_x + p.real * scale_x, 2)
+    y = round(origin_y + p.imag * scale_y, 2)
+    x += slant * y
+    led_8seg.append((x, y))
+  led_8seg_ptr.append(len(led_8seg))
+
+print(
+  'float led_8seg[][2] = {{{0:s}\n}};'.format(
+    ','.join(
+      [f'\n  {{{x:.8f}f, {y:.8f}f}}' for x, y in led_8seg]
+    )
+  )
+)
+print(
+  'int led_8seg_ptr[] = {{{0:s}}};'.format(
+    ', '.join(
+      [str(i) for i in led_8seg_ptr]
+    )
+  )
+)
diff --git a/examples/board_clock_7seg/led_8seg.svg b/examples/board_clock_7seg/led_8seg.svg
new file mode 100644 (file)
index 0000000..8908215
--- /dev/null
@@ -0,0 +1,105 @@
+<?xml version="1.0" encoding="UTF-8" standalone="no"?>
+<!-- Created with Inkscape (http://www.inkscape.org/) -->
+
+<svg
+   width="200"
+   height="400"
+   viewBox="0 0 52.916666 105.83333"
+   version="1.1"
+   id="svg5"
+   inkscape:version="1.1.2 (1:1.1+202202050950+0a00cf5339)"
+   sodipodi:docname="led_8seg.svg"
+   xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
+   xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
+   xmlns="http://www.w3.org/2000/svg"
+   xmlns:svg="http://www.w3.org/2000/svg">
+  <sodipodi:namedview
+     id="namedview7"
+     pagecolor="#ffffff"
+     bordercolor="#666666"
+     borderopacity="1.0"
+     inkscape:pageshadow="2"
+     inkscape:pageopacity="0.0"
+     inkscape:pagecheckerboard="0"
+     inkscape:document-units="mm"
+     showgrid="true"
+     units="px"
+     width="100px"
+     inkscape:zoom="0.73940795"
+     inkscape:cx="179.87364"
+     inkscape:cy="387.47217"
+     inkscape:window-width="1920"
+     inkscape:window-height="1009"
+     inkscape:window-x="0"
+     inkscape:window-y="0"
+     inkscape:window-maximized="1"
+     inkscape:current-layer="layer1">
+    <inkscape:grid
+       type="xygrid"
+       id="grid824"
+       spacingx="0.13229166"
+       spacingy="0.13229166"
+       empspacing="4" />
+  </sodipodi:namedview>
+  <defs
+     id="defs2" />
+  <g
+     inkscape:label="Layer 1"
+     inkscape:groupmode="layer"
+     id="layer1">
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 49.344789,111.12499 1.058333,-0.26458 1.058334,-0.52917 1.058333,-0.79375 1.058333,-1.05833 -7.937499,-7.9375 c 0,0 -30.138854,0 -38.3645838,0 l -7.9375,7.9375 1.058333,1.05833 1.058334,0.79375 1.058333,0.52917 1.058333,0.26458 z"
+       id="path928-9-2"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 46.302082,47.624999 6.614584,5.291667 -6.614584,5.291663 -39.6875003,6e-6 L -1.6000005e-6,52.916665 6.6145817,47.625005 Z"
+       id="path928"
+       sodipodi:nodetypes="ccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 49.344789,-5.2916664 1.058333,0.2645833 1.058334,0.5291667 1.058333,0.7937499 1.058333,1.0583333 -7.937499,7.9374996 -38.364583,9e-7 -7.9374999,-7.9375 1.0583333,-1.058333 1.0583333,-0.79375 1.0583332,-0.529167 1.0583333,-0.264583 z"
+       id="path928-9"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <ellipse
+       style="fill:#ff000f;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       id="path10970"
+       ry="5.2916627"
+       rx="5.291666"
+       cy="105.83332"
+       cx="68.791672" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m -2.6458348,-0.6614577 7.9374998,7.9375 V 44.979167 l -7.6067707,6.085417 -1.3229167,-1.05833 -0.8598958,-1.05834 -0.5291666,-1.32291 -0.2645834,-1.058338 2e-7,-42.9947907 0.2645833,-1.058333 0.5291667,-1.058334 0.7937499,-1.058333 z"
+       id="path928-3-7"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 55.562498,-0.6614557 -7.937499,7.9375 V 44.979169 l 7.60677,6.085417 1.322916,-1.058329 0.859896,-1.05834 0.529167,-1.32291 0.264583,-1.058338 V 3.5718773 l -0.264583,-1.058333 -0.529167,-1.058334 -0.79375,-1.058333 z"
+       id="path928-3-7-5"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m -2.6458358,106.49478 7.9375,-7.937495 V 60.854166 l -7.606771,-6.085417 -1.322916,1.05833 -0.859896,1.05834 -0.529167,1.32291 -0.264583,1.058337 v 42.994784 l 0.264583,1.05833 0.529167,1.05834 0.79375,1.05833 z"
+       id="path928-3-7-9"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="M 55.562498,106.49478 47.624999,98.557283 V 60.854164 l 7.60677,-6.085417 1.322916,1.05833 0.859896,1.05834 0.529167,1.32291 0.264583,1.058337 v 42.994786 l -0.264583,1.05833 -0.529167,1.05833 -0.79375,1.05834 z"
+       id="path928-3-7-5-0"
+       sodipodi:nodetypes="ccccccccccccc" />
+    <ellipse
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       id="path10968"
+       cx="69.717712"
+       cy="107.8177"
+       rx="0.92604166"
+       ry="1.984375" />
+    <path
+       style="fill:#000000;fill-opacity:1;stroke-width:0.529167;paint-order:stroke fill markers;stop-color:#000000"
+       d="m 69.849999,100.54166 1.852083,0.79375 1.5875,1.5875 0.79375,1.85209 v 2.11666 l -0.79375,1.85209 -1.5875,1.5875 -1.852083,0.79375 -2.116667,0 -1.852083,-0.79375 -1.5875,-1.5875 -0.79375,-1.85209 0,-2.11666 0.79375,-1.85208 1.5875,-1.5875 1.852083,-0.79376 z"
+       id="path928-6-5-6"
+       sodipodi:nodetypes="ccccccccccccccccc" />
+  </g>
+</svg>
diff --git a/n.sh b/n.sh
new file mode 100755 (executable)
index 0000000..7ba53f4
--- /dev/null
+++ b/n.sh
@@ -0,0 +1,3 @@
+#!/bin/sh
+apt install libelf-dev gcc-avr binutils-avr avr-libc gdb-avr avrdude freeglut3-dev
+make install DESTDIR=$HOME