summaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
-rw-r--r--.gitignore3
-rw-r--r--Readme.txt21
-rw-r--r--firmware/Makefile19
-rw-r--r--firmware/bootloaderconfig.h95
-rw-r--r--firmware/crt1.S107
-rw-r--r--firmware/libs-device/osccal.c178
-rw-r--r--firmware/libs-device/osccal.h34
-rw-r--r--firmware/libs-device/osccalASM.S228
-rw-r--r--firmware/main.c320
-rw-r--r--firmware/releases/micronucleus-1.10.hex121
-rw-r--r--firmware/releases/micronucleus-1.10_LEDonPB1.hex122
-rw-r--r--firmware/releases/release notes.txt36
-rw-r--r--firmware/usbconfig.h17
-rw-r--r--firmware/usbdrv/Changelog.txt21
-rw-r--r--firmware/usbdrv/CommercialLicense.txt10
-rw-r--r--firmware/usbdrv/USB-ID-FAQ.txt6
-rw-r--r--firmware/usbdrv/USB-IDs-for-free.txt16
-rw-r--r--firmware/usbdrv/asmcommon.inc1
-rw-r--r--firmware/usbdrv/oddebug.c1
-rw-r--r--firmware/usbdrv/oddebug.h1
-rw-r--r--firmware/usbdrv/usbconfig-prototype.h10
-rw-r--r--firmware/usbdrv/usbdrv.c31
-rw-r--r--firmware/usbdrv/usbdrv.h37
-rw-r--r--firmware/usbdrv/usbdrvasm.S1
-rw-r--r--firmware/usbdrv/usbdrvasm.asm1
-rw-r--r--firmware/usbdrv/usbdrvasm12.inc45
-rw-r--r--firmware/usbdrv/usbdrvasm128.inc1
-rw-r--r--firmware/usbdrv/usbdrvasm15.inc1
-rw-r--r--firmware/usbdrv/usbdrvasm16.inc1
-rw-r--r--firmware/usbdrv/usbdrvasm18-crc.inc1
-rw-r--r--firmware/usbdrv/usbdrvasm20.inc1
-rw-r--r--firmware/usbdrv/usbportability.h1
32 files changed, 1089 insertions, 399 deletions
diff --git a/.gitignore b/.gitignore
index 4f45dcc..23e53ad 100644
--- a/.gitignore
+++ b/.gitignore
@@ -10,8 +10,11 @@ firmware/main.bin
firmware/main.c.lst
firmware/main.map
firmware/main.o
+firmware/crt1.o
+firmware/main.lss
firmware/usbdrv/oddebug.c.lst
firmware/main.hex
firmware/libs-device/osccal.o
+firmware/libs-device/osccalASM.o
firmware/usbdrv/oddebug.o
firmware/usbdrv/usbdrvasm.o
diff --git a/Readme.txt b/Readme.txt
index b1c696f..051e54c 100644
--- a/Readme.txt
+++ b/Readme.txt
@@ -1,6 +1,7 @@
-micronucleus tiny85
-===================
-Micronucleus is a bootloader designed for AVR tiny 85 chips with a minimal usb interface, cross platform libusb-based program upload tool, and a strong emphasis on bootloader compactness. The project aims to release a 2.0kb usb bootloader, and is nearly there, with recent builds at 2.07kb. By using the tinyvector mechanism designed by Embedded Creations in their USBaspLoader-tiny85 project, combined with the simplicity of Objective Development's bootloadHID and a unique bare bones usb protocol, Micronucleus is the smallest usb bootloader available for tiny85 at the time of writing.
+
+Micronucleus
+=============
+Micronucleus is a bootloader designed for AVR tiny 85 chips with a minimal usb interface, cross platform libusb-based program upload tool, and a strong emphasis on bootloader compactness. The project aims to release a 2.0kb usb bootloader, and has reached this goal with the latest release. By using the tinyvector mechanism designed by Embedded Creations in their USBaspLoader-tiny85 project, combined with the simplicity of Objective Development's bootloadHID and a unique bare bones usb protocol, Micronucleus is the smallest usb bootloader available for tiny85 at the time of writing.
Micronucleus adds a small amount of delay to the Pin Change interrupt in user applications, but this latency is low enough to not interfere with V-USB applications. Once bootloaded, an ISP or HVSP programmer can disable the reset pin, offering an extra pin for GPIO and ADC use! After disabling the reset pin functionality, of course you will no longer be able to use ISP programmers with the chip, but that's okay because we made a neat 'upgrade' program. The Upgrade program takes a compiled bootloader hex file and packs it in to an AVR program. You upload the 'upgrade' program via an existing micronucleus installation, any other bootloader, or via ISP or HVSP programmer, and once uploaded the upgrade program runs and writes over the bootloader and then installs a trampoline over it's own interrupt vector table, then reboots, launching the new bootloader. In this way users can change their bootloader to have bugfixes or different configurations like the 'jumper' versions without needing any programming tools.
@@ -8,6 +9,20 @@ tiny85 does not offer any hardware bootloading support, and does not protect the
Micronucleus is now widely installed on over 40,000 Digispark devices from Digistump - a tiny unofficial arduino device, so you can be confident that micronucleus will be well supported in the future. Micronucleus is now also the recommended bootloader for Ihsan Kehribar's wonderful LittleWire devices, and can be successfully installed on to existing LittleWire's by uploading the 'upgrade' program via the old serial bootloader, then uploading the littlewire firmware via the micronucleus command line upload tool.
+Changes
+=======
+
+This is release 1.10. Please use this at your own risk. The last official release for the DigiSpark is v1.06, which can be found here: https://github.com/micronucleus/micronucleus/tree/v1.06
+
+Changes compared to v1.06:
+ • Major size optimization and code reorganization.
+ • The size was reduced to 1878 bytes, allowing 256 bytes more user space.
+ • The bootloader will disconnect from USB on exit.
+
+See release notes (/firmware/releases/release notes.txt) for details.
+
+@cpldcpu - Dec 15th, 2013
+
----------------------------------------------------------------------------------
==================================================================================
!!%$!^%%$!#%$@#!%$@!$#@!%$#@%!#@%$!@$%#@!$%%!$#^&%$!%(*$!^%#!$@!#%$*^%!!&^%!%@$#!^
diff --git a/firmware/Makefile b/firmware/Makefile
index 8dfba5d..0905d0a 100644
--- a/firmware/Makefile
+++ b/firmware/Makefile
@@ -24,7 +24,7 @@ LOCKOPT = -U lock:w:0x2f:m
# - for the size of your device (8kb = 1024 * 8 = 8192) subtract above value 2124... = 6068
# - How many pages in is that? 6068 / 64 (tiny85 page size in bytes) = 94.8125
# - round that down to 94 - our new bootloader address is 94 * 64 = 6016, in hex = 1780
-BOOTLOADER_ADDRESS = 1780
+BOOTLOADER_ADDRESS = 1880
PROGRAMMER = -c USBasp
# PROGRAMMER contains AVRDUDE options to address your programmer
@@ -148,12 +148,13 @@ CC = avr-gcc
# Options:
DEFINES = -DBOOTLOADER_ADDRESS=0x$(BOOTLOADER_ADDRESS) #-DDEBUG_LEVEL=2
# Remove the -fno-* options when you use gcc 3, it does not understand them
-CFLAGS = -Wall -Os -fno-move-loop-invariants -fno-tree-scev-cprop -fno-inline-small-functions -I. -Ilibs-device -mmcu=$(DEVICE) -DF_CPU=$(F_CPU) $(DEFINES)
-LDFLAGS = -Wl,--relax,--gc-sections -Wl,--section-start=.text=$(BOOTLOADER_ADDRESS),-Map=main.map
+#
+CFLAGS = -g2 -nostartfiles -ffunction-sections -fdata-sections -fpack-struct -Wall -Os -fno-inline-small-functions -fno-move-loop-invariants -fno-tree-scev-cprop -I. -Ilibs-device -mmcu=$(DEVICE) -DF_CPU=$(F_CPU) $(DEFINES)
+LDFLAGS = -Wl,--relax,--section-start=.text=$(BOOTLOADER_ADDRESS),-Map=main.map,--section-start=.zerotable=0
-OBJECTS = usbdrv/usbdrvasm.o usbdrv/oddebug.o main.o
-OBJECTS += libs-device/osccal.o
+OBJECTS = crt1.o usbdrv/usbdrvasm.o usbdrv/oddebug.o main.o
+OBJECTS += libs-device/osccalASM.o
# symbolic targets:
all: main.hex
@@ -171,7 +172,7 @@ all: main.hex
$(CC) $(CFLAGS) -S $< -o $@
flash: all
- $(AVRDUDE) -U flash:w:main.hex:i
+ $(AVRDUDE) -U flash:w:main.hex:i -B 10
readflash:
$(AVRDUDE) -U flash:r:read.hex:i
@@ -189,7 +190,7 @@ read_fuses:
$(UISP) --rd_fuses
clean:
- rm -f main.hex main.bin main.c.lst main.map *.o usbdrv/*.o main.s usbdrv/oddebug.s usbdrv/usbdrv.s libs-device/osccal.o
+ rm -f main.hex main.bin main.c.lst main.map *.o usbdrv/*.o main.s usbdrv/oddebug.s usbdrv/usbdrv.s libs-device/osccalASM.o *.lss
# file targets:
main.bin: $(OBJECTS)
@@ -197,11 +198,11 @@ main.bin: $(OBJECTS)
main.hex: main.bin
rm -f main.hex main.eep.hex
- avr-objcopy -j .text -j .data -O ihex main.bin main.hex
+ avr-objcopy -j .text -j .zerotable -j .data -O ihex main.bin main.hex
avr-size main.hex
disasm: main.bin
- avr-objdump -d main.bin
+ avr-objdump -d -S main.bin >main.lss
cpp:
$(CC) $(CFLAGS) -E main.c
diff --git a/firmware/bootloaderconfig.h b/firmware/bootloaderconfig.h
index 3133368..e1b2a4c 100644
--- a/firmware/bootloaderconfig.h
+++ b/firmware/bootloaderconfig.h
@@ -133,6 +133,7 @@ these macros are defined, the boot loader uses them.
* programmer closes the connection to the device. Costs ~36 bytes.
* Required for TINY85MODE
*/
+
//#define HAVE_CHIP_ERASE 0
/* If this macro is defined to 1, the boot loader implements the Chip Erase
* ISP command. Otherwise pages are erased on demand before they are written.
@@ -169,13 +170,8 @@ these macros are defined, the boot loader uses them.
* bootLoaderCondition() for efficiency.
*/
-
#define JUMPER_BIT 0 /* jumper is connected to this bit in port B, active low */
-#ifndef MCUCSR /* compatibility between ATMega8 and ATMega88 */
-# define MCUCSR MCUSR
-#endif
-
/* tiny85 Architecture Specifics */
#ifndef __AVR_ATtiny85__
# error "uBoot is only designed for attiny85"
@@ -205,18 +201,14 @@ these macros are defined, the boot loader uses them.
#define USB_INTR_PENDING_BIT PCIF
#define USB_INTR_VECTOR PCINT0_vect
-
-/* max 6200ms to not overflow idlePolls variable */
-#define AUTO_EXIT_MS 5000
-//#define AUTO_EXIT_CONDITION() (idlePolls > (AUTO_EXIT_MS * 10UL))
-
+
// uncomment for chips with clkdiv8 enabled in fuses
//#define LOW_POWER_MODE 1
-// restore cpu speed calibration back to 8/16mhz instead of 8.25/16.5mhz
-//#define RESTORE_OSCCAL 1
+
// set clock prescaler to a value before running user program
//#define SET_CLOCK_PRESCALER _BV(CLKPS0) /* divide by 2 for 8mhz */
+
#ifdef BUILD_JUMPER_MODE
#define START_JUMPER_PIN 5
#define digitalRead(pin) (PINB & _BV(pin))
@@ -234,10 +226,11 @@ these macros are defined, the boot loader uses them.
PORTB = 0;
}
#endif /* __ASSEMBLER__ */
+
#else
#define bootLoaderInit()
#define bootLoaderExit()
- #define bootLoaderCondition() (idlePolls < (AUTO_EXIT_MS * 10UL))
+ #define bootLoaderCondition() (++idlePolls < (AUTO_EXIT_MS * 10UL))
#if LOW_POWER_MODE
// only starts bootloader if USB D- is pulled high on startup - by putting your pullup in to an external connector
// you can avoid ever entering an out of spec clock speed or waiting on bootloader when that pullup isn't there
@@ -273,20 +266,74 @@ these macros are defined, the boot loader uses them.
#ifndef __ASSEMBLER__ /* assembler cannot parse function definitions */
-//static inline void bootLoaderInit(void) {
-// // DeuxVis pin-5 pullup
-// DDRB |= _BV(DEUXVIS_JUMPER_PIN); // is an input
-// PORTB |= _BV(DEUXVIS_JUMPER_PIN); // has pullup enabled
-// _delay_ms(10);
-//}
-//static inline void bootLoaderExit(void) {
- // DeuxVis pin-5 pullup
-// PORTB = 0;
-// DDRB = 0;
-//}
+/*
+ * Define bootloader timeout value.
+ *
+ * These will only be used if is bootLoaderCondition() evaluates idlePolls below!
+ *
+ * AUTO_EXIT_NO_USB_MS The bootloader will exit after this delay if no USB is connected.
+ * Set to 0 to disable
+ * Adds ~6 bytes.
+ * (This will wait for an USB SE0 reset from the host)
+ * AUTO_EXIT_MS The bootloader will exit after this delay if no USB communication
+ * from the host tool was received.
+ *
+ * All values are approx. in milliseconds
+ */
+
+#define AUTO_EXIT_NO_USB_MS 0
+#define AUTO_EXIT_MS 6000
+
+ /*
+ * Defines the setting of the RC-oscillator calibration after quitting the bootloader. (OSCCAL)
+ *
+ * OSCCAL_RESTORE Set this to '1' to revert to factory calibration, which is 16.0 MHZ +/-10%
+ * Adds ~14 bytes.
+ *
+ * OSCCAL_16.5MHz Set this to '1' to use the same calibration as during program upload.
+ * This value is 16.5Mhz +/-1% as calibrated from the USB timing. Please note
+ * that only true if the ambient temperature does not change.
+ * This is the default behaviour of the Digispark.
+ * Adds ~38 bytes.
+ *
+ * If both options are selected, OSCCAL_RESTORE takes precedence.
+ *
+ * If no option is selected, OSCCAL will be left untouched and stay at either 16.0Mhz or 16.5Mhz depending
+ * on whether the bootloader was activated. This will take the least memory. You can use this if your program
+ * comes with its own OSCCAL calibration or an external clock source is used.
+ */
+
+ #define OSCCAL_RESTORE 0
+ #define OSCCAL_16_5MHz 1
+
+/*
+ * Defines handling of an indicator LED while the bootloader is active.
+ *
+ * LED_PRESENT Set this this to '1' to active all LED related code. If this is 0, all other
+ * defines are ignored.
+ * Adds 18 bytes depending on implementation.
+ *
+ * LED_DDR,LED_PORT,LED_PIN Where is your LED connected?
+ *
+ * LED_INIT Called once after bootloader entry
+ * LED_EXIT Called once during bootloader exit
+ * LED_MACRO Called in the main loop with the idle counter as parameter.
+ * Use to define pattern.
+ */
+
+#define LED_PRESENT 0
+
+#define LED_DDR DDRB
+#define LED_PORT PORTB
+#define LED_PIN PB1
+
+#define LED_INIT(x) LED_PORT &=~_BV(LED_PIN);
+#define LED_EXIT(x) LED_DDR &=~_BV(LED_PIN);
+#define LED_MACRO(x) if ( x & 0xd ) {LED_DDR&=~_BV(LED_PIN);} else {LED_DDR|=_BV(LED_PIN);}
#endif /* __ASSEMBLER__ */
+
/* ------------------------------------------------------------------------- */
#endif /* __bootloader_h_included__ */
diff --git a/firmware/crt1.S b/firmware/crt1.S
new file mode 100644
index 0000000..29693ac
--- /dev/null
+++ b/firmware/crt1.S
@@ -0,0 +1,107 @@
+
+/* Copyright (c) 2002, Marek Michalkiewicz <marekm@amelek.gda.pl>
+ Copyright (c) 2007, 2008 Eric B. Weddington
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in
+ the documentation and/or other materials provided with the
+ distribution.
+
+ * Neither the name of the copyright holders nor the names of
+ contributors may be used to endorse or promote products derived
+ from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ POSSIBILITY OF SUCH DAMAGE. */
+
+/* $Id$ */
+
+#if (__GNUC__ < 3) || (__GNUC__ == 3 && __GNUC_MINOR__ < 3)
+#error "GCC version >= 3.3 required"
+#endif
+
+/*
+#include IOSYMFILE
+#include "macros.inc"
+*/
+#include <avr/io.h>
+//#include <avr/pgmspace.h>
+
+ #define XJMP rjmp
+ #define XCALL rcall
+
+ .macro vector name
+ .weak \name
+ .set \name, __init
+ XJMP \name
+ .endm
+
+ .section .vectors,"ax",@progbits
+ .global __vectors
+ .global __bad_interrupt
+ .func __vectors
+__bad_interrupt:
+__vectors:
+ XJMP __init
+ vector __vector_1
+ vector __vector_2
+ vector __vector_3
+ .endfunc
+
+ /* Handle unexpected interrupts (enabled and no handler), which
+ usually indicate a bug. Jump to the __vector_default function
+ if defined by the user, otherwise jump to the reset address.
+
+ This must be in a different section, otherwise the assembler
+ will resolve "rjmp" offsets and there will be no relocs. */
+
+ .section .init0,"ax",@progbits
+ .weak __init
+; .func __init
+__init:
+
+ .weak __stack
+ .set __stack, RAMEND
+ /* By default, malloc() uses the current value of the stack pointer
+ minus __malloc_margin as the highest available address.
+
+ In some applications with external SRAM, the stack can be below
+ the data section (in the internal SRAM - faster), and __heap_end
+ should be set to the highest address available for malloc(). */
+ .weak __heap_end
+ .set __heap_end, 0
+
+ .section .init2,"ax",@progbits
+ clr R1
+ out 0x3f,r1
+ ldi r28,lo8(__stack)
+ ldi r29,hi8(__stack)
+ out 0x3d, r28
+ out 0x3e, r29
+ .section .init9,"ax",@progbits
+ XJMP main
+; .endfunc
+
+
+ .section .zerotable,"ax",@progbits
+zerovectors:
+ XJMP __init
+ XJMP __vector_1
+ XJMP __vector_2
+ XJMP __vector_3
diff --git a/firmware/libs-device/osccal.c b/firmware/libs-device/osccal.c
index 939d5c3..8debe49 100644
--- a/firmware/libs-device/osccal.c
+++ b/firmware/libs-device/osccal.c
@@ -8,49 +8,169 @@
*/
#include <avr/io.h>
-
+#include <avr/interrupt.h>
#ifndef uchar
#define uchar unsigned char
#endif
+int usbMeasureFrameLengthDecreasing(int);
+
/* ------------------------------------------------------------------------- */
/* ------------------------ Oscillator Calibration ------------------------- */
/* ------------------------------------------------------------------------- */
/* Calibrate the RC oscillator. Our timing reference is the Start Of Frame
* signal (a single SE0 bit) repeating every millisecond immediately after
- * a USB RESET. We first do a binary search for the OSCCAL value and then
- * optimize this value with a neighboorhod search.
+ * a USB RESET.
+ *
+ *
+ * Optimized version by cpldcpu@gmail.com, Nov 3rd 2013.
+ *
+ * Benefits:
+ * - Codesize reduced by 54 bytes.
+ * - Improved robustness due to removing timeout from frame length measurement and
+ * inserted NOP after OSCCAL writes.
+ *
+ * Changes:
+ * - The new routine performs a combined binary and neighborhood search
+ * in a single loop.
+ * Note that the neighborhood search is necessary due to the quasi-monotonic
+ * nature of OSCCAL. (See Atmel application note AVR054).
+ * - Inserted NOP after writes to OSCCAL to avoid CPU errors during oscillator
+ * stabilization.
+ * - Implemented new routine to measure frame time "usbMeasureFrameLengthDecreasing".
+ * This routine takes the target time as a parameter and returns the deviation.
+ * - usbMeasureFrameLengthDecreasing measures in multiples of 5 cycles and is thus
+ * slighly more accurate.
+ * - usbMeasureFrameLengthDecreasing does not support time out anymore. The original
+ * implementation returned zero in case of time out, which would have caused the old
+ * calibrateOscillator() implementation to increase OSSCAL to 255, effictively
+ * overclocking and most likely crashing the CPU. The new implementation will enter
+ * an infinite loop when no USB activity is encountered. The user program should
+ * use the watchdog to escape from situations like this.
+ *
+ * This routine will work both on controllers with and without split OSCCAL range.
+ * The first trial value is 128 which is the lowest value of the upper OSCCAL range
+ * on Attiny85 and will effectively limit the search to the upper range, unless the
+ * RC oscillator frequency is unusually high. Under normal operation, the highest
+ * tested frequency setting is 192. This corresponds to ~20 Mhz core frequency and
+ * is still within spec for a 5V device.
*/
+
void calibrateOscillator(void)
{
-uchar step = 128;
-uchar trialValue = 0, optimumValue;
-int x, optimumDev, targetValue = (unsigned)(1499 * (double)F_CPU / 10.5e6 + 0.5);
-
- /* do a binary search: */
- do{
- OSCCAL = trialValue + step;
- x = usbMeasureFrameLength(); /* proportional to current real frequency */
- if(x < targetValue) /* frequency still too low */
- trialValue += step;
- step >>= 1;
- }while(step > 0);
- /* We have a precision of +/- 1 for optimum OSCCAL here */
- /* now do a neighborhood search for optimum value */
- optimumValue = trialValue;
- optimumDev = x; /* this is certainly far away from optimum */
- for(OSCCAL = trialValue - 1; OSCCAL <= trialValue + 1; OSCCAL++){
- x = usbMeasureFrameLength() - targetValue;
- if(x < 0)
- x = -x;
- if(x < optimumDev){
- optimumDev = x;
- optimumValue = OSCCAL;
- }
- }
- OSCCAL = optimumValue;
+ uchar step, trialValue, optimumValue;
+ int x, targetValue;
+ uchar optimumDev;
+ uchar i,xl;
+
+ targetValue = (unsigned)((double)F_CPU * 999e-6 / 5.0 + 0.5); /* Time is measured in multiples of 5 cycles. Target is 0.999µs */
+ optimumDev = 0xff;
+ // optimumValue = OSCCAL;
+ step=64;
+ trialValue = 128;
+
+ cli(); // disable interrupts
+
+ /*
+ Performs seven iterations of a binary search (stepwidth decreasing9
+ with three additional steps of a neighborhood search (step=1, trialvalue will oscillate around target value to find optimum)
+ */
+
+ for(i=0; i<10; i++){
+ OSCCAL = trialValue;
+ asm volatile(" NOP");
+
+ x = usbMeasureFrameLengthDecreasing(targetValue);
+
+ if(x < 0) /* frequency too high */
+ {
+ trialValue -= step;
+ xl=(uchar)-x;
+ }
+ else /* frequency too low */
+ {
+ trialValue += step;
+ xl=(uchar)x;
+ }
+
+ /*
+ Halve stepwidth to perform binary search. Logical oring with 1 to ensure step is never equal to zero.
+ This results in a neighborhood search with stepwidth 1 after binary search is finished.
+ Once the neighbourhood search stage is reached, x will be smaller than +-255, hence more code can be
+ saved by only working with the lower 8 bits.
+ */
+
+ step >>= 1;
+
+ if (step==0)
+ {
+ step=1;
+ if(xl <= optimumDev){
+ optimumDev = xl;
+ optimumValue = OSCCAL;
+ }
+ }
+
+ }
+
+ OSCCAL = optimumValue;
+ asm volatile(" NOP");
+
+ sei(); // enable interrupts
}
+
+void calibrateOscillator_old(void)
+{
+ uchar step, trialValue, optimumValue;
+ int x, optimumDev, targetValue;
+ uchar i;
+
+ targetValue = (unsigned)((double)F_CPU * 999e-6 / 5.0 + 0.5); /* Time is measured in multiples of 5 cycles. Target is 0.999µs */
+ optimumDev = 0x7f00; // set to high positive value
+ optimumValue = OSCCAL;
+ step=64;
+ trialValue = 128;
+
+ /*
+ Performs seven iterations of a binary search (stepwidth decreasing9
+ with three additional steps of a neighborhood search (step=1, trialvalue will oscillate around target value to find optimum)
+ */
+
+ for(i=0; i<10; i++){
+ OSCCAL = trialValue;
+ asm volatile(" NOP");
+
+ x = usbMeasureFrameLengthDecreasing(targetValue);
+
+ if(x < 0) /* frequency too high */
+ {
+ trialValue -= step;
+ x = -x;
+ }
+ else /* frequency too low */
+ {
+ trialValue += step;
+ }
+
+ /*
+ Halve stepwidth to perform binary search. Logical oring with 1 to ensure step is never equal to zero.
+ This results in a neighborhood search with stepwidth 1 after binary search is finished.
+ */
+
+ step >>= 1;
+ step |=1;
+
+ if(x < optimumDev){
+ optimumDev = x;
+ optimumValue = OSCCAL;
+ }
+ }
+
+ OSCCAL = optimumValue;
+ asm volatile(" NOP");
+}
+
/*
Note: This calibration algorithm may try OSCCAL values of up to 192 even if
the optimum value is far below 192. It may therefore exceed the allowed clock
diff --git a/firmware/libs-device/osccal.h b/firmware/libs-device/osccal.h
index 710ce05..af37a43 100644
--- a/firmware/libs-device/osccal.h
+++ b/firmware/libs-device/osccal.h
@@ -1,10 +1,10 @@
/* Name: osccal.h
* Author: Christian Starkjohann
* Creation Date: 2008-04-10
+ * Changes 2013-11-04 cpldcpu@gmail.com
* Tabsize: 4
* Copyright: (c) 2008 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: osccal.h 762 2009-08-12 17:10:30Z cs $
*/
/*
@@ -14,30 +14,18 @@ oscillator so that the CPU runs at F_CPU (F_CPU is a macro which must be
defined when the module is compiled, best passed in the compiler command
line). The time reference is the USB frame clock of 1 kHz available
immediately after a USB RESET condition. Timing is done by counting CPU
-cycles, so all interrupts must be disabled while the calibration runs. For
-low level timing measurements, usbMeasureFrameLength() is called. This
-function must be enabled in usbconfig.h by defining
-USB_CFG_HAVE_MEASURE_FRAME_LENGTH to 1. It is recommended to call
-calibrateOscillator() from the reset hook in usbconfig.h:
-*/
+cycles, so all interrupts must be disabled while the calibration runs.
+The size optimized assembler implementation includes its own implementation
+of usbMeasureFrameLength. Therefore USB_CFG_HAVE_MEASURE_FRAME_LENGTH should
+be set to 0 to avoid including unused code sections. It is recommended to call
+calibrateOscillatorASM() from the reset hook in usbconfig.h by including osccal.h:
-#ifndef __ASSEMBLER__
-#include <avr/interrupt.h> // for sei()
-extern void calibrateOscillator(void);
-#endif
-#define USB_RESET_HOOK(resetStarts) if(!resetStarts){cli(); calibrateOscillator(); sei();}
+#include "osccal.h"
-/*
This routine is an alternative to the continuous synchronization described
in osctune.h.
-Algorithm used:
-calibrateOscillator() first does a binary search in the OSCCAL register for
-the best matching oscillator frequency. Then it does a next neighbor search
-to find the value with the lowest clock rate deviation. It is guaranteed to
-find the best match among neighboring values, but for version 5 oscillators
-(which have a discontinuous relationship between OSCCAL and frequency) a
-better match might be available in another OSCCAL region.
+Algorithm used: See osccalASM.x
Limitations:
This calibration algorithm may try OSCCAL values of up to 192 even if the
@@ -53,7 +41,11 @@ deviation! All other frequency modules require at least 0.2% precision.
#ifndef __OSCCAL_H_INCLUDED__
#define __OSCCAL_H_INCLUDED__
-//void calibrateOscillator(void);
+#ifndef __ASSEMBLER__
+ void calibrateOscillatorASM(void);
+# define USB_RESET_HOOK(resetStarts) if(!resetStarts){ calibrateOscillatorASM();}
+# define USB_CFG_HAVE_MEASURE_FRAME_LENGTH 0
+#endif
/* This function calibrates the RC oscillator so that the CPU runs at F_CPU.
* It MUST be called immediately after the end of a USB RESET condition!
* Disable all interrupts during the call!
diff --git a/firmware/libs-device/osccalASM.S b/firmware/libs-device/osccalASM.S
new file mode 100644
index 0000000..9a317f1
--- /dev/null
+++ b/firmware/libs-device/osccalASM.S
@@ -0,0 +1,228 @@
+/* Name: osccalASM.S
+ * Author: cpldcpu@gmail.com
+ * Creation Date: 2013-11-3
+ * Tabsize: 4
+ * License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
+ */
+
+/* Calibrate the RC oscillator. Our timing reference is the Start Of Frame
+ * signal (a single SE0 bit) repeating every millisecond immediately after
+ * a USB RESET.
+ *
+ *
+ * Benefits:
+ * - Codesize reduced by 90 bytes.
+ * - Improved robustness due to removing timeout from frame length measurement and
+ * inserted NOP after OSCCAL writes.
+ *
+ * Changes:
+ * - The new routine performs a combined binary and neighborhood search
+ * in a single loop.
+ * Note that the neighborhood search is necessary due to the quasi-monotonic
+ * nature of OSCCAL. (See Atmel application note AVR054).
+ * - Inserted NOP after writes to OSCCAL to avoid CPU errors during oscillator
+ * stabilization.
+ * - Implemented new routine to measure frame time "usbMeasureFrameLengthDecreasing".
+ * This routine takes the target time as a parameter and returns the deviation.
+ * - usbMeasureFrameLengthDecreasing measures in multiples of 5 cycles and is thus
+ * slighly more accurate.
+ * - usbMeasureFrameLengthDecreasing does not support time out anymore. The original
+ * implementation returned zero in case of time out, which would have caused the old
+ * calibrateOscillator() implementation to increase OSSCAL to 255, effictively
+ * overclocking and most likely crashing the CPU. The new implementation will enter
+ * an infinite loop when no USB activity is encountered. The user program should
+ * use the watchdog to escape from situations like this.
+ *
+ * This routine will work both on controllers with and without split OSCCAL range.
+ * The first trial value is 128 which is the lowest value of the upper OSCCAL range
+ * on Attiny85 and will effectively limit the search to the upper range, unless the
+ * RC oscillator frequency is unusually high. Under normal operation, the highest
+ * tested frequency setting is 192. This corresponds to ~20 Mhz core frequency and
+ * is still within spec for a 5V device.
+ */
+
+
+#define __SFR_OFFSET 0 /* used by avr-libc's register definitions */
+#include "./usbdrv/usbdrv.h" /* for common defs */
+
+#ifdef __IAR_SYSTEMS_ASM__
+/* Register assignments for usbMeasureFrameLengthDecreasing on IAR cc */
+/* Calling conventions on IAR:
+ * First parameter passed in r16/r17, second in r18/r19 and so on.
+ * Callee must preserve r4-r15, r24-r29 (r28/r29 is frame pointer)
+ * Result is passed in r16/r17
+ * In case of the "tiny" memory model, pointers are only 8 bit with no
+ * padding. We therefore pass argument 1 as "16 bit unsigned".
+ */
+
+//Untested
+
+# define i r20
+# define opV r19
+# define opD r18
+# define try r21
+# define stp r22
+
+# define cnt16L r30
+# define cnt16H r31
+
+
+#else /* __IAR_SYSTEMS_ASM__ */
+/* Register assignments for usbMeasureFrameLength on gcc */
+/* Calling conventions on gcc:
+ * First parameter passed in r24/r25, second in r22/23 and so on.
+ * Callee must preserve r1-r17, r28/r29
+ * Result is passed in r24/r25
+ */
+
+# define i r20
+# define opV r19
+# define opD r18
+# define try r27
+# define stp r26
+# define cnt16L r24
+# define cnt16H r25
+#endif
+# define cnt16 cnt16L
+
+; extern void calibrateOscillatorASM(void);
+
+.global calibrateOscillatorASM
+calibrateOscillatorASM:
+
+ cli
+ ldi opD, 255
+
+ ldi try, 128 ; calibration start value
+ ldi stp, 64 ; initial step width
+ ldi i, 10 ; 10 iterations
+
+usbCOloop:
+
+ out OSCCAL, try
+ nop
+
+ ; Delay values = F_CPU * 999e-6 / 5 + 0.5
+
+#if (F_CPU == 16500000)
+ ldi cnt16L, lo8(3297)
+ ldi cnt16H, hi8(3297)
+#elif (F_CPU == 12800000)
+ ldi cnt16L, lo8(2557)
+ ldi cnt16H, hi8(2557)
+#else
+ #error "calibrateOscillatorASM: no delayvalues defined for this F_CPU setting"
+#endif
+
+usbCOWaitStrobe: ; first wait for D- == 0 (idle strobe)
+ sbic USBIN, USBMINUS ;
+ rjmp usbCOWaitStrobe ;
+usbCOWaitIdle: ; then wait until idle again
+ sbis USBIN, USBMINUS ;1 wait for D- == 1
+ rjmp usbCOWaitIdle ;2
+usbCOWaitLoop:
+ sbiw cnt16,1 ;[0] [5]
+ sbic USBIN, USBMINUS ;[2]
+ rjmp usbCOWaitLoop ;[3]
+
+ sbrs cnt16H, 7 ;delay overflow?
+ rjmp usbCOclocktoolow
+ sub try, stp
+ neg cnt16L
+ rjmp usbCOclocktoohigh
+usbCOclocktoolow:
+ add try, stp
+usbCOclocktoohigh:
+ lsr stp
+ brne usbCOnoneighborhoodsearch
+ cp opD, cnt16L
+ brcs usbCOnoimprovement
+ in opV, OSCCAL
+ mov opD, cnt16L
+usbCOnoimprovement:
+ ldi stp, 1
+usbCOnoneighborhoodsearch:
+ subi i, 1
+ brne usbCOloop
+
+ out OSCCAL, opV
+ nop
+ sei
+ ret
+
+#undef i
+#undef opV
+#undef opD
+#undef try
+#undef stp
+#undef cnt16
+#undef cnt16L
+#undef cnt16H
+
+/* ------------------------------------------------------------------------- */
+/* ------ Original C Implementation of improved calibrateOscillator -------- */
+/* ---------------------- for Reference only ----------------------------- */
+/* ------------------------------------------------------------------------- */
+
+#if 0
+void calibrateOscillator(void)
+{
+ uchar step, trialValue, optimumValue;
+ int x, targetValue;
+ uchar optimumDev;
+ uchar i,xl;
+
+ targetValue = (unsigned)((double)F_CPU * 999e-6 / 5.0 + 0.5); /* Time is measured in multiples of 5 cycles. Target is 0.999µs */
+ optimumDev = 0xff;
+ // optimumValue = OSCCAL;
+ step=64;
+ trialValue = 128;
+
+ cli(); // disable interrupts
+
+ /*
+ Performs seven iterations of a binary search (stepwidth decreasing9
+ with three additional steps of a neighborhood search (step=1, trialvalue will oscillate around target value to find optimum)
+ */
+
+ for(i=0; i<10; i++){
+ OSCCAL = trialValue;
+ asm volatile(" NOP");
+
+ x = usbMeasureFrameLengthDecreasing(targetValue);
+
+ if(x < 0) /* frequency too high */
+ {
+ trialValue -= step;
+ xl=(uchar)-x;
+ }
+ else /* frequency too low */
+ {
+ trialValue += step;
+ xl=(uchar)x;
+ }
+
+ /*
+ Halve stepwidth to perform binary search. At step=1 the mode changes to neighbourhood search.
+ Once the neighbourhood search stage is reached, x will be smaller than +-255, hence more code can be
+ saved by only working with the lower 8 bits.
+ */
+
+ step >>= 1;
+
+ if (step==0) // Enter neighborhood search mode
+ {
+ step=1;
+ if(xl <= optimumDev){
+ optimumDev = xl;
+ optimumValue = OSCCAL;
+ }
+ }
+ }
+
+ OSCCAL = optimumValue;
+ asm volatile(" NOP");
+
+ sei(); // enable interrupts
+}
+#endif \ No newline at end of file
diff --git a/firmware/main.c b/firmware/main.c
index e56de62..a6af148 100644
--- a/firmware/main.c
+++ b/firmware/main.c
@@ -4,26 +4,27 @@
* Creation Date: 2007-12-08
* Tabsize: 4
* Copyright: (c) 2012 Jenna Fox
+ * All changes past revision 1.06 authored by http://github.com/cpldcpu
* Portions Copyright: (c) 2007 by OBJECTIVE DEVELOPMENT Software GmbH (USBaspLoader)
* Portions Copyright: (c) 2012 Louis Beaudoin (USBaspLoader-tiny85)
* License: GNU GPL v2 (see License.txt)
+ *
*/
#define MICRONUCLEUS_VERSION_MAJOR 1
-#define MICRONUCLEUS_VERSION_MINOR 6
+#define MICRONUCLEUS_VERSION_MINOR 10
// how many milliseconds should host wait till it sends another erase or write?
// needs to be above 4.5 (and a whole integer) as avr freezes for 4.5ms
#define MICRONUCLEUS_WRITE_SLEEP 8
+// Use the old delay routines without NOP padding. This saves memory.
+#define __DELAY_BACKWARD_COMPATIBLE__
#include <avr/io.h>
-#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <avr/boot.h>
-//#include <avr/eeprom.h>
#include <util/delay.h>
-//#include <string.h>
static void leaveBootloader() __attribute__((__noreturn__));
@@ -31,43 +32,6 @@ static void leaveBootloader() __attribute__((__noreturn__));
#include "usbdrv/usbdrv.c"
/* ------------------------------------------------------------------------ */
-
-#ifndef ulong
-# define ulong unsigned long
-#endif
-#ifndef uint
-# define uint unsigned int
-#endif
-
-#ifndef BOOTLOADER_CAN_EXIT
-# define BOOTLOADER_CAN_EXIT 0
-#endif
-
-/* allow compatibility with avrusbboot's bootloaderconfig.h: */
-#ifdef BOOTLOADER_INIT
-# define bootLoaderInit() BOOTLOADER_INIT
-# define bootLoaderExit()
-#endif
-#ifdef BOOTLOADER_CONDITION
-# define bootLoaderCondition() BOOTLOADER_CONDITION
-#endif
-
-/* device compatibility: */
-#ifndef GICR /* ATMega*8 don't have GICR, use MCUCR instead */
-# define GICR MCUCR
-#endif
-
-/* ------------------------------------------------------------------------ */
-
-#define addr_t uint
-
-// typedef union longConverter{
-// addr_t l;
-// uint w[sizeof(addr_t)/2];
-// uchar b[sizeof(addr_t)];
-// } longConverter_t;
-
-//////// Stuff Bluebie Added
// postscript are the few bytes at the end of programmable memory which store tinyVectors
// and used to in USBaspLoader-tiny85 store the checksum iirc
#define POSTSCRIPT_SIZE 6
@@ -88,72 +52,63 @@ static void leaveBootloader() __attribute__((__noreturn__));
// events system schedules functions to run in the main loop
static uchar events = 0; // bitmap of events to run
#define EVENT_ERASE_APPLICATION 1
-#define EVENT_WRITE_PAGE 2
-#define EVENT_EXECUTE 4
+#define EVENT_WRITE_PAGE 2
+#define EVENT_EXECUTE 4
// controls state of events
#define fireEvent(event) events |= (event)
#define isEvent(event) (events & (event))
#define clearEvents() events = 0
-// length of bytes to write in to flash memory in upcomming usbFunctionWrite calls
-//static unsigned char writeLength;
-
-// becomes 1 when some programming happened
-// lets leaveBootloader know if needs to finish up the programming
-static uchar didWriteSomething = 0;
+// Definition of sei and cli without memory barrier keyword to prevent reloading of memory variables
+#define sei() __asm__ __volatile__ ("sei")
+#define cli() __asm__ __volatile__ ("cli")
uint16_t idlePolls = 0; // how long have we been idle?
-
-
static uint16_t vectorTemp[2]; // remember data to create tinyVector table before BOOTLOADER_ADDRESS
-static addr_t currentAddress; // current progmem address, used for erasing and writing
+static uint16_t currentAddress; // current progmem address, used for erasing and writing
+#if OSCCAL_RESTORE
+ static uint8_t osccal_default; // due to compiler insanity, having this as global actually saves memory
+#endif
/* ------------------------------------------------------------------------ */
static inline void eraseApplication(void);
static void writeFlashPage(void);
static void writeWordToPageBuffer(uint16_t data);
-static void fillFlashWithVectors(void);
static uchar usbFunctionSetup(uchar data[8]);
static uchar usbFunctionWrite(uchar *data, uchar length);
-static inline void initForUsbConnectivity(void);
-static inline void tiny85FlashInit(void);
-static inline void tiny85FlashWrites(void);
-//static inline void tiny85FinishWriting(void);
static inline void leaveBootloader(void);
// erase any existing application and write in jumps for usb interrupt and reset to bootloader
// - Because flash can be erased once and programmed several times, we can write the bootloader
// - vectors in now, and write in the application stuff around them later.
-// - if vectors weren't written back in immidately, usb would fail.
+// - if vectors weren't written back in immediately, usb would fail.
static inline void eraseApplication(void) {
// erase all pages until bootloader, in reverse order (so our vectors stay in place for as long as possible)
// while the vectors don't matter for usb comms as interrupts are disabled during erase, it's important
// to minimise the chance of leaving the device in a state where the bootloader wont run, if there's power failure
// during upload
- currentAddress = BOOTLOADER_ADDRESS;
+
+ uint8_t i;
+ uint16_t ptr = BOOTLOADER_ADDRESS;
cli();
- while (currentAddress) {
- currentAddress -= SPM_PAGESIZE;
-
- boot_page_erase(currentAddress);
- boot_spm_busy_wait();
+ while (ptr) {
+ ptr -= SPM_PAGESIZE;
+ boot_page_erase(ptr);
}
- fillFlashWithVectors();
- sei();
+ currentAddress = 0;
+ for (i=0; i<8; i++) writeWordToPageBuffer(0xFFFF); // Write first 8 words to fill in vectors.
+ writeFlashPage(); // enables interrupts
}
// simply write currently stored page in to already erased flash memory
static void writeFlashPage(void) {
- uint8_t previous_sreg = SREG; // backup current interrupt setting
- didWriteSomething = 1;
cli();
- boot_page_write(currentAddress - 2);
- boot_spm_busy_wait(); // Wait until the memory is written.
- SREG = previous_sreg; // restore interrupts to previous state
+ boot_page_write(currentAddress - 2); // will halt CPU, no waiting required
+ sei();
}
// clear memory which stores data to be written by next writeFlashPage call
@@ -174,10 +129,17 @@ static void writeWordToPageBuffer(uint16_t data) {
uint8_t previous_sreg;
// first two interrupt vectors get replaced with a jump to the bootloader's vector table
- if (currentAddress == (RESET_VECTOR_OFFSET * 2) || currentAddress == (USBPLUS_VECTOR_OFFSET * 2)) {
- data = 0xC000 + (BOOTLOADER_ADDRESS/2) - 1;
- }
-
+ // remember vectors or the tinyvector table
+ if (currentAddress == RESET_VECTOR_OFFSET * 2) {
+ vectorTemp[0] = data;
+ data = 0xC000 + (BOOTLOADER_ADDRESS/2) - 1;
+ }
+
+ if (currentAddress == USBPLUS_VECTOR_OFFSET * 2) {
+ vectorTemp[1] = data;
+ data = 0xC000 + (BOOTLOADER_ADDRESS/2) - 1;
+ }
+
// at end of page just before bootloader, write in tinyVector table
// see http://embedded-creations.com/projects/attiny85-usb-bootloader-overview/avr-jtag-programmer/
// for info on how the tiny vector table works
@@ -185,58 +147,34 @@ static void writeWordToPageBuffer(uint16_t data) {
data = vectorTemp[0] + ((FLASHEND + 1) - BOOTLOADER_ADDRESS)/2 + 2 + RESET_VECTOR_OFFSET;
} else if (currentAddress == BOOTLOADER_ADDRESS - TINYVECTOR_USBPLUS_OFFSET) {
data = vectorTemp[1] + ((FLASHEND + 1) - BOOTLOADER_ADDRESS)/2 + 1 + USBPLUS_VECTOR_OFFSET;
+#if (!OSCCAL_RESTORE) && OSCCAL_16_5MHz
} else if (currentAddress == BOOTLOADER_ADDRESS - TINYVECTOR_OSCCAL_OFFSET) {
data = OSCCAL;
+#endif
}
-
+
+ previous_sreg=SREG;
+ cli(); // ensure interrupts are disabled
// clear page buffer as a precaution before filling the buffer on the first page
// in case the bootloader somehow ran after user program and there was something
// in the page buffer already
if (currentAddress == 0x0000) __boot_page_fill_clear();
-
- previous_sreg = SREG; // backup previous interrupt settings
- cli(); // ensure interrupts are disabled
boot_page_fill(currentAddress, data);
- SREG = previous_sreg; // restore previous interrupt setting
-
- // only need to erase if there is data already in the page that doesn't match what we're programming
- // TODO: what about this: if (pgm_read_word(currentAddress) & data != data) { ??? should work right?
- //if (pgm_read_word(currentAddress) != data && pgm_read_word(currentAddress) != 0xFFFF) {
- //if ((pgm_read_word(currentAddress) & data) != data) {
- // fireEvent(EVENT_PAGE_NEEDS_ERASE);
- //}
// increment progmem address by one word
currentAddress += 2;
-}
-
-// fills the rest of this page with vectors - interrupt vector or tinyvector tables where needed
-static void fillFlashWithVectors(void) {
- //int16_t i;
- //
- // fill all or remainder of page with 0xFFFF (as if unprogrammed)
- //for (i = currentAddress % SPM_PAGESIZE; i < SPM_PAGESIZE; i += 2) {
- // writeWordToPageBuffer(0xFFFF); // is where vector tables are sorted out
- //}
-
- // TODO: Or more simply:
- do {
- writeWordToPageBuffer(0xFFFF);
- } while (currentAddress % SPM_PAGESIZE);
-
- writeFlashPage();
+ SREG=previous_sreg;
}
/* ------------------------------------------------------------------------ */
-
static uchar usbFunctionSetup(uchar data[8]) {
usbRequest_t *rq = (void *)data;
- idlePolls = 0; // reset idle polls when we get usb traffic
-
+ ((uint8_t*)&idlePolls)[1] = 0; // reset idle polls when we get usb traffic
+
static uchar replyBuffer[4] = {
- (((uint)PROGMEM_SIZE) >> 8) & 0xff,
- ((uint)PROGMEM_SIZE) & 0xff,
+ (((uint16_t)PROGMEM_SIZE) >> 8) & 0xff,
+ ((uint16_t)PROGMEM_SIZE) & 0xff,
SPM_PAGESIZE,
MICRONUCLEUS_WRITE_SLEEP
};
@@ -246,9 +184,7 @@ static uchar usbFunctionSetup(uchar data[8]) {
return 4;
} else if (rq->bRequest == 1) { // write page
- //writeLength = rq->wValue.word;
- currentAddress = rq->wIndex.word;
-
+ currentAddress = rq->wIndex.word;
return USB_NO_MSG; // hands off work to usbFunctionWrite
} else if (rq->bRequest == 2) { // erase application
@@ -263,27 +199,11 @@ static uchar usbFunctionSetup(uchar data[8]) {
return 0;
}
-
// read in a page over usb, and write it in to the flash write buffer
static uchar usbFunctionWrite(uchar *data, uchar length) {
- //if (length > writeLength) length = writeLength; // test for missing final page bug
- //writeLength -= length;
-
- do {
- // remember vectors or the tinyvector table
- if (currentAddress == RESET_VECTOR_OFFSET * 2) {
- vectorTemp[0] = *(short *)data;
- }
-
- if (currentAddress == USBPLUS_VECTOR_OFFSET * 2) {
- vectorTemp[1] = *(short *)data;
- }
-
+ do {
// make sure we don't write over the bootloader!
- if (currentAddress >= BOOTLOADER_ADDRESS) {
- //__boot_page_fill_clear();
- break;
- }
+ if (currentAddress >= BOOTLOADER_ADDRESS) break;
writeWordToPageBuffer(*(uint16_t *) data);
data += 2; // advance data pointer
@@ -291,8 +211,13 @@ static uchar usbFunctionWrite(uchar *data, uchar length) {
} while(length);
// if we have now reached another page boundary, we're done
- //uchar isLast = (writeLength == 0);
+#if SPM_PAGESIZE<256
+ // Hack to reduce code size
+ uchar isLast = ((((uchar)currentAddress) % SPM_PAGESIZE) == 0);
+#else
uchar isLast = ((currentAddress % SPM_PAGESIZE) == 0);
+#endif
+
// definitely need this if! seems usbFunctionWrite gets called again in future usbPoll's in the runloop!
if (isLast) fireEvent(EVENT_WRITE_PAGE); // ask runloop to write our page
@@ -300,7 +225,6 @@ static uchar usbFunctionWrite(uchar *data, uchar length) {
}
/* ------------------------------------------------------------------------ */
-
void PushMagicWord (void) __attribute__ ((naked)) __attribute__ ((section (".init3")));
// put the word "B007" at the bottom of the stack (RAMEND - RAMEND-1)
@@ -312,97 +236,53 @@ void PushMagicWord (void) {
}
/* ------------------------------------------------------------------------ */
-
-static inline void initForUsbConnectivity(void) {
- usbInit();
- /* enforce USB re-enumerate: */
- usbDeviceDisconnect(); /* do this while interrupts are disabled */
- _delay_ms(500);
- usbDeviceConnect();
- sei();
-}
-
-static inline void tiny85FlashInit(void) {
- // check for erased first page (no bootloader interrupt vectors), add vectors if missing
- // this needs to happen for usb communication to work later - essential to first run after bootloader
- // being installed
- if(pgm_read_word(RESET_VECTOR_OFFSET * 2) != 0xC000 + (BOOTLOADER_ADDRESS/2) - 1 ||
- pgm_read_word(USBPLUS_VECTOR_OFFSET * 2) != 0xC000 + (BOOTLOADER_ADDRESS/2) - 1) {
-
- fillFlashWithVectors();
- }
-
- // TODO: necessary to reset currentAddress?
- currentAddress = 0;
-}
-
-static inline void tiny85FlashWrites(void) {
- _delay_us(2000); // TODO: why is this here? - it just adds pointless two level deep loops seems like?
- // write page to flash, interrupts will be disabled for > 4.5ms including erase
-
- // TODO: Do we need this? Wouldn't the programmer always send full sized pages?
- if (currentAddress % SPM_PAGESIZE) { // when we aren't perfectly aligned to a flash page boundary
- fillFlashWithVectors(); // fill up the rest of the page with 0xFFFF (unprogrammed) bits
- } else {
- writeFlashPage(); // otherwise just write it
- }
-}
-
-// finishes up writing to the flash, including adding the tinyVector tables at the end of memory
-// TODO: can this be simplified? EG: currentAddress = PROGMEM_SIZE; fillFlashWithVectors();
-// static inline void tiny85FinishWriting(void) {
-// // make sure remainder of flash is erased and write checksum and application reset vectors
-// if (didWriteSomething) {
-// while (currentAddress < BOOTLOADER_ADDRESS) {
-// fillFlashWithVectors();
-// }
-// }
-// }
-
// reset system to a normal state and launch user program
static inline void leaveBootloader(void) {
_delay_ms(10); // removing delay causes USB errors
- //DBG1(0x01, 0, 0);
bootLoaderExit();
cli();
+ usbDeviceDisconnect(); /* Disconnect micronucleus */
+
USB_INTR_ENABLE = 0;
USB_INTR_CFG = 0; /* also reset config bits */
// clear magic word from bottom of stack before jumping to the app
- *(uint8_t*)(RAMEND) = 0x00;
- *(uint8_t*)(RAMEND-1) = 0x00;
+ *(uint8_t*)(RAMEND) = 0x00; // A single write is sufficient to invalidate magic word
+#if (!OSCCAL_RESTORE) && OSCCAL_16_5MHz
// adjust clock to previous calibration value, so user program always starts with same calibration
// as when it was uploaded originally
- // TODO: Test this and find out, do we need the +1 offset?
unsigned char stored_osc_calibration = pgm_read_byte(BOOTLOADER_ADDRESS - TINYVECTOR_OSCCAL_OFFSET);
if (stored_osc_calibration != 0xFF && stored_osc_calibration != 0x00) {
- //OSCCAL = stored_osc_calibration; // this should really be a gradual change, but maybe it's alright anyway?
- // do the gradual change - failed to score extra free bytes anyway in 1.06
- while (OSCCAL > stored_osc_calibration) OSCCAL--;
- while (OSCCAL < stored_osc_calibration) OSCCAL++;
+ OSCCAL=stored_osc_calibration;
+ asm volatile("nop");
}
-
+#endif
// jump to application reset vector at end of flash
asm volatile ("rjmp __vectors - 4");
}
int main(void) {
/* initialize */
- #ifdef RESTORE_OSCCAL
- uint8_t osccal_default = OSCCAL;
+ #if OSCCAL_RESTORE
+ osccal_default = OSCCAL;
#endif
#if (!SET_CLOCK_PRESCALER) && LOW_POWER_MODE
uint8_t prescaler_default = CLKPR;
#endif
-
- wdt_disable(); /* main app may have enabled watchdog */
- tiny85FlashInit();
+
bootLoaderInit();
-
-
+
+# if AUTO_EXIT_NO_USB_MS
+ ((uint8_t*)&idlePolls)[1]=((AUTO_EXIT_MS-AUTO_EXIT_NO_USB_MS) * 10UL)>>8; // write only high byte to save 6 bytes
+# endif
+
if (bootLoaderStartCondition()) {
+
+ MCUSR=0; /* need this to properly disable watchdog */
+ wdt_disable();
+
#if LOW_POWER_MODE
// turn off clock prescalling - chip must run at full speed for usb
// if you might run chip at lower voltages, detect that in bootLoaderStartCondition
@@ -410,26 +290,38 @@ int main(void) {
CLKPR = 0;
#endif
- initForUsbConnectivity();
+# if LED_PRESENT
+ LED_INIT();
+# endif
+
+ usbDeviceDisconnect(); /* do this while interrupts are disabled */
+ _delay_ms(500);
+ usbDeviceConnect();
+ usbInit(); // Initialize INT settings after reconnect
+ sei();
+
do {
- usbPoll();
+ usbPoll();
_delay_us(100);
- idlePolls++;
// these next two freeze the chip for ~ 4.5ms, breaking usb protocol
// and usually both of these will activate in the same loop, so host
// needs to wait > 9ms before next usb request
if (isEvent(EVENT_ERASE_APPLICATION)) eraseApplication();
- if (isEvent(EVENT_WRITE_PAGE)) tiny85FlashWrites();
-
-# if BOOTLOADER_CAN_EXIT
- if (isEvent(EVENT_EXECUTE)) { // when host requests device run uploaded program
- break;
- }
-# endif
-
+ if (isEvent(EVENT_WRITE_PAGE)) {
+ _delay_us(2000); // Wait for USB traffic to finish before halting CPU with write-
+ writeFlashPage();
+ }
+
+# if BOOTLOADER_CAN_EXIT
+ if (isEvent(EVENT_EXECUTE)) break; // when host requests device run uploaded program
+# endif
clearEvents();
-
+
+# if LED_PRESENT
+ LED_MACRO( ((uint8_t*)&idlePolls)[1] )
+# endif
+
} while(bootLoaderCondition()); /* main event loop runs so long as bootLoaderCondition remains truthy */
}
@@ -444,11 +336,15 @@ int main(void) {
#endif
#endif
- // slowly bring down OSCCAL to it's original value before launching in to user program
- #ifdef RESTORE_OSCCAL
- while (OSCCAL > osccal_default) { OSCCAL -= 1; }
- #endif
+# if LED_PRESENT
+ LED_EXIT();
+# endif
+
+# if OSCCAL_RESTORE
+ OSCCAL=osccal_default;
+ asm volatile("nop"); // NOP to avoid CPU hickup during oscillator stabilization
+# endif
+
leaveBootloader();
}
-
/* ------------------------------------------------------------------------ */
diff --git a/firmware/releases/micronucleus-1.10.hex b/firmware/releases/micronucleus-1.10.hex
new file mode 100644
index 0000000..8b66f21
--- /dev/null
+++ b/firmware/releases/micronucleus-1.10.hex
@@ -0,0 +1,121 @@
+:0800000057CC56CC8CCC54CC3B
+:1018800017C016C04CC014C009021200010100802C
+:101890003209040000000000000012011001FF00E6
+:1018A0000008D01653070A010000000104030904D0
+:1018B00011241FBECFE5D2E0CDBFDEBF00EB0F93FA
+:1018C00007E00F9310E0A0E6B0E0E8ECFFE102C013
+:1018D00005900D92A636B107D9F720E0A6E6B0E054
+:1018E00001C01D92AB39B207E1F7ECC1A82FB92FA7
+:1018F00080E090E041E050EA609530E009C02D9131
+:1019000082279795879510F084279527305EC8F336
+:101910006F5FA8F30895EADF8D939D930895CF93A9
+:10192000CFB7CF93C0915F02C03B21F4C0915E025C
+:10193000C73021F0CF91CFBFCF91A1CFCC27C39596
+:10194000B39BE9F7B39B0BC0B39B09C0B39B07C024
+:10195000B39B05C0B39B03C0B39B01C0D3C00F9220
+:10196000DF93C0917E00DD27CB57DF4F012EB39B65
+:1019700003C0DF910F90E6CF2F930F931F934F93E8
+:101980002FEF4F6F06B303FB20F95F933F9350E0B7
+:101990003BE065C016B30126502953FDC89556B3E8
+:1019A000012703FB25F92F7306B3B1F05027102749
+:1019B00013FB26F906B22230F0F000C016B301275F
+:1019C00003FB27F90126502906B22430E8F54F77AA
+:1019D000206816B30000F6CF50274F7D206206B274
+:1019E000102F000000C006B300265029102713FB5B
+:1019F00026F906B2E2CF4F7B06B3206400C0DACFEF
+:101A000001265029187106B269F14E7F2160012F1D
+:101A100016B328C0002650294D7F06B22260102F31
+:101A200029C0012650294B7F06B22460012F2DC00A
+:101A300016B301265029477F2860000006B22EC049
+:101A40004F7E06B3206130C0422706B3499300267B
+:101A50005029102706B24FEF13FB20F9297F16B348
+:101A600079F2187159F10126502906B2012703FBBA
+:101A700021F9237F06B371F2002650293150D0F0AE
+:101A800006B2102713FB22F9277E16B351F2012666
+:101A90005029012703FB06B223F92F7C49F20000ED
+:101AA00006B3102713FB24F90026502906B22F791C
+:101AB00039F270CF10E21ABF002717C03B503195A2
+:101AC000C31BD04010E21ABF0881033CF9F00B346D
+:101AD000E9F020917C001981110F1213EDCF093626
+:101AE00051F10D3211F0013E39F7009383003F911F
+:101AF0005F914F911F910F912F91DF910F90CAB776
+:101B0000C5FD1DCFCF91CFBFCF91189520918300F8
+:101B1000222369F310918100112321F5343022F141
+:101B20003093810020937D0010917E003BE0311BBB
+:101B300030937E0019C00091810001309CF40AE5C9
+:101B40003091600034FD11C000936000C1E7D0E027
+:101B500010C0052710E000C021C0052710E0C8957F
+:101B600008BB14C03AE501C032ED032EC0E0D0E05E
+:101B700032E017B31861C39A08B317BB58E120E8E5
+:101B80004FEF20FF052708BB279517951C3F28F727
+:101B900000004552B0F720FF0527279508BB179591
+:101BA0001C3FB8F629913A9561F7077E10918200A3
+:101BB000110F08BBC250D04011F010937C0010E20E
+:101BC0001ABF086017B3177E402F477E54E05A951E
+:101BD000F1F708BB17BB48BB8ACFF8942FEFB0E8EA
+:101BE000A0E44AE0B1BF000081EE9CE0B399FECFD3
+:101BF000B39BFECF0197B399FDCF97FF03C0BA1BEC
+:101C0000819501C0BA0FA69529F4281710F031B7B5
+:101C1000282FA1E0415031F731BF0000789408959A
+:101C2000F894E0916A00F0916B00329785E0809320
+:101C30005700E89578940895E0916A00F0916B0060
+:101C4000309729F490936D0080936C0007C0E430C6
+:101C5000F10539F490936F0080936E008FE39CEC54
+:101C60001CC0EC3728E1F20739F480916C009091A8
+:101C70006D008E539C4F11C0EE3728E1F20739F406
+:101C800080916E0090916F008D539C4F06C0EA3793
+:101C900028E1F20711F481B790E02FB7F89430975C
+:101CA00021F431E130935700E89531E00C01309395
+:101CB0005700E89511243296F0936B00E0936A0088
+:101CC0002FBF089514BE88E10FB6F89481BD11BCF2
+:101CD0000FBEBB9A88E893E1ECE9F1E03197F1F7A8
+:101CE0000197D1F7BB98AC9A8BB780628BBF789481
+:101CF00000918100035007FDBAC080917E00CCE0C6
+:101D0000D0E0C81BD109CB57DF4F80917D008D32C9
+:101D100009F08EC0083009F0A8C083EC80937100F0
+:101D20008AE580936000109269002881922F907656
+:101D30008981992319F110926700811108C082E608
+:101D400090E09093800080937F0014E067C0813022
+:101D500051F48C819D8190936B0080936A0027FDE4
+:101D600058C01FEF57C090916800823011F4916005
+:101D700001C094609093680010E050C09A81109266
+:101D80007A00811106C010927B008AE790E012E091
+:101D90003BC0853019F4909382002CC0863009F541
+:101DA0008B81813019F48AE998E104C0823041F4D2
+:101DB00088E898E19093800080937F0012E10DC045
+:101DC000833051F4911108C08CEA98E1909380001F
+:101DD00080937F0014E001C010E080E480936900EC
+:101DE0001DC0883059F0893019F49093840002C0E6
+:101DF0008A3039F08AE790E010E006C084E890E08D
+:101E000002C08AE790E011E09093800080937F0009
+:101E100005C01E8180E88093690007C08F81811111
+:101E200004C08E81811708F4182F109361001DC023
+:101E30008091690087FF19C080916A0090916B00C2
+:101E40008038984128F080916A008F7339F00DC076
+:101E500089919991F1DE025079F7F5CF8091680070
+:101E600082608093680010926100109281008091DE
+:101E7000600084FF43C0809161008F3F09F43EC041
+:101E8000082F893008F008E0801B80936100809162
+:101E9000710098E8892780937100002319F1E0917F
+:101EA0007F00F09180008091690086FF0BC0A2E75F
+:101EB000B0E084918D93319682E790E0800F8A1391
+:101EC000F8CF0CC0CF01A2E7B0E0FC012191CF0117
+:101ED0002D9322E730E0200F2A13F7CFF0938000F4
+:101EE000E0937F00602F82E790E015DD0C5F0C30FF
+:101EF00019F08FEF809361000093600084E196B346
+:101F0000987131F48150D9F71092820010927C00C0
+:101F100001E0811100E080917000801739F001111B
+:101F200003C01092670059DE009370008CE991E0C5
+:101F30000197F1F70091680000FF17C0F894E0E8FE
+:101F4000F8E1E054F10983E080935700E895309779
+:101F5000C1F710926B0010926A0088E0F82E8FEFA4
+:101F60009FEF6ADEFA94D9F75BDE01FF05C08AE3D2
+:101F700090E20197F1F754DE02FF12C082E291EA8B
+:101F80000197F1F7F894BB9A1BBE15BA10925F0245
+:101F9000EAE7F8E1E4918E2F81508E3F88F012C07D
+:101FA000109268008091660090916700019690936E
+:101FB00067008093660080369A4E08F499CEDECF93
+:081FC000E1BF00005BCC2ACF59
+:061FC8005AFF187A4008E0
+:040000030000188061
+:00000001FF
diff --git a/firmware/releases/micronucleus-1.10_LEDonPB1.hex b/firmware/releases/micronucleus-1.10_LEDonPB1.hex
new file mode 100644
index 0000000..074a0d6
--- /dev/null
+++ b/firmware/releases/micronucleus-1.10_LEDonPB1.hex
@@ -0,0 +1,122 @@
+:0800000057CC56CC8CCC54CC3B
+:1018800017C016C04CC014C009021200010100802C
+:101890003209040000000000000012011001FF00E6
+:1018A0000008D01653070A010000000104030904D0
+:1018B00011241FBECFE5D2E0CDBFDEBF00EB0F93FA
+:1018C00007E00F9310E0A0E6B0E0EAEDFFE102C010
+:1018D00005900D92A636B107D9F720E0A6E6B0E054
+:1018E00001C01D92AB39B207E1F7ECC1A82FB92FA7
+:1018F00080E090E041E050EA609530E009C02D9131
+:1019000082279795879510F084279527305EC8F336
+:101910006F5FA8F30895EADF8D939D930895CF93A9
+:10192000CFB7CF93C0915F02C03B21F4C0915E025C
+:10193000C73021F0CF91CFBFCF91A1CFCC27C39596
+:10194000B39BE9F7B39B0BC0B39B09C0B39B07C024
+:10195000B39B05C0B39B03C0B39B01C0D3C00F9220
+:10196000DF93C0917E00DD27CB57DF4F012EB39B65
+:1019700003C0DF910F90E6CF2F930F931F934F93E8
+:101980002FEF4F6F06B303FB20F95F933F9350E0B7
+:101990003BE065C016B30126502953FDC89556B3E8
+:1019A000012703FB25F92F7306B3B1F05027102749
+:1019B00013FB26F906B22230F0F000C016B301275F
+:1019C00003FB27F90126502906B22430E8F54F77AA
+:1019D000206816B30000F6CF50274F7D206206B274
+:1019E000102F000000C006B300265029102713FB5B
+:1019F00026F906B2E2CF4F7B06B3206400C0DACFEF
+:101A000001265029187106B269F14E7F2160012F1D
+:101A100016B328C0002650294D7F06B22260102F31
+:101A200029C0012650294B7F06B22460012F2DC00A
+:101A300016B301265029477F2860000006B22EC049
+:101A40004F7E06B3206130C0422706B3499300267B
+:101A50005029102706B24FEF13FB20F9297F16B348
+:101A600079F2187159F10126502906B2012703FBBA
+:101A700021F9237F06B371F2002650293150D0F0AE
+:101A800006B2102713FB22F9277E16B351F2012666
+:101A90005029012703FB06B223F92F7C49F20000ED
+:101AA00006B3102713FB24F90026502906B22F791C
+:101AB00039F270CF10E21ABF002717C03B503195A2
+:101AC000C31BD04010E21ABF0881033CF9F00B346D
+:101AD000E9F020917C001981110F1213EDCF093626
+:101AE00051F10D3211F0013E39F7009383003F911F
+:101AF0005F914F911F910F912F91DF910F90CAB776
+:101B0000C5FD1DCFCF91CFBFCF91189520918300F8
+:101B1000222369F310918100112321F5343022F141
+:101B20003093810020937D0010917E003BE0311BBB
+:101B300030937E0019C00091810001309CF40AE5C9
+:101B40003091600034FD11C000936000C1E7D0E027
+:101B500010C0052710E000C021C0052710E0C8957F
+:101B600008BB14C03AE501C032ED032EC0E0D0E05E
+:101B700032E017B31861C39A08B317BB58E120E8E5
+:101B80004FEF20FF052708BB279517951C3F28F727
+:101B900000004552B0F720FF0527279508BB179591
+:101BA0001C3FB8F629913A9561F7077E10918200A3
+:101BB000110F08BBC250D04011F010937C0010E20E
+:101BC0001ABF086017B3177E402F477E54E05A951E
+:101BD000F1F708BB17BB48BB8ACFF8942FEFB0E8EA
+:101BE000A0E44AE0B1BF000081EE9CE0B399FECFD3
+:101BF000B39BFECF0197B399FDCF97FF03C0BA1BEC
+:101C0000819501C0BA0FA69529F4281710F031B7B5
+:101C1000282FA1E0415031F731BF0000789408959A
+:101C2000F894E0916A00F0916B00329785E0809320
+:101C30005700E89578940895E0916A00F0916B0060
+:101C4000309729F490936D0080936C0007C0E430C6
+:101C5000F10539F490936F0080936E008FE39CEC54
+:101C60001CC0EC3728E1F20739F480916C009091A8
+:101C70006D008E539C4F11C0EE3728E1F20739F406
+:101C800080916E0090916F008D539C4F06C0EA3793
+:101C900028E1F20711F481B790E02FB7F89430975C
+:101CA00021F431E130935700E89531E00C01309395
+:101CB0005700E89511243296F0936B00E0936A0088
+:101CC0002FBF089514BE88E10FB6F89481BD11BCF2
+:101CD0000FBEC198BB9A88E893E1ECE9F1E0319737
+:101CE000F1F70197D1F7BB98AC9A8BB780628BBFA5
+:101CF000789400918100035007FDBAC080917E0066
+:101D0000CCE0D0E0C81BD109CB57DF4F80917D00DC
+:101D10008D3209F08EC0083009F0A8C083EC8093A2
+:101D200071008AE580936000109269002881922FEB
+:101D300090768981992319F110926700811108C06A
+:101D400082E690E09093800080937F0014E067C06B
+:101D5000813051F48C819D8190936B0080936A0057
+:101D600027FD58C01FEF57C090916800823011F4D2
+:101D7000916001C094609093680010E050C09A8117
+:101D800010927A00811106C010927B008AE790E0E1
+:101D900012E03BC0853019F4909382002CC086304D
+:101DA00009F58B81813019F48AE998E104C0823009
+:101DB00041F488E898E19093800080937F0012E1DD
+:101DC0000DC0833051F4911108C08CEA98E19093D2
+:101DD000800080937F0014E001C010E080E48093D5
+:101DE00069001DC0883059F0893019F4909384003F
+:101DF00002C08A3039F08AE790E010E006C084E83B
+:101E000090E002C08AE790E011E090938000809318
+:101E10007F0005C01E8180E88093690007C08F8124
+:101E2000811104C08E81811708F4182F109361006E
+:101E30001DC08091690087FF19C080916A00909150
+:101E40006B008038984128F080916A008F7339F0D8
+:101E50000DC089919991F0DE025079F7F5CF80910C
+:101E60006800826080936800109261001092810087
+:101E70008091600084FF43C0809161008F3F09F42E
+:101E80003EC0082F893008F008E0801B8093610075
+:101E90008091710098E8892780937100002319F1DF
+:101EA000E0917F00F09180008091690086FF0BC077
+:101EB000A2E7B0E084918D93319682E790E0800FA5
+:101EC0008A13F8CF0CC0CF01A2E7B0E0FC0121914A
+:101ED000CF012D9322E730E0200F2A13F7CFF093A4
+:101EE0008000E0937F00602F82E790E014DD0C5FBC
+:101EF0000C3019F08FEF809361000093600084E153
+:101F000096B3987131F48150D9F7109282001092F3
+:101F10007C0001E0811100E080917000801739F0B1
+:101F2000011103C01092670058DE009370008CE925
+:101F300091E00197F1F70091680000FF17C0F89455
+:101F4000E0E8F8E1E054F10983E080935700E89578
+:101F50003097C1F710926B0010926A0088E0F82E5B
+:101F60008FEF9FEF69DEFA94D9F75ADE01FF05C0C3
+:101F70008AE390E20197F1F753DE02FF13C0B998AC
+:101F800082E291EA0197F1F7F894BB9A1BBE15BA69
+:101F900010925F02EAE7F8E1E4918E2F81508E3FC4
+:101FA000C0F019C010926800809167008D7011F028
+:101FB000B99801C0B99A8091660090916700019626
+:101FC000909367008093660080369A4E08F491CE15
+:0A1FD000D6CFE1BF000052CC22CFB3
+:061FDA005AFF187A4008CE
+:040000030000188061
+:00000001FF
diff --git a/firmware/releases/release notes.txt b/firmware/releases/release notes.txt
index 792a177..18deb4f 100644
--- a/firmware/releases/release notes.txt
+++ b/firmware/releases/release notes.txt
@@ -1,3 +1,39 @@
+== 1.10rc3 - 2013-12-15 ==
+firmware:
+ o Major reorganization of the source and build system.
+ - Used own crt1.s to create vector table in the first flash-page.
+ - Removed all functions related to vector-table writing.
+ - Refactored code and inlined all functions that were only called once.
+ - Removed redundantly defined types to avoid confusion. Only C99 types are used now.
+ o Size is now 1878 bytes, 6314 bytes user space. No changes to functionality.
+
+== 1.10rc2 - 2013-11-25 ==
+
+firmware:
+ o It seems that the USB specification does not define a maximum delay from device power up until
+ the host issues a bus reset. Therefore too short delays AUTO_EXIT_NO_USB_MS can lead to the
+ bootloader exiting before enumeration on some systems. Disabled AUTO_EXIT_NO_USB_MS in default configuration.
+
+== 1.10rc1 - 2013-11-25 ==
+
+firmware:
+Version jump to 1.10 due to major changes in firmware by @cpldcpu.
+ o Reduced code size to below 2kb (1974 with standard configuration) by implementing oscillator
+ calibration in assembler and various local code tweaking. See Github commit history for full details.
+ This version has 6208 bytes programmable code space.
+ o Micronucleus will now simulate an USB-disconnect when exiting the bootloader. This prevents various
+ issues with having a non-responsive USB device, including crashing the host tool. It is now possible
+ to enter the bootloader again by resetting the device using the watchdog timer or the reset input without
+ physically disconnecting from USB.
+ o Cleaned up bootloaderconfig.h
+ o Introduced a second time-out (AUTO_EXIT_NO_USB_MS) if no USB reset from the host is detected. This can be used
+ to quit the bootloader early if the device is not connected to USB. The bootloader will enter the user
+ program after ~0.8s with the default settings instead of 6s when USB is connected.
+ o Introduced optional code to flash a LED. See LED_PRESENT in bootloaderconfig.h for details.
+ Careful: Right now enabling the LED-code requires setting the bootloader base address to 0x1800 due
+ to increased code size.
+
+
== 1.06-jumper-v2 - 2013-5-20 ==
firmware:
diff --git a/firmware/usbconfig.h b/firmware/usbconfig.h
index 55707cb..560c34d 100644
--- a/firmware/usbconfig.h
+++ b/firmware/usbconfig.h
@@ -158,11 +158,18 @@
* for each control- and out-endpoint to check for duplicate packets.
*/
//#if USB_CFG_CLOCK_KHZ==16500
-#define USB_CFG_HAVE_MEASURE_FRAME_LENGTH 1
-#include "osccal.h"
-//#else
-//#define USB_CFG_HAVE_MEASURE_FRAME_LENGTH 0
-//#endif
+
+//#include "osccal.h"
+
+#ifndef __ASSEMBLER__
+ void calibrateOscillatorASM(void);
+ extern uint16_t idlePolls;
+# define USB_RESET_HOOK(resetStarts) if(!resetStarts){ ((uint8_t*)&idlePolls)[1]= 0;calibrateOscillatorASM();}
+
+# define USB_CFG_HAVE_MEASURE_FRAME_LENGTH 0
+#endif
+
+
/* define this macro to 1 if you want the function usbMeasureFrameLength()
* compiled in. This function can be used to calibrate the AVR's RC oscillator.
*/
diff --git a/firmware/usbdrv/Changelog.txt b/firmware/usbdrv/Changelog.txt
index 5c6354a..79b5215 100644
--- a/firmware/usbdrv/Changelog.txt
+++ b/firmware/usbdrv/Changelog.txt
@@ -306,3 +306,24 @@ Scroll down to the bottom to see the most recent changes.
endpoint now.
* Release 2010-07-15
+
+ - Fixed bug in usbDriverSetup() which prevented descriptor sizes above 255
+ bytes.
+ - Avoid a compiler warning for unused parameter in usbHandleResetHook() when
+ compiler option -Wextra is enabled.
+ - Fixed wrong hex value for some IDs in USB-IDs-for-free.txt.
+ - Keep a define for USBATTR_BUSPOWER, although the flag does not exist
+ in USB 1.1 any more. Set it to 0. This is for backward compatibility.
+
+* Release 2012-01-09
+
+ - Define a separate (defined) type for usbMsgPtr so that projects using a
+ tiny memory model can define it to an 8 bit type in usbconfig.h. This
+ change also saves a couple of bytes when using a scalar 16 bit type.
+ - Inserted "const" keyword for all PROGMEM declarations because new GCC
+ requires it.
+ - Fixed problem with dependence of usbportability.h on usbconfig.h. This
+ problem occurred with IAR CC only.
+ - Prepared repository for github.com.
+
+* Release 2012-12-06 \ No newline at end of file
diff --git a/firmware/usbdrv/CommercialLicense.txt b/firmware/usbdrv/CommercialLicense.txt
index 11d07d9..de1a2b0 100644
--- a/firmware/usbdrv/CommercialLicense.txt
+++ b/firmware/usbdrv/CommercialLicense.txt
@@ -1,5 +1,5 @@
V-USB Driver Software License Agreement
-Version 2009-08-03
+Version 2012-07-09
THIS LICENSE AGREEMENT GRANTS YOU CERTAIN RIGHTS IN A SOFTWARE. YOU CAN
ENTER INTO THIS AGREEMENT AND ACQUIRE THE RIGHTS OUTLINED BELOW BY PAYING
@@ -37,10 +37,10 @@ Product ID(s), sent to you in e-mail. These Product IDs are reserved
exclusively for you. OBJECTIVE DEVELOPMENT has obtained USB Product ID
ranges under the Vendor ID 5824 from Wouter van Ooijen (Van Ooijen
Technische Informatica, www.voti.nl) and under the Vendor ID 8352 from
-Jason Kotzin (Clay Logic, www.claylogic.com). Both owners of the Vendor IDs
-have obtained these IDs from the USB Implementers Forum, Inc.
-(www.usb.org). OBJECTIVE DEVELOPMENT disclaims all liability which might
-arise from the assignment of USB IDs.
+Jason Kotzin (now flirc.tv, Inc.). Both owners of the Vendor IDs have
+obtained these IDs from the USB Implementers Forum, Inc. (www.usb.org).
+OBJECTIVE DEVELOPMENT disclaims all liability which might arise from the
+assignment of USB IDs.
2.5 USB Certification. Although not part of this agreement, we want to make
it clear that you cannot become USB certified when you use V-USB or a USB
diff --git a/firmware/usbdrv/USB-ID-FAQ.txt b/firmware/usbdrv/USB-ID-FAQ.txt
index d1de8fb..a4a6bd6 100644
--- a/firmware/usbdrv/USB-ID-FAQ.txt
+++ b/firmware/usbdrv/USB-ID-FAQ.txt
@@ -1,4 +1,4 @@
-Version 2009-08-22
+Version 2012-07-09
==========================
WHY DO WE NEED THESE IDs?
@@ -107,8 +107,8 @@ WHO IS THE OWNER OF THE VENDOR-ID?
Objective Development has obtained ranges of USB Product-IDs under two
Vendor-IDs: Under Vendor-ID 5824 from Wouter van Ooijen (Van Ooijen
Technische Informatica, www.voti.nl) and under Vendor-ID 8352 from Jason
-Kotzin (Clay Logic, www.claylogic.com). Both VID owners have received their
-Vendor-ID directly from usb.org.
+Kotzin (now flirc.tv, Inc.). Both VID owners have received their Vendor-ID
+directly from usb.org.
=========================================================================
diff --git a/firmware/usbdrv/USB-IDs-for-free.txt b/firmware/usbdrv/USB-IDs-for-free.txt
index 2f4d59a..d46517d 100644
--- a/firmware/usbdrv/USB-IDs-for-free.txt
+++ b/firmware/usbdrv/USB-IDs-for-free.txt
@@ -86,8 +86,9 @@ If you use one of the IDs listed below, your device and host-side software
must conform to these rules:
(1) The USB device MUST provide a textual representation of the serial
-number. The serial number string MUST be available at least in USB language
-0x0409 (English/US).
+number, unless ONLY the operating system's default class driver is used.
+The serial number string MUST be available at least in USB language 0x0409
+(English/US).
(2) The serial number MUST start with either an Internet domain name (e.g.
"mycompany.com") registered and owned by you, or an e-mail address under your
@@ -108,6 +109,11 @@ driver for Vendor Class devices is needed, this driver must be libusb or
libusb-win32 (see http://libusb.org/ and
http://libusb-win32.sourceforge.net/).
+(7) If ONLY the operating system's default class driver is used, e.g. for
+mice, keyboards, joysticks, CDC or MIDI devices and no discrimination by an
+application is needed, the serial number may be omitted.
+
+
Table if IDs for discrimination by serial number string:
PID dec (hex) | VID dec (hex) | Description of use
@@ -121,11 +127,11 @@ PID dec (hex) | VID dec (hex) | Description of use
---------------+---------------+-------------------------------------------
10203 (0x27db) | 5824 (0x16c0) | For USB Keyboards
---------------+---------------+-------------------------------------------
-10204 (0x27db) | 5824 (0x16c0) | For USB Joysticks
+10204 (0x27dc) | 5824 (0x16c0) | For USB Joysticks
---------------+---------------+-------------------------------------------
-10205 (0x27dc) | 5824 (0x16c0) | For CDC-ACM class devices (modems)
+10205 (0x27dd) | 5824 (0x16c0) | For CDC-ACM class devices (modems)
---------------+---------------+-------------------------------------------
-10206 (0x27dd) | 5824 (0x16c0) | For MIDI class devices
+10206 (0x27de) | 5824 (0x16c0) | For MIDI class devices
---------------+---------------+-------------------------------------------
diff --git a/firmware/usbdrv/asmcommon.inc b/firmware/usbdrv/asmcommon.inc
index 07d692b..d2a4f7c 100644
--- a/firmware/usbdrv/asmcommon.inc
+++ b/firmware/usbdrv/asmcommon.inc
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2007 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * Revision: $Id$
*/
/* Do not link this file! Link usbdrvasm.S instead, which includes the
diff --git a/firmware/usbdrv/oddebug.c b/firmware/usbdrv/oddebug.c
index 945457c..19bf142 100644
--- a/firmware/usbdrv/oddebug.c
+++ b/firmware/usbdrv/oddebug.c
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2005 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: oddebug.c 692 2008-11-07 15:07:40Z cs $
*/
#include "oddebug.h"
diff --git a/firmware/usbdrv/oddebug.h b/firmware/usbdrv/oddebug.h
index d61309d..851f84d 100644
--- a/firmware/usbdrv/oddebug.h
+++ b/firmware/usbdrv/oddebug.h
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2005 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: oddebug.h 692 2008-11-07 15:07:40Z cs $
*/
#ifndef __oddebug_h_included__
diff --git a/firmware/usbdrv/usbconfig-prototype.h b/firmware/usbdrv/usbconfig-prototype.h
index 847710e..93721c2 100644
--- a/firmware/usbdrv/usbconfig-prototype.h
+++ b/firmware/usbdrv/usbconfig-prototype.h
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2005 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: usbconfig-prototype.h 785 2010-05-30 17:57:07Z cs $
*/
#ifndef __usbconfig_h_included__
@@ -356,6 +355,15 @@ section at the end of this file).
#define USB_CFG_DESCR_PROPS_HID_REPORT 0
#define USB_CFG_DESCR_PROPS_UNKNOWN 0
+
+#define usbMsgPtr_t unsigned short
+/* If usbMsgPtr_t is not defined, it defaults to 'uchar *'. We define it to
+ * a scalar type here because gcc generates slightly shorter code for scalar
+ * arithmetics than for pointer arithmetics. Remove this define for backward
+ * type compatibility or define it to an 8 bit type if you use data in RAM only
+ * and all RAM is below 256 bytes (tiny memory model in IAR CC).
+ */
+
/* ----------------------- Optional MCU Description ------------------------ */
/* The following configurations have working defaults in usbdrv.h. You
diff --git a/firmware/usbdrv/usbdrv.c b/firmware/usbdrv/usbdrv.c
index 21ed554..d838935 100644
--- a/firmware/usbdrv/usbdrv.c
+++ b/firmware/usbdrv/usbdrv.c
@@ -5,10 +5,8 @@
* Tabsize: 4
* Copyright: (c) 2005 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: usbdrv.c 791 2010-07-15 15:56:13Z cs $
*/
-#include "usbportability.h"
#include "usbdrv.h"
#include "oddebug.h"
@@ -45,7 +43,7 @@ uchar usbCurrentDataToken;/* when we check data toggling to ignore duplica
#endif
/* USB status registers / not shared with asm code */
-uchar *usbMsgPtr; /* data to transmit next -- ROM or RAM address */
+usbMsgPtr_t usbMsgPtr; /* data to transmit next -- ROM or RAM address */
static usbMsgLen_t usbMsgLen = USB_NO_MSG; /* remaining number of bytes */
static uchar usbMsgFlags; /* flag values see below */
@@ -67,7 +65,7 @@ optimizing hints:
#if USB_CFG_DESCR_PROPS_STRING_0 == 0
#undef USB_CFG_DESCR_PROPS_STRING_0
#define USB_CFG_DESCR_PROPS_STRING_0 sizeof(usbDescriptorString0)
-PROGMEM char usbDescriptorString0[] = { /* language descriptor */
+PROGMEM const char usbDescriptorString0[] = { /* language descriptor */
4, /* sizeof(usbDescriptorString0): length of descriptor in bytes */
3, /* descriptor type */
0x09, 0x04, /* language index (0x0409 = US-English) */
@@ -77,7 +75,7 @@ PROGMEM char usbDescriptorString0[] = { /* language descriptor */
#if USB_CFG_DESCR_PROPS_STRING_VENDOR == 0 && USB_CFG_VENDOR_NAME_LEN
#undef USB_CFG_DESCR_PROPS_STRING_VENDOR
#define USB_CFG_DESCR_PROPS_STRING_VENDOR sizeof(usbDescriptorStringVendor)
-PROGMEM int usbDescriptorStringVendor[] = {
+PROGMEM const int usbDescriptorStringVendor[] = {
USB_STRING_DESCRIPTOR_HEADER(USB_CFG_VENDOR_NAME_LEN),
USB_CFG_VENDOR_NAME
};
@@ -86,7 +84,7 @@ PROGMEM int usbDescriptorStringVendor[] = {
#if USB_CFG_DESCR_PROPS_STRING_PRODUCT == 0 && USB_CFG_DEVICE_NAME_LEN
#undef USB_CFG_DESCR_PROPS_STRING_PRODUCT
#define USB_CFG_DESCR_PROPS_STRING_PRODUCT sizeof(usbDescriptorStringDevice)
-PROGMEM int usbDescriptorStringDevice[] = {
+PROGMEM const int usbDescriptorStringDevice[] = {
USB_STRING_DESCRIPTOR_HEADER(USB_CFG_DEVICE_NAME_LEN),
USB_CFG_DEVICE_NAME
};
@@ -95,7 +93,7 @@ PROGMEM int usbDescriptorStringDevice[] = {
#if USB_CFG_DESCR_PROPS_STRING_SERIAL_NUMBER == 0 && USB_CFG_SERIAL_NUMBER_LEN
#undef USB_CFG_DESCR_PROPS_STRING_SERIAL_NUMBER
#define USB_CFG_DESCR_PROPS_STRING_SERIAL_NUMBER sizeof(usbDescriptorStringSerialNumber)
-PROGMEM int usbDescriptorStringSerialNumber[] = {
+PROGMEM const int usbDescriptorStringSerialNumber[] = {
USB_STRING_DESCRIPTOR_HEADER(USB_CFG_SERIAL_NUMBER_LEN),
USB_CFG_SERIAL_NUMBER
};
@@ -108,7 +106,7 @@ PROGMEM int usbDescriptorStringSerialNumber[] = {
#if USB_CFG_DESCR_PROPS_DEVICE == 0
#undef USB_CFG_DESCR_PROPS_DEVICE
#define USB_CFG_DESCR_PROPS_DEVICE sizeof(usbDescriptorDevice)
-PROGMEM char usbDescriptorDevice[] = { /* USB device descriptor */
+PROGMEM const char usbDescriptorDevice[] = { /* USB device descriptor */
18, /* sizeof(usbDescriptorDevice): length of descriptor in bytes */
USBDESCR_DEVICE, /* descriptor type */
0x10, 0x01, /* USB version supported */
@@ -139,7 +137,7 @@ PROGMEM char usbDescriptorDevice[] = { /* USB device descriptor */
#if USB_CFG_DESCR_PROPS_CONFIGURATION == 0
#undef USB_CFG_DESCR_PROPS_CONFIGURATION
#define USB_CFG_DESCR_PROPS_CONFIGURATION sizeof(usbDescriptorConfiguration)
-PROGMEM char usbDescriptorConfiguration[] = { /* USB configuration descriptor */
+PROGMEM const char usbDescriptorConfiguration[] = { /* USB configuration descriptor */
9, /* sizeof(usbDescriptorConfiguration): length of descriptor in bytes */
USBDESCR_CONFIG, /* descriptor type */
18 + 7 * USB_CFG_HAVE_INTRIN_ENDPOINT + 7 * USB_CFG_HAVE_INTRIN_ENDPOINT3 +
@@ -301,7 +299,7 @@ USB_PUBLIC void usbSetInterrupt3(uchar *data, uchar len)
len = usbFunctionDescriptor(rq); \
}else{ \
len = USB_PROP_LENGTH(cfgProp); \
- usbMsgPtr = (uchar *)(staticName); \
+ usbMsgPtr = (usbMsgPtr_t)(staticName); \
} \
}
@@ -361,7 +359,8 @@ uchar flags = USB_FLG_MSGPTR_IS_ROM;
*/
static inline usbMsgLen_t usbDriverSetup(usbRequest_t *rq)
{
-uchar len = 0, *dataPtr = usbTxBuf + 9; /* there are 2 bytes free space at the end of the buffer */
+usbMsgLen_t len = 0;
+uchar *dataPtr = usbTxBuf + 9; /* there are 2 bytes free space at the end of the buffer */
uchar value = rq->wValue.bytes[0];
#if USB_CFG_IMPLEMENT_HALT
uchar index = rq->wIndex.bytes[0];
@@ -408,7 +407,7 @@ uchar index = rq->wIndex.bytes[0];
SWITCH_DEFAULT /* 7=SET_DESCRIPTOR, 12=SYNC_FRAME */
/* Should we add an optional hook here? */
SWITCH_END
- usbMsgPtr = dataPtr;
+ usbMsgPtr = (usbMsgPtr_t)dataPtr;
skipMsgPtrAssignment:
return len;
}
@@ -498,7 +497,8 @@ static uchar usbDeviceRead(uchar *data, uchar len)
}else
#endif
{
- uchar i = len, *r = usbMsgPtr;
+ uchar i = len;
+ usbMsgPtr_t r = usbMsgPtr;
if(usbMsgFlags & USB_FLG_MSGPTR_IS_ROM){ /* ROM data */
do{
uchar c = USB_READ_FLASH(r); /* assign to char size variable to enforce byte ops */
@@ -507,7 +507,8 @@ static uchar usbDeviceRead(uchar *data, uchar len)
}while(--i);
}else{ /* RAM data */
do{
- *data++ = *r++;
+ *data++ = *((uchar *)r);
+ r++;
}while(--i);
}
usbMsgPtr = r;
@@ -557,6 +558,8 @@ uchar isReset = !notResetState;
USB_RESET_HOOK(isReset);
wasReset = isReset;
}
+#else
+ notResetState = notResetState; // avoid compiler warning
#endif
}
diff --git a/firmware/usbdrv/usbdrv.h b/firmware/usbdrv/usbdrv.h
index d8a4a16..3fe84d5 100644
--- a/firmware/usbdrv/usbdrv.h
+++ b/firmware/usbdrv/usbdrv.h
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2005 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: usbdrv.h 793 2010-07-15 15:58:11Z cs $
*/
#ifndef __usbdrv_h_included__
@@ -122,7 +121,7 @@ USB messages, even if they address another (low-speed) device on the same bus.
/* --------------------------- Module Interface ---------------------------- */
/* ------------------------------------------------------------------------- */
-#define USBDRV_VERSION 20100715
+#define USBDRV_VERSION 20121206
/* This define uniquely identifies a driver version. It is a decimal number
* constructed from the driver's release date in the form YYYYMMDD. If the
* driver's behavior or interface changes, you can use this constant to
@@ -163,6 +162,17 @@ USB messages, even if they address another (low-speed) device on the same bus.
*/
#define USB_NO_MSG ((usbMsgLen_t)-1) /* constant meaning "no message" */
+#ifndef usbMsgPtr_t
+#define usbMsgPtr_t uchar *
+#endif
+/* Making usbMsgPtr_t a define allows the user of this library to define it to
+ * an 8 bit type on tiny devices. This reduces code size, especially if the
+ * compiler supports a tiny memory model.
+ * The type can be a pointer or scalar type, casts are made where necessary.
+ * Although it's paradoxical, Gcc 4 generates slightly better code for scalar
+ * types than for pointers.
+ */
+
struct usbRequest; /* forward declaration */
USB_PUBLIC void usbInit(void);
@@ -178,7 +188,7 @@ USB_PUBLIC void usbPoll(void);
* Please note that debug outputs through the UART take ~ 0.5ms per byte
* at 19200 bps.
*/
-extern uchar *usbMsgPtr;
+extern usbMsgPtr_t usbMsgPtr;
/* This variable may be used to pass transmit data to the driver from the
* implementation of usbFunctionWrite(). It is also used internally by the
* driver for standard control requests.
@@ -210,7 +220,7 @@ USB_PUBLIC usbMsgLen_t usbFunctionSetup(uchar data[8]);
* Note that calls to the functions usbFunctionRead() and usbFunctionWrite()
* are only done if enabled by the configuration in usbconfig.h.
*/
-//USB_PUBLIC usbMsgLen_t usbFunctionDescriptor(struct usbRequest *rq);
+USB_PUBLIC usbMsgLen_t usbFunctionDescriptor(struct usbRequest *rq);
/* You need to implement this function ONLY if you provide USB descriptors at
* runtime (which is an expert feature). It is very similar to
* usbFunctionSetup() above, but it is called only to request USB descriptor
@@ -390,13 +400,13 @@ extern volatile schar usbRxLen;
* about the various methods to define USB descriptors. If you do nothing,
* the default descriptors will be used.
*/
-#define USB_PROP_IS_DYNAMIC (1 << 14)
+#define USB_PROP_IS_DYNAMIC (1u << 14)
/* If this property is set for a descriptor, usbFunctionDescriptor() will be
* used to obtain the particular descriptor. Data directly returned via
* usbMsgPtr are FLASH data by default, combine (OR) with USB_PROP_IS_RAM to
* return RAM data.
*/
-#define USB_PROP_IS_RAM (1 << 15)
+#define USB_PROP_IS_RAM (1u << 15)
/* If this property is set for a descriptor, the data is read from RAM
* memory instead of Flash. The property is used for all methods to provide
* external descriptors.
@@ -450,43 +460,43 @@ extern volatile schar usbRxLen;
#ifndef __ASSEMBLER__
extern
#if !(USB_CFG_DESCR_PROPS_DEVICE & USB_PROP_IS_RAM)
-PROGMEM
+PROGMEM const
#endif
char usbDescriptorDevice[];
extern
#if !(USB_CFG_DESCR_PROPS_CONFIGURATION & USB_PROP_IS_RAM)
-PROGMEM
+PROGMEM const
#endif
char usbDescriptorConfiguration[];
extern
#if !(USB_CFG_DESCR_PROPS_HID_REPORT & USB_PROP_IS_RAM)
-PROGMEM
+PROGMEM const
#endif
char usbDescriptorHidReport[];
extern
#if !(USB_CFG_DESCR_PROPS_STRING_0 & USB_PROP_IS_RAM)
-PROGMEM
+PROGMEM const
#endif
char usbDescriptorString0[];
extern
#if !(USB_CFG_DESCR_PROPS_STRING_VENDOR & USB_PROP_IS_RAM)
-PROGMEM
+PROGMEM const
#endif
int usbDescriptorStringVendor[];
extern
#if !(USB_CFG_DESCR_PROPS_STRING_PRODUCT & USB_PROP_IS_RAM)
-PROGMEM
+PROGMEM const
#endif
int usbDescriptorStringDevice[];
extern
#if !(USB_CFG_DESCR_PROPS_STRING_SERIAL_NUMBER & USB_PROP_IS_RAM)
-PROGMEM
+PROGMEM const
#endif
int usbDescriptorStringSerialNumber[];
@@ -719,6 +729,7 @@ typedef struct usbRequest{
#define USBDESCR_HID_PHYS 0x23
//#define USBATTR_BUSPOWER 0x80 // USB 1.1 does not define this value any more
+#define USBATTR_BUSPOWER 0
#define USBATTR_SELFPOWER 0x40
#define USBATTR_REMOTEWAKE 0x20
diff --git a/firmware/usbdrv/usbdrvasm.S b/firmware/usbdrv/usbdrvasm.S
index 45fcf18..32ce8ef 100644
--- a/firmware/usbdrv/usbdrvasm.S
+++ b/firmware/usbdrv/usbdrvasm.S
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2007 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * Revision: $Id: usbdrvasm.S 785 2010-05-30 17:57:07Z cs $
*/
/*
diff --git a/firmware/usbdrv/usbdrvasm.asm b/firmware/usbdrv/usbdrvasm.asm
index 9cc4e4d..fb66934 100644
--- a/firmware/usbdrv/usbdrvasm.asm
+++ b/firmware/usbdrv/usbdrvasm.asm
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2006 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id$
*/
/*
diff --git a/firmware/usbdrv/usbdrvasm12.inc b/firmware/usbdrv/usbdrvasm12.inc
index 78a14e0..d3bd056 100644
--- a/firmware/usbdrv/usbdrvasm12.inc
+++ b/firmware/usbdrv/usbdrvasm12.inc
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2007 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: usbdrvasm12.inc 740 2009-04-13 18:23:31Z cs $
*/
/* Do not link this file! Link usbdrvasm.S instead, which includes the
@@ -41,50 +40,8 @@ DATAx (rx) to ACK/NAK/STALL (tx) 2 7.5 16-60
USB_INTR_VECTOR:
;order of registers pushed: YL, SREG [sofError], YH, shift, x1, x2, x3, cnt
push YL ;2 [35] push only what is necessary to sync with edge ASAP
-
in YL, SREG ;1 [37]
push YL ;2 [39]
-
- in YL, TIMSK
- cpi YL, 0
- breq compare2 ; don't go to app if equal (possible bootloader)
-
- ; prep and jump to app vector
- pop YL
- out SREG, YL
- pop YL
- rjmp __vectors - 2
-
-compare2:
- in YL, TCNT2
- cpi YL, 0xFF
- breq bootloaderExt0 ; don't go to app if equal (bootloader)
-
- ; prep and jump to app vector
- pop YL
- out SREG, YL
- pop YL
-
- ; some errors with 1 nop
- ;nop
- ;nop
- ;nop
- ;nop
- ;nop
- ;nop
- ;nop
- ;nop
- ;nop
- ;nop
-
-
- rjmp __vectors - 2
-
-
-bootloaderExt0:
- ldi YL, 0
-
-
;----------------------------------------------------------------------------
; Synchronize with sync pattern:
;----------------------------------------------------------------------------
@@ -432,4 +389,4 @@ skipAddrAssign:
out USBOUT, x1 ;[16] <-- out J (idle) -- end of SE0 (EOP signal)
out USBDDR, x2 ;[17] <-- release bus now
out USBOUT, x3 ;[18] <-- ensure no pull-up resistors are active
- rjmp doReturn \ No newline at end of file
+ rjmp doReturn
diff --git a/firmware/usbdrv/usbdrvasm128.inc b/firmware/usbdrv/usbdrvasm128.inc
index bcd6621..8f67bcc 100644
--- a/firmware/usbdrv/usbdrvasm128.inc
+++ b/firmware/usbdrv/usbdrvasm128.inc
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2008 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: usbdrvasm128.inc 758 2009-08-06 10:12:54Z cs $
*/
/* Do not link this file! Link usbdrvasm.S instead, which includes the
diff --git a/firmware/usbdrv/usbdrvasm15.inc b/firmware/usbdrv/usbdrvasm15.inc
index 401b7f8..33bcf0e 100644
--- a/firmware/usbdrv/usbdrvasm15.inc
+++ b/firmware/usbdrv/usbdrvasm15.inc
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2007 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * Revision: $Id: usbdrvasm15.inc 740 2009-04-13 18:23:31Z cs $
*/
/* Do not link this file! Link usbdrvasm.S instead, which includes the
diff --git a/firmware/usbdrv/usbdrvasm16.inc b/firmware/usbdrv/usbdrvasm16.inc
index 207b6e4..25b84e6 100644
--- a/firmware/usbdrv/usbdrvasm16.inc
+++ b/firmware/usbdrv/usbdrvasm16.inc
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2007 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * Revision: $Id: usbdrvasm16.inc 760 2009-08-09 18:59:43Z cs $
*/
/* Do not link this file! Link usbdrvasm.S instead, which includes the
diff --git a/firmware/usbdrv/usbdrvasm18-crc.inc b/firmware/usbdrv/usbdrvasm18-crc.inc
index f83347d..0ff2f42 100644
--- a/firmware/usbdrv/usbdrvasm18-crc.inc
+++ b/firmware/usbdrv/usbdrvasm18-crc.inc
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2008 by Lukas Schrittwieser and OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * Revision: $Id: usbdrvasm18-crc.inc 740 2009-04-13 18:23:31Z cs $
*/
/* Do not link this file! Link usbdrvasm.S instead, which includes the
diff --git a/firmware/usbdrv/usbdrvasm20.inc b/firmware/usbdrv/usbdrvasm20.inc
index 303abaf..5027edd 100644
--- a/firmware/usbdrv/usbdrvasm20.inc
+++ b/firmware/usbdrv/usbdrvasm20.inc
@@ -6,7 +6,6 @@
* Tabsize: 4
* Copyright: (c) 2008 by Jeroen Benschop and OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * Revision: $Id: usbdrvasm20.inc 740 2009-04-13 18:23:31Z cs $
*/
/* Do not link this file! Link usbdrvasm.S instead, which includes the
diff --git a/firmware/usbdrv/usbportability.h b/firmware/usbdrv/usbportability.h
index 476184d..0a861d0 100644
--- a/firmware/usbdrv/usbportability.h
+++ b/firmware/usbdrv/usbportability.h
@@ -5,7 +5,6 @@
* Tabsize: 4
* Copyright: (c) 2008 by OBJECTIVE DEVELOPMENT Software GmbH
* License: GNU GPL v2 (see License.txt), GNU GPL v3 or proprietary (CommercialLicense.txt)
- * This Revision: $Id: usbportability.h 785 2010-05-30 17:57:07Z cs $
*/
/*