Commit 4854e70c0ebf7fccc35fe0fd4b25b7bd6ce727e3
authorMichel Pollet <buserror@gmail.com>
Thu, 17 Dec 2009 20:31:23 +0000 (20:31 +0000)
committerMichel Pollet <buserror@gmail.com>
Thu, 17 Dec 2009 20:31:23 +0000 (20:31 +0000)
This example is a real board firmware that was built and
works. The firmware was adapted lightly and now runs
perfectly in simavr. It's a "stopwatch" timer with a lot
of features.
The "board" generates a very complete waveform for a LOT
of interesting signals, like the 74HC595 latches, intetupts,
SPI activity and the lot.

This example is the crown jewel of simavr development so far,
because simavr was design with the goal of being able to simulate
one's own project, for real.

Signed-off-by: Michel Pollet <buserror@gmail.com>
8 files changed:
examples/board_timer_64led/Makefile [new file with mode: 0644]
examples/board_timer_64led/README [new file with mode: 0644]
examples/board_timer_64led/atmega168_timer_64led.c [new file with mode: 0644]
examples/board_timer_64led/atmega168_timer_64led.h [new file with mode: 0644]
examples/board_timer_64led/timer_64led.c [new file with mode: 0644]
examples/board_timer_64led/timer_led64_real.jpg [new file with mode: 0644]
examples/parts/hc595.c [new file with mode: 0644]
examples/parts/hc595.h [new file with mode: 0644]

diff --git a/examples/board_timer_64led/Makefile b/examples/board_timer_64led/Makefile
new file mode 100644 (file)
index 0000000..976db0f
--- /dev/null
@@ -0,0 +1,45 @@
+# 
+#      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/>.
+
+board= timer_64led
+firm_src = ${wildcard at*${board}.c}
+firmware = ${firm_src:.c=.axf}
+simavr = ../../
+
+IPATH = .
+IPATH += ../parts
+IPATH += ${simavr}/include
+IPATH += ${simavr}/simavr/sim
+
+VPATH = .
+VPATH += ../parts
+
+LDFLAGS += -lglut -lpthread
+
+all: obj ${firmware} ${board}
+
+include ${simavr}/Makefile.common
+
+${board} : ${OBJ}/button.o
+${board} : ${OBJ}/hc595.o
+${board} : ${OBJ}/${board}.o
+       @echo LD $@
+       @gcc -MD ${CFLAGS} -o $@ $^ $(LDFLAGS) ${simavr}/simavr/libsimavr.a
+
+clean:
+       rm -rf obj *.hex *.a *.axf ${board} *.vcd
diff --git a/examples/board_timer_64led/README b/examples/board_timer_64led/README
new file mode 100644 (file)
index 0000000..6378f98
--- /dev/null
@@ -0,0 +1,21 @@
+
+timer_64led
+(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 6 LEDs. 3 Buttons
+provite 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_timer_64led/atmega168_timer_64led.c b/examples/board_timer_64led/atmega168_timer_64led.c
new file mode 100644 (file)
index 0000000..23a11db
--- /dev/null
@@ -0,0 +1,520 @@
+/*
+       atmega168_timer_64led.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_timer_64led.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);
+    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;
+       }
+}
+
+/*
+                       0x01 0x01
+               0x20            0x02
+               0x20            0x02
+                       0x40 0x40
+               0x10            0x04
+               0x10            0x04
+                       0x08 0x08
+  */
+const uint8_t  digits2led[10]= {
+       0x3f, 0x06, 0x5b, 79, 102, 109, 125, 7, 0x7f, 111
+};
+
+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 cia the interupts, we start counting. If the 'different' key(s) stays the same for
+                       50ms, we declare it an 'event' and update the internsl 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_timer_64led/atmega168_timer_64led.h b/examples/board_timer_64led/atmega168_timer_64led.h
new file mode 100644 (file)
index 0000000..935b506
--- /dev/null
@@ -0,0 +1,62 @@
+/*
+       atmega168_timer_64led.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_timer_64led/timer_64led.c b/examples/board_timer_64led/timer_64led.c
new file mode 100644 (file)
index 0000000..5fa73aa
--- /dev/null
@@ -0,0 +1,356 @@
+/*
+       timer_64led.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 <stdlib.h>
+#include <stdio.h>
+#include <libgen.h>
+
+#include <GL/glut.h>
+#include <pthread.h>
+
+#include "sim_avr.h"
+#include "avr_ioport.h"
+#include "avr_spi.h"
+#include "avr_timer8.h"
+#include "sim_elf.h"
+#include "sim_gdb.h"
+#include "sim_vcd_file.h"
+
+#include "button.h"
+#include "hc595.h"
+
+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;
+
+float pixsize = 16;
+int window;
+
+/*
+ * 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...
+       glClear(GL_COLOR_BUFFER_BIT);
+
+       // Set up modelview matrix
+       glMatrixMode(GL_MODELVIEW); // Select modelview matrix
+       glLoadIdentity(); // Start with an identity matrix
+
+       float grid = pixsize;
+       float size = grid * 0.8;
+       float color_on = (float)(0xff - display_pwm) / 15.0f;
+       float color_off = 0.1;
+       if (color_on < color_off)
+               color_on = color_off;
+
+       glTranslatef(pixsize / 2.25f, pixsize / 1.8f, 0);
+       
+    glBegin(GL_QUADS);
+       
+       for (int di = 0; di < 4; di++) {
+               uint8_t digit = display_bits >> (di * 8);
+               
+               for (int i = 0; i < 8; i++) {   
+                       glColor3f(0,0, digit & (1 << i) ? color_on : color_off);
+                       float dx = ((di * 5.5)) * pixsize, dy = 0*pixsize;
+                       switch (i) {
+                               case 3:
+                                       dy += 3.0f * pixsize;
+                               case 6:
+                                       dy += 3.0f * pixsize;
+                               case 0:
+                                       dx += 1.0f * pixsize;
+                                       glVertex2f(dx + size, dy + size); glVertex2f(dx, dy + size); glVertex2f(dx, dy); glVertex2f(dx + size, dy);
+                                       dx += 1.0f * pixsize;
+                                       glVertex2f(dx + size, dy + size); glVertex2f(dx, dy + size); glVertex2f(dx, dy); glVertex2f(dx + size, dy);
+                                       break;
+                               case 7: // dot!
+                                       dx += 4.25 * pixsize;
+                                       switch (di) {
+                                               case 0:
+                                               case 3:
+                                                       dy += 6.25 * pixsize;
+                                                       break;
+                                               case 1:
+                                                       dy += 2 * pixsize;
+                                                       break;
+                                               case 2:
+                                                       dy += 4 * pixsize;
+                                                       dx -= 5.50 * pixsize;
+                                                       break;
+                                       }
+                                                       
+                                       glVertex2f(dx + size, dy + size); glVertex2f(dx, dy + size); glVertex2f(dx, dy); glVertex2f(dx + size, dy);                                     
+                                       break;
+                               default:
+                                       if (i == 1 || i == 2)
+                                               dx += 3.0f * pixsize;
+                                       if (i == 4 || i == 2)
+                                               dy += 4.0f * pixsize;
+                                       else
+                                               dy += 1.0f * pixsize;                                   
+                                       glVertex2f(dx + size, dy + size); glVertex2f(dx, dy + size); glVertex2f(dx, dy); glVertex2f(dx + size, dy);
+                                       dy += 1.0f * pixsize;
+                                       glVertex2f(dx + size, dy + size); glVertex2f(dx, dy + size); glVertex2f(dx, dy); glVertex2f(dx + size, dy);
+                                       break;
+                       }
+               }
+       }
+
+    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);
+                       }
+               }
+       }
+}
+
+
+int main(int argc, char *argv[])
+{
+       elf_firmware_t f;
+       const char * fname =  "atmega168_timer_64led.axf";
+       char path[256];
+
+       sprintf(path, "%s/%s", dirname(argv[0]), fname);
+       printf("Firmware pathname is %s\n", path);
+       elf_read_firmware(path, &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' now known\n", argv[0], f.mmcu);
+               exit(1);
+       }
+       avr_init(avr);
+       avr_load_firmware(avr, &f);
+
+       //
+       // initialize our 'peripherals'
+       //
+       hc595_init(&shifter);
+       
+       button_init(avr, &button[B_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]);
+       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]);
+       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_TIMER8_GETIRQ('0'), TIMER8_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_interupt_irq(avr, 7), 1 /* bit */ ,
+               "TIMER2_COMPA" );
+       avr_vcd_add_signal(&vcd_file, 
+               avr_get_interupt_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 '0' to press the 'start' button\n"
+                       "   Press '1' to press the 'stop' button\n"
+                       "   Press '2' 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 */
+
+
+       int w = 22, h = 8;
+       
+       glutInitDisplayMode(GLUT_RGB | GLUT_DOUBLE);
+       glutInitWindowSize(w * pixsize, h * pixsize);           /* width=400pixels height=500pixels */
+       window = glutCreateWindow("Press 0, 1, 2 or q");        /* create window */
+
+       // Set up projection matrix
+       glMatrixMode(GL_PROJECTION); // Select projection matrix
+       glLoadIdentity(); // Start with an identity matrix
+       glOrtho(0, w * pixsize, 0, h * pixsize, 0, 10);
+       glScalef(1,-1,1);
+       glTranslatef(0, -1 * h * pixsize, 0);
+
+       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_timer_64led/timer_led64_real.jpg b/examples/board_timer_64led/timer_led64_real.jpg
new file mode 100644 (file)
index 0000000..cfffc0a
Binary files /dev/null and b/examples/board_timer_64led/timer_led64_real.jpg differ
diff --git a/examples/parts/hc595.c b/examples/parts/hc595.c
new file mode 100644 (file)
index 0000000..7d9e5e0
--- /dev/null
@@ -0,0 +1,74 @@
+/*
+       hc595.c
+
+       This defines a sample for a very simple "peripheral" 
+       that can talk to an AVR core.
+       It is in fact a bit more involved than strictly necessary,
+       but is made to demonstrante a few useful features that are
+       easy to use.
+       
+       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 <stdlib.h>
+#include <stdio.h>
+#include "hc595.h"
+
+/*
+ * called when a SPI byte is sent
+ */
+static void hc595_spi_in_hook(struct avr_irq_t * irq, uint32_t value, void * param)
+{
+       hc595_t * p = (hc595_t*)param;
+       // send "old value" to any chained one..
+       avr_raise_irq(p->irq + IRQ_HC595_SPI_BYTE_OUT, p->value);       
+       p->value = (p->value << 8) | (value & 0xff);
+}
+
+/*
+ * called when a LATCH signal is sent
+ */
+static void hc595_latch_hook(struct avr_irq_t * irq, uint32_t value, void * param)
+{
+       hc595_t * p = (hc595_t*)param;
+       if (irq->value && !value) {     // falling edge
+               p->latch = p->value;
+               avr_raise_irq(p->irq + IRQ_HC595_OUT, p->latch);
+       }
+}
+
+/*
+ * called when a RESET signal is sent
+ */
+static void hc595_reset_hook(struct avr_irq_t * irq, uint32_t value, void * param)
+{
+       hc595_t * p = (hc595_t*)param;
+       if (irq->value && !value)       // falling edge
+               p->latch = p->value = 0;
+}
+
+void hc595_init(hc595_t *p)
+{
+       p->irq = avr_alloc_irq(0, IRQ_HC595_COUNT);
+       avr_irq_register_notify(p->irq + IRQ_HC595_SPI_BYTE_IN, hc595_spi_in_hook, p);
+       avr_irq_register_notify(p->irq + IRQ_HC595_IN_LATCH, hc595_latch_hook, p);
+       avr_irq_register_notify(p->irq + IRQ_HC595_IN_RESET, hc595_reset_hook, p);
+       
+       p->latch = p->value = 0;
+}
+
diff --git a/examples/parts/hc595.h b/examples/parts/hc595.h
new file mode 100644 (file)
index 0000000..22d5844
--- /dev/null
@@ -0,0 +1,57 @@
+/*
+       hc595.h
+
+       This defines a sample for a very simple "peripheral" 
+       that can talk to an AVR core.
+       It is in fact a bit more involved than strictly necessary,
+       but is made to demonstrante a few useful features that are
+       easy to use.
+       
+       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 __HC595_H__
+#define __HC595_H__
+
+#include "sim_irq.h"
+
+/*
+ * this one is quite fun, it simulated a 74HC595 shift register
+ * driven by an SPI signal.
+ * For the interest of the simulation, they can be chained, but 
+ * for practicality sake the shift register is kept 32 bits
+ * wide so it acts as 4 of them "daisy chained" already. 
+ */
+enum {
+       IRQ_HC595_SPI_BYTE_IN = 0,      // if hooked to a byte based SPI IRQ
+       IRQ_HC595_SPI_BYTE_OUT,         // to chain them !!
+       IRQ_HC595_IN_LATCH,
+       IRQ_HC595_IN_RESET,
+       IRQ_HC595_OUT,                          // when latched, output on this IRQ
+       IRQ_HC595_COUNT
+};
+
+typedef struct hc595_t {
+       avr_irq_t *     irq;            // irq list
+       uint32_t        latch;          // value "on the pins"
+       uint32_t        value;          // value shifted in
+} hc595_t;
+
+void hc595_init(hc595_t *p);
+
+#endif