From db7828504e70b301ab73524b95e44adc900d9bc9 Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Tue, 3 Dec 2024 00:30:39 +0000
Subject: [PATCH 01/43] [cron] Bump distribution date (2024-12-03)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 07a14787202a..86256e81f5dc 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-02"
+//#define STRING_DISTRIBUTION_DATE "2024-12-03"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index ade37929b247..9eec4e3fa337 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-02"
+ #define STRING_DISTRIBUTION_DATE "2024-12-03"
#endif
/**
From 9cbab467b491dbbaf0ee78be126431abf6925f81 Mon Sep 17 00:00:00 2001
From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com>
Date: Tue, 3 Dec 2024 15:47:57 -0800
Subject: [PATCH 02/43] =?UTF-8?q?=F0=9F=93=9D=20Add=20Bluesky=20badge=20(#?=
=?UTF-8?q?27560)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
README.md | 1 +
1 file changed, 1 insertion(+)
diff --git a/README.md b/README.md
index 4d835685d105..160c288aad82 100644
--- a/README.md
+++ b/README.md
@@ -9,6 +9,7 @@
+
From 94bd6d52e9d7b04d99e3754ca004f4bd3acad29f Mon Sep 17 00:00:00 2001
From: ellensp <530024+ellensp@users.noreply.github.com>
Date: Wed, 4 Dec 2024 12:50:25 +1300
Subject: [PATCH 03/43] =?UTF-8?q?=F0=9F=94=A8=20Fix=20ESP32=20build=20(for?=
=?UTF-8?q?=20xtensa32)=20(#27561)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
buildroot/share/PlatformIO/scripts/preprocessor.py | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/buildroot/share/PlatformIO/scripts/preprocessor.py b/buildroot/share/PlatformIO/scripts/preprocessor.py
index d409f32f27b7..5355fa4e923a 100644
--- a/buildroot/share/PlatformIO/scripts/preprocessor.py
+++ b/buildroot/share/PlatformIO/scripts/preprocessor.py
@@ -86,8 +86,8 @@ def search_compiler(env):
# Use any item in $PATH corresponding to a platformio toolchain bin folder
if ppath.match(env['PROJECT_PACKAGES_DIR'] + "/**/bin"):
for gpath in ppath.glob(gcc_exe):
- # Skip '*-elf-g++' (crosstool-NG)
- if not gpath.stem.endswith('-elf-g++'):
+ # Skip '*-elf-g++' (crosstool-NG) except for xtensa32
+ if not "xtensa32" not in str(gpath) and gpath.stem.endswith('-elf-g++'):
gccpath = str(gpath.resolve())
break
From 63a7d42f30112027216ebd75010e3b5689182f2d Mon Sep 17 00:00:00 2001
From: ellensp <530024+ellensp@users.noreply.github.com>
Date: Wed, 4 Dec 2024 12:55:33 +1300
Subject: [PATCH 04/43] =?UTF-8?q?=F0=9F=93=9D=20TinyBee=20note:=205V=20out?=
=?UTF-8?q?-only=20pins!=20(#27563)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 21 ++++++++++++---------
1 file changed, 12 insertions(+), 9 deletions(-)
diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h
index 282ac5288d6c..4c043fd36335 100644
--- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h
+++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h
@@ -43,7 +43,7 @@
//
// Servos
//
-#define SERVO0_PIN 2 // 3D TOUCH
+#define SERVO0_PIN 2 // 3D TOUCH, Pin is level-shifted to 5V, and cannot be used as an INPUT pin!
//
// Limit Switches
@@ -121,14 +121,17 @@
#define ADC_REFERENCE_VOLTAGE 2.565 // 2.5V reference VDDA
/**
- * ------ ------
- * (BEEPER) 149 | 1 2 | 13 (BTN_ENC) (SPI MISO) 19 | 1 2 | 18 (SPI SCK)
- * (LCD_EN) 21 | 3 4 | 4 (LCD_RS) (BTN_EN1) 14 | 3 4 | 5 (SPI CS)
- * (LCD_D4) 0 | 5 6 16 (LCD_D5) (BTN_EN2) 12 | 5 6 23 (SPI MOSI)
- * (LCD_D6) 15 | 7 8 | 17 (LCD_D7) (SPI_DET) 34 | 7 8 | RESET
- * GND | 9 10 | 5V GND | 9 10 | 3.3V
- * ------ ------
- * EXP1 EXP2
+ * ------ ------
+ * (BEEPER) 149 | 1 2 | 13 (BTN_ENC) (SPI MISO) 19 | 1 2 | 18 (SPI SCK)
+ * (LCD_EN) 21* | 3 4 | 4* (LCD_RS) (BTN_EN1) 14 | 3 4 | 5 (SPI CS)
+ * (LCD_D4) 0* | 5 6 16* (LCD_D5) (BTN_EN2) 12 | 5 6 23 (SPI MOSI)
+ * (LCD_D6) 15* | 7 8 | 17* (LCD_D7) (SPI_DET) 34 | 7 8 | RESET
+ * GND | 9 10 | 5V GND | 9 10 | 3.3V
+ * ------ ------
+ * EXP1 EXP2
+ *
+ * * = Note: Pin is level-shifted to 5V. Cannot be used as an INPUT pin!
+ * Displays like a CR10_STOCKDISPLAY that require inputs on EXP1 cannot be plugged straight into this board.
*/
#define EXP1_01_PIN 149
From 00c28eb9e3b4a4a996e7ad7fd391cdd07710d65f Mon Sep 17 00:00:00 2001
From: Andrew <18502096+classicrocker883@users.noreply.github.com>
Date: Tue, 3 Dec 2024 18:59:45 -0500
Subject: [PATCH 05/43] =?UTF-8?q?=F0=9F=94=A8=20Update=20hc32.ini=20(board?=
=?UTF-8?q?=5Fupload.offset=5Faddress)=20(#27550)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/HAL/HC32/README.md | 2 +-
ini/hc32.ini | 26 +++++++++++++-------------
2 files changed, 14 insertions(+), 14 deletions(-)
diff --git a/Marlin/src/HAL/HC32/README.md b/Marlin/src/HAL/HC32/README.md
index c9ae8a9a20ef..ed11c4003514 100644
--- a/Marlin/src/HAL/HC32/README.md
+++ b/Marlin/src/HAL/HC32/README.md
@@ -11,7 +11,7 @@ The HC32F460 HAL is designed to be generic enough for any HC32F460-based board.
- Examine the board's main processor. (Refer the naming key in `hc32.ini`.)
- Extend the `HC32F460C_common` base env for 256K, or `HC32F460E_common` for 512K.
3. Determine your board's application start address (see [below](#finding-the-application-start-address))
-4. Set `board_build.ld_args.flash_start` to the app start address once you've found it. If your board doesn't use a bootloader, you may be able to use the "ICSP" header or DFU. This document will be updated once we have more information about flashing without a bootloader.
+4. Set `board_upload.offset_address` to the app start address once you've found it. If your board doesn't use a bootloader, you may be able to use the "ICSP" header or DFU. This document will be updated once we have more information about flashing without a bootloader.
### Finding the application start address
diff --git a/ini/hc32.ini b/ini/hc32.ini
index 71a1e35c3730..a99614beeca6 100644
--- a/ini/hc32.ini
+++ b/ini/hc32.ini
@@ -35,12 +35,12 @@ build_src_filter = ${common.default_src_filter} + +
Date: Wed, 4 Dec 2024 01:01:37 +0000
Subject: [PATCH 06/43] [cron] Bump distribution date (2024-12-04)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 86256e81f5dc..8d157cce0f19 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-03"
+//#define STRING_DISTRIBUTION_DATE "2024-12-04"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index 9eec4e3fa337..a7a9c4b11e96 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-03"
+ #define STRING_DISTRIBUTION_DATE "2024-12-04"
#endif
/**
From 257ffe98b19bc2e54187ec5c612086e41f1db35f Mon Sep 17 00:00:00 2001
From: Chris <52449218+shadow578@users.noreply.github.com>
Date: Wed, 4 Dec 2024 02:44:54 +0100
Subject: [PATCH 07/43] =?UTF-8?q?=F0=9F=90=9B=20Fix=20HC32=20Clock=20Confi?=
=?UTF-8?q?guration=20(#27099)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/HAL/HC32/app_config.h | 11 +-
Marlin/src/HAL/HC32/sysclock.cpp | 237 ++++++++++++++++++++++---------
Marlin/src/HAL/HC32/sysclock.h | 65 +++++++++
Marlin/src/HAL/HC32/timers.h | 15 +-
Marlin/src/inc/Warnings.cpp | 7 -
5 files changed, 246 insertions(+), 89 deletions(-)
create mode 100644 Marlin/src/HAL/HC32/sysclock.h
diff --git a/Marlin/src/HAL/HC32/app_config.h b/Marlin/src/HAL/HC32/app_config.h
index fb291419fc10..b971903bba3a 100644
--- a/Marlin/src/HAL/HC32/app_config.h
+++ b/Marlin/src/HAL/HC32/app_config.h
@@ -8,6 +8,7 @@
#define _HC32_APP_CONFIG_H_
#include "../../inc/MarlinConfigPre.h"
+#include "sysclock.h"
//
// dev mode
@@ -64,12 +65,8 @@
// redirect printf to host serial
#define REDIRECT_PRINTF_TO_SERIAL 1
-// F_CPU must be known at compile time, but on HC32F460 it's not.
-// Thus we assume HCLK to be 200MHz, as that's what is configured in
-// 'core_hook_sysclock_init' in 'sysclock.cpp'.
-// If you face issues with this assumption, please double-check with the values
-// printed by 'MarlinHAL::HAL_clock_frequencies_dump'.
-// see also: HAL_TIMER_RATE in timers.h
-#define F_CPU 200000000 // 200MHz HCLK
+// F_CPU is F_HCLK, as that's the main CPU core's clock.
+// see 'sysclock.h' for more information.
+#define F_CPU F_HCLK
#endif // _HC32_APP_CONFIG_H_
diff --git a/Marlin/src/HAL/HC32/sysclock.cpp b/Marlin/src/HAL/HC32/sysclock.cpp
index 475be3bbc9cb..493515b0e88f 100644
--- a/Marlin/src/HAL/HC32/sysclock.cpp
+++ b/Marlin/src/HAL/HC32/sysclock.cpp
@@ -26,64 +26,144 @@
#ifdef ARDUINO_ARCH_HC32
-// Get BOARD_XTAL_FREQUENCY from configuration / pins
#include "../../inc/MarlinConfig.h"
+#include "sysclock.h"
#include
#include
+/***
+ * @brief Automatically calculate M, N, P values for the MPLL to reach a target frequency.
+ * @param input_frequency The input frequency.
+ * @param target_frequency The target frequency.
+ * @return The MPLL configuration structure. Q and R are not set.
+ *
+ * @note
+ * Simplified MPLL block diagram, with intermediary clocks (1) = VCO_in, (2) = VCO_out:
+ *
+ * INPUT -> [/ M] -(1)-> [* N] -(2)-|-> [/ P] -> MPLL-P
+ */
+constexpr stc_clk_mpll_cfg_t get_mpll_config(double input_frequency, double target_frequency) {
+ // PLL input clock divider: M in [1, 24]
+ for (uint32_t M = 1; M <= 24; M++) {
+ double f_vco_in = input_frequency / M;
+
+ // 1 <= VCO_in <= 25 MHz
+ if (f_vco_in < 1e6 || f_vco_in > 25e6) continue;
+
+ // VCO multiplier: N in [20, 480]
+ for (uint32_t N = 20; N <= 480; N++) {
+ double f_vco_out = f_vco_in * N;
+
+ // 240 <= VCO_out <= 480 MHz
+ if (f_vco_out < 240e6 || f_vco_out > 480e6) continue;
+
+ // Output "P" divider: P in [2, 16]
+ for (uint32_t P = 2; P <= 16; P++) {
+ double f_calculated_out = f_vco_out / P;
+ if (f_calculated_out == target_frequency) {
+ // Found a match, return it
+ return {
+ .PllpDiv = P,
+ .PllqDiv = P, // Don't care for Q and R
+ .PllrDiv = P, // "
+ .plln = N,
+ .pllmDiv = M
+ };
+ }
+ }
+ }
+ }
+
+ // If no valid M, N, P found, return invalid config
+ return { 0, 0, 0, 0, 0 };
+}
+
+/**
+ * @brief Get the division factor required to get the target frequency from the input frequency.
+ * @tparam input_freq The input frequency.
+ * @tparam target_freq The target frequency.
+ * @return The division factor.
+ */
+template
+constexpr en_clk_sysclk_div_factor_t get_division_factor() {
+ // Calculate the divider to get the target frequency
+ constexpr float fdivider = static_cast(input_freq) / static_cast(target_freq);
+ constexpr int divider = static_cast(fdivider);
+
+ // divider must be an integer
+ static_assert(fdivider == divider, "Target frequency not achievable, divider must be an integer");
+
+ // divider must be between 1 and 64 (enum range), and must be a power of 2
+ static_assert(divider >= 1 && divider <= 64, "Invalid divider, out of range");
+ static_assert((divider & (divider - 1)) == 0, "Invalid divider, not a power of 2");
+
+ // return the divider
+ switch (divider) {
+ case 1: return ClkSysclkDiv1;
+ case 2: return ClkSysclkDiv2;
+ case 4: return ClkSysclkDiv4;
+ case 8: return ClkSysclkDiv8;
+ case 16: return ClkSysclkDiv16;
+ case 32: return ClkSysclkDiv32;
+ case 64: return ClkSysclkDiv64;
+ }
+}
+
+/**
+ * @brief Validate the runtime clocks match the expected values.
+ */
+void validate_system_clocks() {
+ #define CLOCK_ASSERT(expected, actual) \
+ if (expected != actual) { \
+ SERIAL_ECHOPGM( \
+ "Clock Mismatch for " #expected ": " \
+ "expected ", expected, \
+ ", got ", actual \
+ ); \
+ CORE_ASSERT_FAIL("Clock Mismatch: " #expected); \
+ }
+
+ update_system_clock_frequencies();
+
+ CLOCK_ASSERT(F_SYSTEM_CLOCK, SYSTEM_CLOCK_FREQUENCIES.system);
+ CLOCK_ASSERT(F_HCLK, SYSTEM_CLOCK_FREQUENCIES.hclk);
+ CLOCK_ASSERT(F_EXCLK, SYSTEM_CLOCK_FREQUENCIES.exclk);
+ CLOCK_ASSERT(F_PCLK0, SYSTEM_CLOCK_FREQUENCIES.pclk0);
+ CLOCK_ASSERT(F_PCLK1, SYSTEM_CLOCK_FREQUENCIES.pclk1);
+ CLOCK_ASSERT(F_PCLK2, SYSTEM_CLOCK_FREQUENCIES.pclk2);
+ CLOCK_ASSERT(F_PCLK3, SYSTEM_CLOCK_FREQUENCIES.pclk3);
+ CLOCK_ASSERT(F_PCLK4, SYSTEM_CLOCK_FREQUENCIES.pclk4);
+}
+
+/**
+ * @brief Configure HC32 system clocks.
+ *
+ * This function is called by the Arduino core early in the startup process, before setup() is called.
+ * It is used to configure the system clocks to the desired state.
+ *
+ * See https://github.com/MarlinFirmware/Marlin/pull/27099 for more information.
+ */
void core_hook_sysclock_init() {
// Set wait cycles, as we are about to switch to 200 MHz HCLK
sysclock_configure_flash_wait_cycles();
sysclock_configure_sram_wait_cycles();
- // Configure MPLLp to 200 MHz output, with different settings depending on XTAL availability
- #if BOARD_XTAL_FREQUENCY == 8000000 // 8 MHz XTAL
- // - M = 1 => 8 MHz / 1 = 8 MHz
- // - N = 50 => 8 MHz * 50 = 400 MHz
- // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk)
- // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care)
- stc_clk_mpll_cfg_t pllConf = {
- .PllpDiv = 2u, // P
- .PllqDiv = 4u, // Q
- .PllrDiv = 4u, // R
- .plln = 50u, // N
- .pllmDiv = 1u, // M
- };
- sysclock_configure_xtal();
- sysclock_configure_mpll(ClkPllSrcXTAL, &pllConf);
-
- #elif BOARD_XTAL_FREQUENCY == 16000000 // 16 MHz XTAL
- // - M = 1 => 16 MHz / 1 = 16 MHz
- // - N = 50 => 16 MHz * 25 = 400 MHz
- // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk)
- // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care)
- stc_clk_mpll_cfg_t pllConf = {
- .PllpDiv = 2u, // P
- .PllqDiv = 4u, // Q
- .PllrDiv = 4u, // R
- .plln = 50u, // N
- .pllmDiv = 1u, // M
- };
+ // Select MPLL input frequency based on clock availability
+ #if BOARD_XTAL_FREQUENCY == 8000000 || BOARD_XTAL_FREQUENCY == 16000000 // 8 MHz or 16 MHz XTAL
+ constexpr uint32_t mpll_input_clock = BOARD_XTAL_FREQUENCY;
+
sysclock_configure_xtal();
- sysclock_configure_mpll(ClkPllSrcXTAL, &pllConf);
- #warning "HC32F460 with 16 MHz XTAL has not been tested."
+ #if BOARD_XTAL_FREQUENCY == 16000000
+ #warning "HC32F460 with 16 MHz XTAL has not been tested."
+ #endif
#else // HRC (16 MHz)
- // - M = 1 => 16 MHz / 1 = 16 MHz
- // - N = 25 => 16 MHz * 25 = 400 MHz
- // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk)
- // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care)
- stc_clk_mpll_cfg_t pllConf = {
- .PllpDiv = 2u, // P
- .PllqDiv = 4u, // Q
- .PllrDiv = 4u, // R
- .plln = 25u, // N
- .pllmDiv = 1u, // M
- };
+
+ constexpr uint32_t mpll_input_clock = 16000000;
+
sysclock_configure_hrc();
- sysclock_configure_mpll(ClkPllSrcHRC, &pllConf);
// HRC could have been configured by ICG to 20 MHz
// TODO: handle gracefully if HRC is not 16 MHz
@@ -91,29 +171,56 @@ void core_hook_sysclock_init() {
panic("HRC is not 16 MHz");
}
- #ifdef BOARD_XTAL_FREQUENCY
+ #if defined(BOARD_XTAL_FREQUENCY)
#warning "No valid XTAL frequency defined, falling back to HRC."
#endif
+
#endif
- // sysclk is now configured according to F_CPU (i.e., 200MHz PLL output)
- const uint32_t sysclock = F_CPU;
+ // Automagically calculate MPLL configuration
+ constexpr stc_clk_mpll_cfg_t pllConf = get_mpll_config(mpll_input_clock, F_SYSTEM_CLOCK);
+ static_assert(pllConf.pllmDiv != 0 && pllConf.plln != 0 && pllConf.PllpDiv != 0, "MPLL auto-configuration failed");
+ sysclock_configure_mpll(ClkPllSrcXTAL, &pllConf);
- // Setup clock divisors for sysclk = 200 MHz
- // Note: PCLK1 is used for step+temp timers, and need to be kept at 50 MHz (until there is a better solution)
+ // Setup clock divisors
constexpr stc_clk_sysclk_cfg_t sysClkConf = {
- .enHclkDiv = ClkSysclkDiv1, // HCLK = 200 MHz (CPU)
- .enExclkDiv = ClkSysclkDiv2, // EXCLK = 100 MHz (SDIO)
- .enPclk0Div = ClkSysclkDiv2, // PCLK0 = 100 MHz (Timer6 (not used))
- .enPclk1Div = ClkSysclkDiv4, // PCLK1 = 50 MHz (USART, SPI, I2S, Timer0 (step+temp), TimerA (Servo))
- .enPclk2Div = ClkSysclkDiv8, // PCLK2 = 25 MHz (ADC)
- .enPclk3Div = ClkSysclkDiv8, // PCLK3 = 25 MHz (I2C, WDT)
- .enPclk4Div = ClkSysclkDiv2, // PCLK4 = 100 MHz (ADC ctl)
+ .enHclkDiv = get_division_factor(),
+ .enExclkDiv = get_division_factor(),
+ .enPclk0Div = get_division_factor(),
+ .enPclk1Div = get_division_factor(),
+ .enPclk2Div = get_division_factor(),
+ .enPclk3Div = get_division_factor(),
+ .enPclk4Div = get_division_factor(),
};
+ sysclock_set_clock_dividers(&sysClkConf);
+
+ // Set power mode, before switch
+ power_mode_update_pre(F_SYSTEM_CLOCK);
+
+ // Switch to MPLL-P as system clock source
+ CLK_SetSysClkSource(CLKSysSrcMPLL);
+
+ // Set power mode, after switch
+ power_mode_update_post(F_SYSTEM_CLOCK);
+ // Verify clocks match expected values (at runtime)
+ #if ENABLED(MARLIN_DEV_MODE) || ENABLED(ALWAYS_VALIDATE_CLOCKS)
+ validate_system_clocks();
+ #endif
+
+ // Verify clock configuration (at compile time)
#if ARDUINO_CORE_VERSION_INT >= GET_VERSION_INT(1, 2, 0)
+ assert_mpll_config_valid<
+ mpll_input_clock,
+ pllConf.pllmDiv,
+ pllConf.plln,
+ pllConf.PllpDiv,
+ pllConf.PllqDiv,
+ pllConf.PllrDiv
+ >();
+
assert_system_clocks_valid<
- sysclock,
+ F_SYSTEM_CLOCK,
sysClkConf.enHclkDiv,
sysClkConf.enPclk0Div,
sysClkConf.enPclk1Div,
@@ -122,18 +229,14 @@ void core_hook_sysclock_init() {
sysClkConf.enPclk4Div,
sysClkConf.enExclkDiv
>();
- #endif
- sysclock_set_clock_dividers(&sysClkConf);
-
- // Set power mode
- power_mode_update_pre(sysclock);
-
- // Switch to MPLL as sysclk source
- CLK_SetSysClkSource(CLKSysSrcMPLL);
-
- // Set power mode
- power_mode_update_post(sysclock);
+ static_assert(get_mpll_output_clock(
+ mpll_input_clock,
+ pllConf.pllmDiv,
+ pllConf.plln,
+ pllConf.PllpDiv
+ ) == F_SYSTEM_CLOCK, "actual MPLL output clock does not match F_SYSTEM_CLOCK");
+ #endif
}
#endif // ARDUINO_ARCH_HC32
diff --git a/Marlin/src/HAL/HC32/sysclock.h b/Marlin/src/HAL/HC32/sysclock.h
new file mode 100644
index 000000000000..783d5677e9de
--- /dev/null
+++ b/Marlin/src/HAL/HC32/sysclock.h
@@ -0,0 +1,65 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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.
+ *
+ * This program 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 this program. If not, see .
+ *
+ */
+#pragma once
+
+/**
+ * HC32F460 system clock configuration.
+ *
+ * With the HC32 HAL, the various peripheral clocks (including the CPU clock) are derived
+ * from the main PLL (MPLL-P) output (referred to at F_SYSTEM_CLOCK).
+ *
+ * F_SYSTEM_CLOCK is the target frequency of the main PLL, and the PLL is automatically configured
+ * to achieve this frequency.
+ *
+ * The peripheral clocks are the result of integer division of F_SYSTEM_CLOCK.
+ * Their target frequencies are defined here, and the required division factors are calculated automatically.
+ * Note that the division factor must be a power of 2 between 1 and 64.
+ * If the target frequency is not achievable, a compile-time error will be generated.
+ *
+ * Additionally, there are interdependencies between the peripheral clocks, which are described in
+ * Section 4.4 "Working Clock Specifications" of the HC32F460 Reference Manual.
+ * With Arduino core >= 1.2.0, these interdependencies are checked at compile time.
+ * On earlier versions, you are on your own.
+ *
+ * For all clock frequencies, they can be checked at runtime by enabling the 'ALWAYS_VALIDATE_CLOCKS' define.
+ * In MARLIN_DEV_MODE, they will also be printed to the serial console by 'MarlinHAL::HAL_clock_frequencies_dump'.
+ *
+ * See https://github.com/MarlinFirmware/Marlin/pull/27099 for more information.
+ */
+
+// Target peripheral clock frequencies, must be integer divisors of F_SYSTEM_CLOCK.
+// Changing the frequency here will automagically update everything else.
+#define F_HCLK 200000000UL // 200 MHz; CPU
+#define F_EXCLK (F_HCLK / 2) // 100 MHz; SDIO
+#define F_PCLK0 (F_HCLK / 2) // 100 MHz; Timer6 (unused)
+#define F_PCLK1 (F_HCLK / 4) // 50 MHz; USART, SPI, Timer0 (step + temp), TimerA (Servo)
+#define F_PCLK2 (F_HCLK / 8) // 25 MHz; ADC Sampling
+#define F_PCLK3 (F_HCLK / 8) // 25 MHz; I2C, WDT
+#define F_PCLK4 (F_HCLK / 2) // 100 MHz; ADC Control
+
+// MPLL-P clock target frequency. This must be >= the highest peripheral clock frequency.
+// PLL config is automatically calculated based on this value.
+#define F_SYSTEM_CLOCK F_HCLK
+
+// The Peripheral clocks are only checked at runtime if this is enabled OR MARLIN_DEV_MODE is enabled.
+// Compile time checks are always performed with Arduino core version >= 1.2.0.
+#define ALWAYS_VALIDATE_CLOCKS 1
diff --git a/Marlin/src/HAL/HC32/timers.h b/Marlin/src/HAL/HC32/timers.h
index f5a590deb1f5..c0014df60404 100644
--- a/Marlin/src/HAL/HC32/timers.h
+++ b/Marlin/src/HAL/HC32/timers.h
@@ -20,6 +20,7 @@
#pragma once
#include
#include
+#include "sysclock.h"
//
// Timer Types
@@ -42,17 +43,15 @@ extern Timer0 step_timer;
* HAL_TIMER_RATE must be known at compile time since it's used to calculate
* STEPPER_TIMER_RATE, which is used in 'constexpr' calculations.
* On the HC32F460 the timer rate depends on PCLK1, which is derived from the
- * system clock configured at runtime. As a workaround, we use the existing
- * assumption of a 200MHz clock, defining F_CPU as 200000000, then configure PCLK1
- * as F_CPU with a divider of 4 in 'sysclock.cpp::core_hook_sysclock_init'.
+ * system clock configured at runtime.
+ * Thus we use the 'F_PCLK1' constant defined in 'sysclock.h'.
*
- * If you face issues with this assumption, please double-check with the values
- * printed by 'MarlinHAL::HAL_clock_frequencies_dump'.
+ * See https://github.com/MarlinFirmware/Marlin/pull/27099 for more information.
*
- * TODO: If the 'constexpr' requirement is ever lifted, use TIMER0_BASE_FREQUENCY instead
+ * NOTE: If the 'constexpr' requirement is ever lifted, TIMER0_BASE_FREQUENCY could
+ * be used instead. Tho this would probably not make any noticable difference.
*/
-#define HAL_TIMER_RATE (F_CPU / 4) // i.e., 50MHz
-//#define HAL_TIMER_RATE TIMER0_BASE_FREQUENCY
+#define HAL_TIMER_RATE F_PCLK1
// Temperature timer
#define TEMP_TIMER_NUM (&temp_timer)
diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp
index 229755c6d0ab..a6ea570030f0 100644
--- a/Marlin/src/inc/Warnings.cpp
+++ b/Marlin/src/inc/Warnings.cpp
@@ -919,13 +919,6 @@
#warning "EDITABLE_STEPS_PER_UNIT is required to enable G92 runtime configuration of steps-per-unit."
#endif
-/**
- * HC32 clock speed is hard-coded in Marlin
- */
-#if defined(ARDUINO_ARCH_HC32) && F_CPU == 200000000
- #warning "HC32 clock is assumed to be 200MHz. If this isn't the case for your board please submit a report so we can add support."
-#endif
-
/**
* Peltier with PIDTEMPBED
*/
From 5549d07da34a4ba597aab6064a79457618992c75 Mon Sep 17 00:00:00 2001
From: Red Echidna UK <64329845+RedEchidnaUK@users.noreply.github.com>
Date: Thu, 5 Dec 2024 00:20:10 +0000
Subject: [PATCH 08/43] =?UTF-8?q?=F0=9F=9A=B8=20G34=20Z-align=20in=20ProUI?=
=?UTF-8?q?=20Home=20menu=20(#27567)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
Co-authored-by: Ashley Baker
---
Marlin/src/lcd/e3v2/proui/dwin.cpp | 10 ++++++++++
1 file changed, 10 insertions(+)
diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp
index 8ed75ae1c004..c4d94d68b671 100644
--- a/Marlin/src/lcd/e3v2/proui/dwin.cpp
+++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp
@@ -2207,6 +2207,13 @@ void setMoveX() { hmiValue.axis = X_AXIS; setPFloatOnClick(X_MIN_POS, X_MAX_POS,
void setMoveY() { hmiValue.axis = Y_AXIS; setPFloatOnClick(Y_MIN_POS, Y_MAX_POS, UNITFDIGITS, applyMove, liveMove); }
void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, UNITFDIGITS, applyMove, liveMove); }
+#if ENABLED(Z_STEPPER_AUTO_ALIGN)
+ void autoZAlign() {
+ LCD_MESSAGE(MSG_AUTO_Z_ALIGN);
+ queue.inject(F("G34"));
+ }
+#endif
+
#if HAS_HOTEND
void setMoveE() {
const float e_min = current_position.e - (EXTRUDE_MAXLENGTH),
@@ -4102,6 +4109,9 @@ void drawMaxAccelMenu() {
#if HAS_Z_AXIS
MENU_ITEM(ICON_HomeZ, MSG_AUTO_HOME_Z, onDrawMenuItem, homeZ);
#endif
+ #if ENABLED(Z_STEPPER_AUTO_ALIGN)
+ MENU_ITEM(ICON_HomeZ, MSG_AUTO_Z_ALIGN, onDrawMenuItem, autoZAlign);
+ #endif
#if ENABLED(MESH_BED_LEVELING)
EDIT_ITEM(ICON_ZAfterHome, MSG_Z_AFTER_HOME, onDrawPInt8Menu, setZAfterHoming, &hmiData.zAfterHoming);
#endif
From e733e50207765d5c9861db31af6c774b9cd6f2b5 Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Thu, 5 Dec 2024 00:29:46 +0000
Subject: [PATCH 09/43] [cron] Bump distribution date (2024-12-05)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 8d157cce0f19..0b42cb99685e 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-04"
+//#define STRING_DISTRIBUTION_DATE "2024-12-05"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index a7a9c4b11e96..1bb8d5744680 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-04"
+ #define STRING_DISTRIBUTION_DATE "2024-12-05"
#endif
/**
From 4668b2715802fcb75f640b07e1783c41f2b0a91d Mon Sep 17 00:00:00 2001
From: Andrew <18502096+classicrocker883@users.noreply.github.com>
Date: Thu, 5 Dec 2024 14:57:57 -0500
Subject: [PATCH 10/43] =?UTF-8?q?=F0=9F=94=A8=20Reduce=20some=20256KB=20Ma?=
=?UTF-8?q?ple=20builds=20(#27488)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
ini/stm32f1-maple.ini | 24 ++++++++++++++++--------
1 file changed, 16 insertions(+), 8 deletions(-)
diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini
index b2f14a61644b..59150f38586c 100644
--- a/ini/stm32f1-maple.ini
+++ b/ini/stm32f1-maple.ini
@@ -32,7 +32,8 @@ build_src_filter = ${common.default_src_filter} + -
Date: Fri, 6 Dec 2024 12:20:25 +1300
Subject: [PATCH 11/43] =?UTF-8?q?=F0=9F=94=A8=20Fix=20ESP32=20build=20(for?=
=?UTF-8?q?=20xtensa32)=20(2)=20(#27570)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
Followup to #27561
---
buildroot/share/PlatformIO/scripts/preprocessor.py | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/buildroot/share/PlatformIO/scripts/preprocessor.py b/buildroot/share/PlatformIO/scripts/preprocessor.py
index 5355fa4e923a..bda00dfd2717 100644
--- a/buildroot/share/PlatformIO/scripts/preprocessor.py
+++ b/buildroot/share/PlatformIO/scripts/preprocessor.py
@@ -87,7 +87,7 @@ def search_compiler(env):
if ppath.match(env['PROJECT_PACKAGES_DIR'] + "/**/bin"):
for gpath in ppath.glob(gcc_exe):
# Skip '*-elf-g++' (crosstool-NG) except for xtensa32
- if not "xtensa32" not in str(gpath) and gpath.stem.endswith('-elf-g++'):
+ if not gpath.stem.endswith('-elf-g++') or "xtensa32" in str(gpath):
gccpath = str(gpath.resolve())
break
@@ -95,7 +95,7 @@ def search_compiler(env):
for ppath in envpath:
for gpath in ppath.glob(gcc_exe):
# Skip macOS Clang
- if gpath != 'usr/bin/g++' or env['PLATFORM'] != 'darwin':
+ if not (gpath == 'usr/bin/g++' and env['PLATFORM'] == 'darwin'):
gccpath = str(gpath.resolve())
break
From 5813488412aa3731d24177a037653087aeeb72ef Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Fri, 6 Dec 2024 00:29:38 +0000
Subject: [PATCH 12/43] [cron] Bump distribution date (2024-12-06)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 0b42cb99685e..41a645ee680c 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-05"
+//#define STRING_DISTRIBUTION_DATE "2024-12-06"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index 1bb8d5744680..e0cd06133dd2 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-05"
+ #define STRING_DISTRIBUTION_DATE "2024-12-06"
#endif
/**
From ea993a657f1c42df16c2bc03f30c7c9224647b49 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Thu, 5 Dec 2024 22:02:20 -0600
Subject: [PATCH 13/43] =?UTF-8?q?=F0=9F=94=A8=20More=20informative=20probe?=
=?UTF-8?q?=20conflict=20message?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/inc/SanityCheck.h | 49 +++++++++++++++++++++++++++++++++++-
1 file changed, 48 insertions(+), 1 deletion(-)
diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h
index 9ec17b28089e..6e9e6358ab54 100644
--- a/Marlin/src/inc/SanityCheck.h
+++ b/Marlin/src/inc/SanityCheck.h
@@ -1225,7 +1225,54 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
#if 1 < 0 \
+ (DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE) \
+ COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, BD_SENSOR, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4, MAG_MOUNTED_PROBE, BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2)
- #error "Please enable only one probe option: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, BD_SENSOR, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, MAGLEV4, MAG_MOUNTED_PROBE, BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2, or Z Servo."
+ #error "Please enable only one probe option. See the following errors:"
+ #if DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE
+ #error "(Z_SERVO_PROBE is enabled.)"
+ #elif ENABLED(BLTOUCH) && !HAS_Z_SERVO_PROBE
+ #error "(BLTOUCH is enabled.)"
+ #endif
+ #if ENABLED(PROBE_MANUALLY)
+ #error "(PROBE_MANUALLY is enabled.)"
+ #endif
+ #if ENABLED(BD_SENSOR)
+ #error "(BD_SENSOR is enabled.)"
+ #endif
+ #if ENABLED(FIX_MOUNTED_PROBE)
+ #error "(FIX_MOUNTED_PROBE is enabled.)"
+ #endif
+ #if ENABLED(NOZZLE_AS_PROBE)
+ #error "(NOZZLE_AS_PROBE is enabled.)"
+ #endif
+ #if ENABLED(TOUCH_MI_PROBE)
+ #error "(TOUCH_MI_PROBE is enabled.)"
+ #endif
+ #if ENABLED(SOLENOID_PROBE)
+ #error "(SOLENOID_PROBE is enabled.)"
+ #endif
+ #if ENABLED(Z_PROBE_ALLEN_KEY)
+ #error "(Z_PROBE_ALLEN_KEY is enabled.)"
+ #endif
+ #if ENABLED(Z_PROBE_SLED)
+ #error "(Z_PROBE_SLED is enabled.)"
+ #endif
+ #if ENABLED(RACK_AND_PINION_PROBE)
+ #error "(RACK_AND_PINION_PROBE is enabled.)"
+ #endif
+ #if ENABLED(SENSORLESS_PROBING)
+ #error "(SENSORLESS_PROBING is enabled.)"
+ #endif
+ #if ENABLED(MAGLEV4)
+ #error "(MAGLEV4 is enabled.)"
+ #endif
+ #if ENABLED(MAG_MOUNTED_PROBE)
+ #error "(MAG_MOUNTED_PROBE is enabled.)"
+ #endif
+ #if ENABLED(BIQU_MICROPROBE_V1)
+ #error "(BIQU_MICROPROBE_V1 is enabled.)"
+ #endif
+ #if ENABLED(BIQU_MICROPROBE_V2)
+ #error "(BIQU_MICROPROBE_V2 is enabled.)"
+ #endif
#endif
#if HAS_BED_PROBE
From c271a89a4fead7bdca111a002980ce4732f8d95b Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Thu, 5 Dec 2024 22:06:13 -0600
Subject: [PATCH 14/43] =?UTF-8?q?=F0=9F=8E=A8=20Servo=20angles=20tweaks?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/inc/Conditionals-4-adv.h | 16 ++++++-------
Marlin/src/module/servo.h | 37 ++++++++++-------------------
2 files changed, 20 insertions(+), 33 deletions(-)
diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h
index ccded2eec635..be651206423f 100644
--- a/Marlin/src/inc/Conditionals-4-adv.h
+++ b/Marlin/src/inc/Conditionals-4-adv.h
@@ -51,39 +51,39 @@
#define NUM_SERVOS 0
#if HAS_Z_SERVO_PROBE && NUM_SERVOS <= Z_PROBE_SERVO_NR
#undef NUM_SERVOS
- #define NUM_SERVOS (Z_PROBE_SERVO_NR + 1)
+ #define NUM_SERVOS INCREMENT(Z_PROBE_SERVO_NR)
#endif
#if ENABLED(CHAMBER_VENT) && NUM_SERVOS <= CHAMBER_VENT_SERVO_NR
#undef NUM_SERVOS
- #define NUM_SERVOS (CHAMBER_VENT_SERVO_NR + 1)
+ #define NUM_SERVOS INCREMENT(CHAMBER_VENT_SERVO_NR)
#endif
#if ENABLED(SWITCHING_TOOLHEAD) && NUM_SERVOS <= SWITCHING_TOOLHEAD_SERVO_NR
#undef NUM_SERVOS
- #define NUM_SERVOS (SWITCHING_TOOLHEAD_SERVO_NR + 1)
+ #define NUM_SERVOS INCREMENT(SWITCHING_TOOLHEAD_SERVO_NR)
#endif
#if ENABLED(SWITCHING_NOZZLE)
#if NUM_SERVOS <= SWITCHING_NOZZLE_SERVO_NR
#undef NUM_SERVOS
- #define NUM_SERVOS (SWITCHING_NOZZLE_SERVO_NR + 1)
+ #define NUM_SERVOS INCREMENT(SWITCHING_NOZZLE_SERVO_NR)
#endif
#if NUM_SERVOS <= SWITCHING_NOZZLE_E1_SERVO_NR
#undef NUM_SERVOS
- #define NUM_SERVOS (SWITCHING_NOZZLE_E1_SERVO_NR + 1)
+ #define NUM_SERVOS INCREMENT(SWITCHING_NOZZLE_E1_SERVO_NR)
#endif
#endif
#if ENABLED(SWITCHING_EXTRUDER)
#if NUM_SERVOS <= SWITCHING_EXTRUDER_SERVO_NR
#undef NUM_SERVOS
- #define NUM_SERVOS (SWITCHING_EXTRUDER_SERVO_NR + 1)
+ #define NUM_SERVOS INCREMENT(SWITCHING_EXTRUDER_SERVO_NR)
#endif
#if NUM_SERVOS <= SWITCHING_EXTRUDER_E23_SERVO_NR
#undef NUM_SERVOS
- #define NUM_SERVOS (SWITCHING_EXTRUDER_E23_SERVO_NR + 1)
+ #define NUM_SERVOS INCREMENT(SWITCHING_EXTRUDER_E23_SERVO_NR)
#endif
#endif
#if ENABLED(SPINDLE_SERVO) && NUM_SERVOS <= SPINDLE_SERVO_NR
#undef NUM_SERVOS
- #define NUM_SERVOS (SPINDLE_SERVO_NR + 1)
+ #define NUM_SERVOS INCREMENT(SPINDLE_SERVO_NR)
#endif
#endif // !defined(NUM_SERVOS)
diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h
index 0286fe905bda..3b6c33a8f75c 100644
--- a/Marlin/src/module/servo.h
+++ b/Marlin/src/module/servo.h
@@ -55,7 +55,7 @@
constexpr uint16_t sasn[2] = { 0 };
#endif
- #ifdef Z_PROBE_SERVO_NR
+ #if HAS_Z_SERVO_PROBE
#if ENABLED(BLTOUCH)
#include "../feature/bltouch.h"
#undef Z_SERVO_ANGLES
@@ -76,6 +76,9 @@
#ifndef SWITCHING_NOZZLE_SERVO_NR
#define SWITCHING_NOZZLE_SERVO_NR -1
#endif
+ #ifndef SWITCHING_NOZZLE_E1_SERVO_NR
+ #define SWITCHING_NOZZLE_E1_SERVO_NR -1
+ #endif
#ifndef Z_PROBE_SERVO_NR
#define Z_PROBE_SERVO_NR -1
#endif
@@ -83,12 +86,12 @@
#define SASN(J,I) TERN(SWITCHING_NOZZLE_TWO_SERVOS, sasn[J][I], sasn[I])
#define ASRC(N,I) ( \
- N == SWITCHING_EXTRUDER_SERVO_NR ? sase[I] \
- : N == SWITCHING_EXTRUDER_E23_SERVO_NR ? sase[I+2] \
- : N == SWITCHING_NOZZLE_SERVO_NR ? SASN(0,I) \
- TERN_(SWITCHING_NOZZLE_TWO_SERVOS, : N == SWITCHING_NOZZLE_E1_SERVO_NR ? SASN(1,I)) \
- : N == Z_PROBE_SERVO_NR ? sazp[I] \
- : 0 )
+ N == SWITCHING_EXTRUDER_SERVO_NR ? sase[I] \
+ : N == SWITCHING_EXTRUDER_E23_SERVO_NR ? sase[I+2] \
+ : N == SWITCHING_NOZZLE_SERVO_NR ? SASN(0,I) \
+ : N == SWITCHING_NOZZLE_E1_SERVO_NR ? SASN(1,I) \
+ : N == Z_PROBE_SERVO_NR ? sazp[I] \
+ : 0 )
#if ENABLED(EDITABLE_SERVO_ANGLES)
extern uint16_t servo_angles[NUM_SERVOS][2];
@@ -97,24 +100,8 @@
#define CONST_SERVO_ANGLES servo_angles
#endif
- constexpr uint16_t CONST_SERVO_ANGLES [NUM_SERVOS][2] = {
- { ASRC(0,0), ASRC(0,1) }
- #if NUM_SERVOS > 1
- , { ASRC(1,0), ASRC(1,1) }
- #if NUM_SERVOS > 2
- , { ASRC(2,0), ASRC(2,1) }
- #if NUM_SERVOS > 3
- , { ASRC(3,0), ASRC(3,1) }
- #if NUM_SERVOS > 4
- , { ASRC(4,0), ASRC(4,1) }
- #if NUM_SERVOS > 5
- , { ASRC(5,0), ASRC(5,1) }
- #endif
- #endif
- #endif
- #endif
- #endif
- };
+ #define _ASRC_PAIR(N) { ASRC(N,0), ASRC(N,1) },
+ constexpr uint16_t CONST_SERVO_ANGLES [NUM_SERVOS][2] = { REPEAT(NUM_SERVOS, _ASRC_PAIR) };
#if HAS_Z_SERVO_PROBE
#define DEPLOY_Z_SERVO() servo[Z_PROBE_SERVO_NR].move(servo_angles[Z_PROBE_SERVO_NR][0])
From e82b4e98a492343394ece560f14841b771ea7178 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Fri, 6 Dec 2024 17:13:48 -0600
Subject: [PATCH 15/43] =?UTF-8?q?=F0=9F=94=A8=20More=20informative=20probe?=
=?UTF-8?q?=20conflict=20message=20(2)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/inc/SanityCheck.h | 6 +++---
1 file changed, 3 insertions(+), 3 deletions(-)
diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h
index 6e9e6358ab54..9c21c4fd2960 100644
--- a/Marlin/src/inc/SanityCheck.h
+++ b/Marlin/src/inc/SanityCheck.h
@@ -1226,10 +1226,10 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
+ (DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE) \
+ COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, BD_SENSOR, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4, MAG_MOUNTED_PROBE, BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2)
#error "Please enable only one probe option. See the following errors:"
- #if DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE
- #error "(Z_SERVO_PROBE is enabled.)"
- #elif ENABLED(BLTOUCH) && !HAS_Z_SERVO_PROBE
+ #if ENABLED(BLTOUCH)
#error "(BLTOUCH is enabled.)"
+ #elif HAS_Z_SERVO_PROBE
+ #error "(Z_SERVO_PROBE is enabled.)"
#endif
#if ENABLED(PROBE_MANUALLY)
#error "(PROBE_MANUALLY is enabled.)"
From c5bf705717ccb8f0f716c89712d1016856e8d3f2 Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Sat, 7 Dec 2024 00:29:16 +0000
Subject: [PATCH 16/43] [cron] Bump distribution date (2024-12-07)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 41a645ee680c..7c7b9b4186f3 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-06"
+//#define STRING_DISTRIBUTION_DATE "2024-12-07"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index e0cd06133dd2..080aeb78211d 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-06"
+ #define STRING_DISTRIBUTION_DATE "2024-12-07"
#endif
/**
From 71ce7803e7a910d4512cb0b2dc132c44e4ca2cba Mon Sep 17 00:00:00 2001
From: Andrew <18502096+classicrocker883@users.noreply.github.com>
Date: Sat, 7 Dec 2024 21:11:30 -0500
Subject: [PATCH 17/43] =?UTF-8?q?=F0=9F=8E=A8=20LCD=20conditional=20cleanu?=
=?UTF-8?q?p=20(#27539)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
Co-authored-by: Scott Lahteine
---
Marlin/src/inc/Conditionals-2-LCD.h | 10 ++--------
Marlin/src/lcd/e3v2/common/dwin_set.h | 16 ++++++++++++++++
Marlin/src/lcd/e3v2/creality/dwin.cpp | 26 +++++++++++++++++---------
Marlin/src/lcd/e3v2/proui/dwinui.h | 16 ----------------
Marlin/src/lcd/marlinui.cpp | 14 +++++++-------
Marlin/src/lcd/marlinui.h | 16 +++++++---------
Marlin/src/module/endstops.cpp | 21 ++++++++++++++-------
7 files changed, 63 insertions(+), 56 deletions(-)
diff --git a/Marlin/src/inc/Conditionals-2-LCD.h b/Marlin/src/inc/Conditionals-2-LCD.h
index e7ea7bdeaf3b..0108fad02c48 100644
--- a/Marlin/src/inc/Conditionals-2-LCD.h
+++ b/Marlin/src/inc/Conditionals-2-LCD.h
@@ -585,7 +585,7 @@
#endif
#endif
-#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI)
+#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, HAS_DWIN_E3V2)
/**
* HAS_DISPLAY indicates the display uses these MarlinUI methods...
* - update
@@ -605,10 +605,8 @@
* (calling advance_status_scroll, status_and_len for a scrolling status message)
*/
#define HAS_DISPLAY 1
-#endif
-
-#if ANY(HAS_DISPLAY, DWIN_CREALITY_LCD)
#define HAS_UI_UPDATE 1
+ #define HAS_STATUS_MESSAGE 1
#endif
#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI
@@ -619,10 +617,6 @@
#define HAS_UTF8_UTILS 1
#endif
-#if ANY(HAS_DISPLAY, HAS_DWIN_E3V2)
- #define HAS_STATUS_MESSAGE 1
-#endif
-
#if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS)
#define HAS_MARLINUI_MENU 1
#endif
diff --git a/Marlin/src/lcd/e3v2/common/dwin_set.h b/Marlin/src/lcd/e3v2/common/dwin_set.h
index f32d0e6d9e43..644efb40ba92 100644
--- a/Marlin/src/lcd/e3v2/common/dwin_set.h
+++ b/Marlin/src/lcd/e3v2/common/dwin_set.h
@@ -128,6 +128,22 @@
#define ICON_Info_0 90
#define ICON_Info_1 91
+// Extra Icons
+#define ICON_Printer_0 93
+#define ICON_Box 200
+#define ICON_Checkbox 201
+#define ICON_Fade 202
+#define ICON_Mesh 203
+#define ICON_Tilt 204
+#define ICON_Brightness 205
+#define ICON_Probe 206
+#define ICON_AxisD 249
+#define ICON_AxisBR 250
+#define ICON_AxisTR 251
+#define ICON_AxisBL 252
+#define ICON_AxisTL 253
+#define ICON_AxisC 254
+
#define ICON_Folder ICON_More
#define ICON_AdvSet ICON_Language
#define ICON_HomeOffset ICON_PrintSize
diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp
index 04135ff58bc3..fcbeecde83c3 100644
--- a/Marlin/src/lcd/e3v2/creality/dwin.cpp
+++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp
@@ -355,6 +355,10 @@ void clearPopupArea() {
dwinDrawRectangle(1, COLOR_BG_BLACK, 0, 31, DWIN_WIDTH, DWIN_HEIGHT);
}
+void drawPopupBkgd60() {
+ dwinDrawRectangle(1, COLOR_BG_WINDOW, 14, 60, 258, 330);
+}
+
void drawPopupBkgd105() {
dwinDrawRectangle(1, COLOR_BG_WINDOW, 14, 105, 258, 374);
}
@@ -1081,10 +1085,6 @@ void drawMotionMenu() {
#endif
-void drawPopupBkgd60() {
- dwinDrawRectangle(1, COLOR_BG_WINDOW, 14, 60, 258, 330);
-}
-
#if HAS_HOTEND
void popupWindowETempTooLow() {
@@ -1116,7 +1116,7 @@ void popupWindowResume() {
else {
dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 14) / 2, 115, F("Continue Print"));
dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 22) / 2, 192, F("It looks like the last"));
- dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 22) / 2, 212, F("file was interrupted."));
+ dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 21) / 2, 212, F("file was interrupted."));
dwinIconShow(ICON, ICON_Cancel_E, 26, 307);
dwinIconShow(ICON, ICON_Continue_E, 146, 307);
}
@@ -1125,7 +1125,7 @@ void popupWindowResume() {
void popupWindowHome(const bool parking/*=false*/) {
clearMainWindow();
drawPopupBkgd60();
- dwinIconShow(ICON, ICON_BLTouch, 101, 105);
+ dwinIconShow(ICON, ICON_Printer_0, 101, 105);
if (hmiIsChinese()) {
dwinFrameAreaCopy(1, 0, 371, 33, 386, 85, 240); // Wait for Move to Complete
dwinFrameAreaCopy(1, 203, 286, 271, 302, 118, 240);
@@ -1148,7 +1148,7 @@ void popupWindowHome(const bool parking/*=false*/) {
dwinFrameAreaCopy(1, 0, 389, 150, 402, 61, 280);
}
else {
- dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING));
+ dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 12) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING));
dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 23) / 2, 260, F("Please wait until done."));
}
}
@@ -1169,8 +1169,8 @@ void popupwindowPauseOrStop() {
clearMainWindow();
drawPopupBkgd60();
if (hmiIsChinese()) {
- if (select_print.now == PRINT_PAUSE_RESUME) dwinFrameAreaCopy(1, 237, 338, 269, 356, 98, 150); // Pause
- else if (select_print.now == PRINT_STOP) dwinFrameAreaCopy(1, 221, 320, 253, 336, 98, 150); // Stop
+ if (select_print.now == PRINT_PAUSE_RESUME) dwinFrameAreaCopy(1, 237, 338, 269, 356, 98, 150); // Pause
+ else if (select_print.now == PRINT_STOP) dwinFrameAreaCopy(1, 221, 320, 253, 336, 98, 150); // Stop
dwinFrameAreaCopy(1, 220, 304, 264, 319, 130, 150); // Print
dwinIconShow(ICON, ICON_Confirm_C, 26, 280);
dwinIconShow(ICON, ICON_Cancel_C, 146, 280);
@@ -1826,6 +1826,14 @@ void MarlinUI::update() {
void MarlinUI::_set_brightness() { dwinLCDBrightness(backlight ? brightness : 0); }
#endif
+void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const) {
+ clearMainWindow();
+ drawPopupBkgd60();
+ dwinIconShow(ICON, ICON_Printer_0, 101, 105);
+ dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 15) / 2, 230, GET_TEXT_F(MSG_PRINTER_KILLED));
+ dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 20) / 2, 260, GET_TEXT_F(MSG_TURN_OFF));
+}
+
#if ENABLED(SCROLL_LONG_FILENAMES)
char shift_name[LONG_FILENAME_LENGTH + 1];
diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h
index f606c2440010..0c98fc0d920c 100644
--- a/Marlin/src/lcd/e3v2/proui/dwinui.h
+++ b/Marlin/src/lcd/e3v2/proui/dwinui.h
@@ -36,22 +36,6 @@
#include "../common/dwin_color.h"
#include "dwin_lcd.h"
-// Extra Icons
-#define ICON_Printer_0 93
-#define ICON_Box 200
-#define ICON_Checkbox 201
-#define ICON_Fade 202
-#define ICON_Mesh 203
-#define ICON_Tilt 204
-#define ICON_Brightness 205
-#define ICON_Probe 206
-#define ICON_AxisD 249
-#define ICON_AxisBR 250
-#define ICON_AxisTR 251
-#define ICON_AxisBL 252
-#define ICON_AxisTL 253
-#define ICON_AxisC 254
-
#define ICON_BedSizeX ICON_PrintSize
#define ICON_BedSizeY ICON_PrintSize
#define ICON_BedTramming ICON_SetHome
diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp
index c625351d5a8e..2282cb5ee44c 100644
--- a/Marlin/src/lcd/marlinui.cpp
+++ b/Marlin/src/lcd/marlinui.cpp
@@ -55,10 +55,10 @@ MarlinUI ui;
#endif
#if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL
- #define BASIC_PROGRESS_BAR 1
+ #define HAS_BASIC_PROGRESS_BAR 1
#endif
-#if ANY(HAS_DISPLAY, HAS_STATUS_MESSAGE, BASIC_PROGRESS_BAR)
+#if ANY(HAS_DISPLAY, HAS_STATUS_MESSAGE, HAS_BASIC_PROGRESS_BAR)
#include "../module/printcounter.h"
#endif
@@ -598,7 +598,7 @@ void MarlinUI::init() {
* This is very display-dependent, so the lcd implementation draws this.
*/
- #if BASIC_PROGRESS_BAR
+ #if HAS_BASIC_PROGRESS_BAR
millis_t MarlinUI::progress_bar_ms; // = 0
#if PROGRESS_MSG_EXPIRE > 0
millis_t MarlinUI::expire_status_ms; // = 0
@@ -607,7 +607,7 @@ void MarlinUI::init() {
void MarlinUI::status_screen() {
- #if BASIC_PROGRESS_BAR
+ #if HAS_BASIC_PROGRESS_BAR
//
// HD44780 implements the following message blinking and
@@ -647,7 +647,7 @@ void MarlinUI::init() {
#endif // PROGRESS_MSG_EXPIRE
- #endif // BASIC_PROGRESS_BAR
+ #endif // HAS_BASIC_PROGRESS_BAR
bool did_expire = status_reset_callback && (*status_reset_callback)();
@@ -1592,11 +1592,11 @@ void MarlinUI::host_notify(const char * const cstr) {
#if HAS_WIRED_LCD
- #if BASIC_PROGRESS_BAR || ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA)
+ #if HAS_BASIC_PROGRESS_BAR || ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA)
const millis_t ms = millis();
#endif
- #if BASIC_PROGRESS_BAR
+ #if HAS_BASIC_PROGRESS_BAR
progress_bar_ms = ms;
#if PROGRESS_MSG_EXPIRE > 0
expire_status_ms = persist ? 0 : ms + PROGRESS_MSG_EXPIRE;
diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h
index 64c64020ed99..3c4f28c93e81 100644
--- a/Marlin/src/lcd/marlinui.h
+++ b/Marlin/src/lcd/marlinui.h
@@ -205,15 +205,6 @@ class MarlinUI {
static void init();
- #if HAS_DISPLAY || HAS_DWIN_E3V2
- static void init_lcd();
- // Erase the LCD contents. Do the lowest-level thing required to clear the LCD.
- static void clear_lcd();
- #else
- static void init_lcd() {}
- static void clear_lcd() {}
- #endif
-
static void reinit_lcd() { TERN_(REINIT_NOISY_LCD, init_lcd()); }
#if HAS_WIRED_LCD
@@ -522,6 +513,11 @@ class MarlinUI {
#if HAS_DISPLAY
+ static void init_lcd();
+
+ // Erase the LCD contents. Do the lowest-level thing required to clear the LCD.
+ static void clear_lcd();
+
// Clear the LCD before new drawing. Some LCDs do nothing because they redraw frequently.
static void clear_for_drawing();
@@ -635,6 +631,8 @@ class MarlinUI {
#else // No LCD
+ static void init_lcd() {}
+ static void clear_lcd() {}
static void clear_for_drawing() {}
static void kill_screen(FSTR_P const, FSTR_P const) {}
diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp
index 85e021d661ea..57d6e0989dfe 100644
--- a/Marlin/src/module/endstops.cpp
+++ b/Marlin/src/module/endstops.cpp
@@ -27,9 +27,10 @@
#include "endstops.h"
#include "stepper.h"
-#include "../sd/cardreader.h"
-#include "temperature.h"
-#include "../lcd/marlinui.h"
+#if HAS_STATUS_MESSAGE
+ #include "../lcd/marlinui.h"
+#endif
+
#if ENABLED(SOVOL_SV06_RTS)
#include "../lcd/sovol_rts/sovol_rts.h"
#endif
@@ -44,6 +45,8 @@
#if ENABLED(SD_ABORT_ON_ENDSTOP_HIT)
#include "printcounter.h" // for print_job_timer
+ #include "temperature.h"
+ #include "../sd/cardreader.h"
#endif
#if ENABLED(BLTOUCH)
@@ -54,6 +57,10 @@
#include "../feature/joystick.h"
#endif
+#if HAS_FILAMENT_SENSOR
+ #include "../feature/runout.h"
+#endif
+
#if HAS_BED_PROBE
#include "probe.h"
#endif
@@ -375,13 +382,13 @@ void Endstops::event_handler() {
#endif
SERIAL_EOL();
- TERN_(HAS_STATUS_MESSAGE,
+ #if HAS_STATUS_MESSAGE
ui.status_printf(0,
F(S_FMT GANG_N_1(NUM_AXES, " %c") " %c"),
GET_TEXT_F(MSG_LCD_ENDSTOPS),
NUM_AXIS_LIST_(chrX, chrY, chrZ, chrI, chrJ, chrK, chrU, chrV, chrW) chrP
- )
- );
+ );
+ #endif
#if ENABLED(SD_ABORT_ON_ENDSTOP_HIT)
if (planner.abort_on_endstop_hit) {
@@ -526,7 +533,7 @@ void __O2 Endstops::report_states() {
}
#undef _CASE_RUNOUT
#elif HAS_FILAMENT_SENSOR
- print_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE, F(STR_FILAMENT));
+ print_es_state(!FILAMENT_IS_OUT());
#endif
TERN_(BLTOUCH, bltouch._reset_SW_mode());
From 7e45d56e66383c4ff5d2c0af4e1a75632f0510c0 Mon Sep 17 00:00:00 2001
From: MageDelfador <9780339+MageDelfador@users.noreply.github.com>
Date: Sun, 8 Dec 2024 12:50:41 +0800
Subject: [PATCH 18/43] =?UTF-8?q?=F0=9F=A9=B9=20Advance=20tone=20queue=20w?=
=?UTF-8?q?hen=20muted,=20tuning=20(#26278)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/libs/buzzer.cpp | 39 +++++++++++++++----------------
Marlin/src/module/temperature.cpp | 3 +++
2 files changed, 22 insertions(+), 20 deletions(-)
diff --git a/Marlin/src/libs/buzzer.cpp b/Marlin/src/libs/buzzer.cpp
index 1e2f23c5fdef..350baa333f23 100644
--- a/Marlin/src/libs/buzzer.cpp
+++ b/Marlin/src/libs/buzzer.cpp
@@ -55,30 +55,29 @@ void Buzzer::tone(const uint16_t duration, const uint16_t frequency/*=0*/) {
}
void Buzzer::tick() {
- if (!ui.sound_on) return;
- const millis_t now = millis();
+ if (state.endtime) {
+ if (ELAPSED(millis(), state.endtime)) reset();
+ return;
+ }
- if (!state.endtime) {
- if (buffer.isEmpty()) return;
+ if (buffer.isEmpty()) return;
- state.tone = buffer.dequeue();
- state.endtime = now + state.tone.duration;
+ state.tone = buffer.dequeue();
+ state.endtime = millis() + state.tone.duration;
- if (state.tone.frequency > 0) {
- #if ENABLED(EXTENSIBLE_UI) && DISABLED(EXTUI_LOCAL_BEEPER)
- CRITICAL_SECTION_START();
- ExtUI::onPlayTone(state.tone.frequency, state.tone.duration);
- CRITICAL_SECTION_END();
- #elif ENABLED(SPEAKER)
- CRITICAL_SECTION_START();
- ::tone(BEEPER_PIN, state.tone.frequency, state.tone.duration);
- CRITICAL_SECTION_END();
- #else
- on();
- #endif
- }
+ if (state.tone.frequency > 0) {
+ #if ENABLED(EXTENSIBLE_UI) && DISABLED(EXTUI_LOCAL_BEEPER)
+ CRITICAL_SECTION_START();
+ ExtUI::onPlayTone(state.tone.frequency, state.tone.duration);
+ CRITICAL_SECTION_END();
+ #elif ENABLED(SPEAKER)
+ CRITICAL_SECTION_START();
+ ::tone(BEEPER_PIN, state.tone.frequency, state.tone.duration);
+ CRITICAL_SECTION_END();
+ #else
+ on();
+ #endif
}
- else if (ELAPSED(now, state.endtime)) reset();
}
#endif // HAS_BEEPER
diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp
index 96295d7db586..45dae77d5e5d 100644
--- a/Marlin/src/module/temperature.cpp
+++ b/Marlin/src/module/temperature.cpp
@@ -703,6 +703,9 @@ volatile bool Temperature::raw_temps_ready = false;
ui.update();
#endif
+ // Update beeper queue
+ TERN_(HAS_BEEPER, buzzer.tick());
+
return temp_ready;
}
From 854da5fd9ea12648f982062bca2363244b7ea16c Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Sun, 8 Dec 2024 06:08:33 +0000
Subject: [PATCH 19/43] [cron] Bump distribution date (2024-12-08)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 7c7b9b4186f3..870c6071e522 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-07"
+//#define STRING_DISTRIBUTION_DATE "2024-12-08"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index 080aeb78211d..85ca28729da4 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-07"
+ #define STRING_DISTRIBUTION_DATE "2024-12-08"
#endif
/**
From 5d591fd91d95562bfe7e2886de34a7e6e3e28e11 Mon Sep 17 00:00:00 2001
From: Mihai <299015+mh-dm@users.noreply.github.com>
Date: Mon, 9 Dec 2024 02:55:16 +0200
Subject: [PATCH 20/43] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Improve=20pulse=20ti?=
=?UTF-8?q?ming,=20fix=20LPC176x=20jitter=20(#27131)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/module/stepper.cpp | 21 +++++++++++++--------
1 file changed, 13 insertions(+), 8 deletions(-)
diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp
index b1573f2be9e9..5083c0a4d28d 100644
--- a/Marlin/src/module/stepper.cpp
+++ b/Marlin/src/module/stepper.cpp
@@ -1498,6 +1498,12 @@ void Stepper::apply_directions() {
*/
HAL_STEP_TIMER_ISR() {
+ #ifndef __AVR__
+ // Disable interrupts, to avoid ISR preemption while we reprogram the period
+ // (AVR enters the ISR with global interrupts disabled, so no need to do it here)
+ hal.isr_off();
+ #endif
+
HAL_timer_isr_prologue(MF_TIMER_STEP);
Stepper::isr();
@@ -1515,12 +1521,6 @@ void Stepper::isr() {
static hal_timer_t nextMainISR = 0; // Interval until the next main Stepper Pulse phase (0 = Now)
- #ifndef __AVR__
- // Disable interrupts, to avoid ISR preemption while we reprogram the period
- // (AVR enters the ISR with global interrupts disabled, so no need to do it here)
- hal.isr_off();
- #endif
-
// Program timer compare for the maximum period, so it does NOT
// flag an interrupt while this ISR is running - So changes from small
// periods to big periods are respected and the timer does not reset to 0
@@ -1542,8 +1542,6 @@ void Stepper::isr() {
// We need this variable here to be able to use it in the following loop
hal_timer_t min_ticks;
do {
- // Enable ISRs to reduce USART processing latency
- hal.isr_on();
hal_timer_t interval = 0;
@@ -1559,6 +1557,10 @@ void Stepper::isr() {
ftMotion_nextAuxISR = (STEPPER_TIMER_RATE) / 400;
}
}
+
+ // Enable ISRs to reduce latency for higher priority ISRs, or all ISRs if no prioritization.
+ hal.isr_on();
+
interval = _MIN(nextMainISR, ftMotion_nextAuxISR);
nextMainISR -= interval;
ftMotion_nextAuxISR -= interval;
@@ -1586,6 +1588,9 @@ void Stepper::isr() {
if (is_babystep) nextBabystepISR = babystepping_isr();
#endif
+ // Enable ISRs to reduce latency for higher priority ISRs, or all ISRs if no prioritization.
+ hal.isr_on();
+
// ^== Time critical. NOTHING besides pulse generation should be above here!!!
if (!nextMainISR) nextMainISR = block_phase_isr(); // Manage acc/deceleration, get next block
From 061e02638452fe2353eb26e6d7799a81ab45e597 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Sun, 8 Dec 2024 23:42:11 -0600
Subject: [PATCH 21/43] =?UTF-8?q?=F0=9F=8E=A8=20Remove=20extra=20hotend=20?=
=?UTF-8?q?temp=20update?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
Followup to #24898
---
Marlin/src/module/temperature.cpp | 1 -
1 file changed, 1 deletion(-)
diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp
index 45dae77d5e5d..ab5932851759 100644
--- a/Marlin/src/module/temperature.cpp
+++ b/Marlin/src/module/temperature.cpp
@@ -3781,7 +3781,6 @@ void Temperature::update_raw_temperatures() {
temp_bed.update();
#endif
- TERN_(HAS_TEMP_ADC_2, temp_hotend[2].update());
TERN_(HAS_TEMP_ADC_3, temp_hotend[3].update());
TERN_(HAS_TEMP_ADC_4, temp_hotend[4].update());
TERN_(HAS_TEMP_ADC_5, temp_hotend[5].update());
From 906dcc753685dcca7252eb9a8a2f7fb2b99ac264 Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Mon, 9 Dec 2024 06:09:45 +0000
Subject: [PATCH 22/43] [cron] Bump distribution date (2024-12-09)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 870c6071e522..c8d44b56daa7 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-08"
+//#define STRING_DISTRIBUTION_DATE "2024-12-09"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index 85ca28729da4..179131071781 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-08"
+ #define STRING_DISTRIBUTION_DATE "2024-12-09"
#endif
/**
From 8b7cfa0429231f945eb58398e0ca98de3a74bc72 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Mon, 9 Dec 2024 15:00:18 -0600
Subject: [PATCH 23/43] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Comme?=
=?UTF-8?q?nt=20temperature=20methods,=20fix=20error=20spam?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/module/temperature.cpp | 86 +++++++++++++++++++++++++++++--
1 file changed, 82 insertions(+), 4 deletions(-)
diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp
index ab5932851759..217405eae645 100644
--- a/Marlin/src/module/temperature.cpp
+++ b/Marlin/src/module/temperature.cpp
@@ -1499,6 +1499,13 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) {
// Temperature Error Handlers
//
+/**
+ * Loud Kill
+ * @brief Produce a loud alarm, park the head, "kill" the machine
+ * in response to a temperature error, e.g., a thermal runaway.
+ * @param lcd_msg: The message to display on the LCD
+ * @param heater_id: The heater that caused the error
+ */
inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) {
marlin_state = MarlinState::MF_KILLED;
thermalManager.disable_all_heaters();
@@ -1529,13 +1536,24 @@ inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) {
kill(lcd_msg, HEATER_FSTR(heater_id));
}
+/**
+ * Temperature Error
+ * @brief Handle a temperature error, e.g., a thermal runaway.
+ * @param heater_id: The heater that caused the error
+ * @param serial_msg: The message to display on the serial console
+ * @param lcd_msg: The message to display on the LCD
+ * @param deg: The detected temperature (if ERR_INCLUDE_TEMP)
+ */
void Temperature::_temp_error(
const heater_id_t heater_id, FSTR_P const serial_msg, FSTR_P const lcd_msg
OPTARG(ERR_INCLUDE_TEMP, const celsius_float_t deg)
) {
+ #if BOGUS_TEMPERATURE_GRACE_PERIOD
+ #define HAS_BOGUS_TEMPERATURE_GRACE_PERIOD 1
+ #endif
static uint8_t killed = 0;
- if (IsRunning() && TERN1(BOGUS_TEMPERATURE_GRACE_PERIOD, killed == 2)) {
+ if (IsRunning() && killed == TERN(HAS_BOGUS_TEMPERATURE_GRACE_PERIOD, 2, 0)) {
SERIAL_ERROR_START();
SERIAL_ECHO(serial_msg);
SERIAL_ECHOPGM(STR_STOPPED_HEATER);
@@ -1569,7 +1587,13 @@ void Temperature::_temp_error(
disable_all_heaters(); // always disable (even for bogus temp)
hal.watchdog_refresh();
- #if BOGUS_TEMPERATURE_GRACE_PERIOD
+ #if HAS_BOGUS_TEMPERATURE_GRACE_PERIOD
+
+ // During boot the temperature may be unreliable, so when killed ==
+ // 0: Set the expire time
+ // 1: Check the expiration time has elapsed
+ // 2: Kill the machine
+ // >2: Do nothing
const millis_t ms = millis();
static millis_t expire_ms;
switch (killed) {
@@ -1585,13 +1609,21 @@ void Temperature::_temp_error(
++killed;
break;
}
- #elif defined(BOGUS_TEMPERATURE_GRACE_PERIOD)
- UNUSED(killed);
+
#else
+
if (!killed) { killed = 1; loud_kill(lcd_msg, heater_id); }
+
#endif
}
+/**
+ * Max Temp Error
+ * @brief - The temperature reading is out of range, e.g., too high.
+ * May be caused by a disconnected thermistor which has infinite resistance.
+ * @param heater_id: The heater that caused the error
+ * @param deg: The detected temperature (if ERR_INCLUDE_TEMP)
+ */
void Temperature::maxtemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_TEMP, const celsius_float_t deg)) {
#if HAS_HOTEND || HAS_HEATED_BED
TERN_(SOVOL_SV06_RTS, rts.gotoPageBeep(ID_KillBadTemp_L, ID_KillBadTemp_D));
@@ -1601,6 +1633,13 @@ void Temperature::maxtemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
_TEMP_ERROR(heater_id, F(STR_T_MAXTEMP), MSG_ERR_MAXTEMP, deg);
}
+/**
+ * Min Temp Error
+ * @brief - The temperature reading is out of range, e.g., too high.
+ * May be caused by a shorted thermistor which has near zero resistance.
+ * @param heater_id: The heater that caused the error
+ * @param deg: The detected temperature (if ERR_INCLUDE_TEMP)
+ */
void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_TEMP, const celsius_float_t deg)) {
#if HAS_HOTEND || HAS_HEATED_BED
TERN_(SOVOL_SV06_RTS, rts.gotoPageBeep(ID_KillBadTemp_L, ID_KillBadTemp_D));
@@ -1668,6 +1707,13 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
#if HAS_HOTEND
+ /**
+ * PID Output Hotend
+ * @brief Calculate the power output for the hotend (using PID or MPC)
+ * that is required to get closer to the target temperature.
+ * @param E_NAME: The extruder index
+ * @return The power output for the hotend
+ */
float Temperature::get_pid_output_hotend(const uint8_t E_NAME) {
const uint8_t ee = HOTEND_INDEX;
@@ -1782,6 +1828,12 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
#if ENABLED(PIDTEMPBED)
+ /**
+ * PID Output Bed
+ * @brief Calculate the bed power output using PID that is required
+ * to get closer to the target temperature.
+ * @return The power output for the bed
+ */
float Temperature::get_pid_output_bed() {
static PIDRunner bed_pid(temp_bed);
const float pid_output = bed_pid.get_pid_output();
@@ -1793,6 +1845,12 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
#if ENABLED(PIDTEMPCHAMBER)
+ /**
+ * PID Output Chamber
+ * @brief Calculate the chamber power output using PID that is required
+ * to get closer to the target temperature.
+ * @return The power output for the chamber
+ */
float Temperature::get_pid_output_chamber() {
static PIDRunner chamber_pid(temp_chamber);
const float pid_output = chamber_pid.get_pid_output();
@@ -1804,6 +1862,11 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
#if HAS_HOTEND
+ /**
+ * Manage Hotend Temperatures
+ * @brief Task for managing hotends, called from Temperature::task()
+ * @param ms Current Time
+ */
void Temperature::manage_hotends(const millis_t &ms) {
HOTEND_LOOP() {
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
@@ -1848,6 +1911,11 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
#if HAS_HEATED_BED
+ /**
+ * Manage Heated Bed Temperature
+ * @brief Task for managing the heated bed, called from Temperature::task()
+ * @param ms Current Time
+ */
void Temperature::manage_heated_bed(const millis_t &ms) {
#if ENABLED(THERMAL_PROTECTION_BED)
@@ -1976,6 +2044,11 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
#if HAS_HEATED_CHAMBER
+ /**
+ * Manage Heated Chamber Temperature
+ * @brief Task for managing the heated chamber, called from Temperature::task()
+ * @param ms Current Time
+ */
void Temperature::manage_heated_chamber(const millis_t &ms) {
#ifndef CHAMBER_CHECK_INTERVAL
@@ -2108,6 +2181,11 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
#if HAS_COOLER
+ /**
+ * Manage Heated Cooler Temperature
+ * @brief Task for managing the cooler, called from Temperature::task()
+ * @param ms Current Time
+ */
void Temperature::manage_cooler(const millis_t &ms) {
#ifndef COOLER_CHECK_INTERVAL
From d21e1d4dc8611afeb4e7a6e5325f49e2b8edb49d Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Tue, 10 Dec 2024 00:31:55 +0000
Subject: [PATCH 24/43] [cron] Bump distribution date (2024-12-10)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index c8d44b56daa7..5213f7c05c7e 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-09"
+//#define STRING_DISTRIBUTION_DATE "2024-12-10"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index 179131071781..b8cce2f74381 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-09"
+ #define STRING_DISTRIBUTION_DATE "2024-12-10"
#endif
/**
From 7ad4de2c0812d5b01bd6beccbe40536e526d3888 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Tue, 10 Dec 2024 13:49:06 -0600
Subject: [PATCH 25/43] =?UTF-8?q?=F0=9F=9A=B8=20Filter=20'G29=20S0'=20in?=
=?UTF-8?q?=20ABL?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/gcode/bedlevel/abl/G29.cpp | 1 +
Marlin/src/lcd/extui/ui_api.cpp | 2 +-
2 files changed, 2 insertions(+), 1 deletion(-)
diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp
index 7c8289b7de80..be23de24b18e 100644
--- a/Marlin/src/gcode/bedlevel/abl/G29.cpp
+++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp
@@ -393,6 +393,7 @@ G29_TYPE GcodeSuite::G29() {
#if ABL_USES_GRID
xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.linearval('S', XY_PROBE_FEEDRATE));
+ if (xy_probe_feedrate_mm_s == 0) xy_probe_feedrate_mm_s = XY_PROBE_FEEDRATE; // Don't let "UBL Save Slot #0" break G29
const float x_min = probe.min_x(), x_max = probe.max_x(),
y_min = probe.min_y(), y_max = probe.max_y();
diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp
index 6744643fa9da..4a6f5940662f 100644
--- a/Marlin/src/lcd/extui/ui_api.cpp
+++ b/Marlin/src/lcd/extui/ui_api.cpp
@@ -1003,7 +1003,7 @@ namespace ExtUI {
feedrate_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_FAST);
destination.set(current_position.x, current_position.y, Z_CLEARANCE_BETWEEN_PROBES);
prepare_line_to_destination();
- feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S;
+ if (XY_PROBE_FEEDRATE_MM_S) feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S;
destination.set(x_target, y_target);
prepare_line_to_destination();
}
From 23bc810e6e38d3baa19455713b0c340784555e01 Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Wed, 11 Dec 2024 00:29:50 +0000
Subject: [PATCH 26/43] [cron] Bump distribution date (2024-12-11)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 5213f7c05c7e..434c78a8789a 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-10"
+//#define STRING_DISTRIBUTION_DATE "2024-12-11"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index b8cce2f74381..17db5694e393 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-10"
+ #define STRING_DISTRIBUTION_DATE "2024-12-11"
#endif
/**
From 8d9db0f8999706b913ca48323028b9f708e6b2c7 Mon Sep 17 00:00:00 2001
From: ellensp <530024+ellensp@users.noreply.github.com>
Date: Fri, 13 Dec 2024 10:55:22 +1300
Subject: [PATCH 27/43] =?UTF-8?q?=F0=9F=9A=B8=20Prevent=20very=20slow=20'G?=
=?UTF-8?q?29=20S{value}'=20(ABL=20Mesh)=20(#27579)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
Co-authored-by: Scott Lahteine
---
Marlin/Configuration.h | 8 ++++----
Marlin/src/core/types.h | 2 +-
Marlin/src/gcode/bedlevel/abl/G29.cpp | 6 +++++-
Marlin/src/inc/Conditionals-3-etc.h | 3 +++
4 files changed, 13 insertions(+), 6 deletions(-)
diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h
index c45c75a39d96..7226d337d1fd 100644
--- a/Marlin/Configuration.h
+++ b/Marlin/Configuration.h
@@ -1646,15 +1646,15 @@
// with NOZZLE_AS_PROBE this can be negative for a wider probing area.
#define PROBING_MARGIN 10
-// X and Y axis travel speed (mm/min) between probes.
+// X and Y axis travel speed between probes.
// Leave undefined to use the average of the current XY homing feedrate.
-#define XY_PROBE_FEEDRATE (133*60)
+#define XY_PROBE_FEEDRATE (133*60) // (mm/min)
// Feedrate (mm/min) for the first approach when double-probing (MULTIPLE_PROBING == 2)
-#define Z_PROBE_FEEDRATE_FAST (4*60)
+#define Z_PROBE_FEEDRATE_FAST (4*60) // (mm/min)
// Feedrate (mm/min) for the "accurate" probe of each point
-#define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2)
+#define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2) // (mm/min)
/**
* Probe Activation Switch
diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h
index 7793f1f99561..74570ced76b5 100644
--- a/Marlin/src/core/types.h
+++ b/Marlin/src/core/types.h
@@ -346,7 +346,7 @@ enum AxisEnum : uint8_t {
#define LOOP_DISTINCT_E(VAR) for (uint8_t VAR = 0; VAR < DISTINCT_E; ++VAR)
//
-// feedRate_t is just a humble float
+// feedRate_t is just a humble float that can represent mm/s or mm/min
//
typedef float feedRate_t;
diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp
index be23de24b18e..3b922dd54ffc 100644
--- a/Marlin/src/gcode/bedlevel/abl/G29.cpp
+++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp
@@ -392,8 +392,12 @@ G29_TYPE GcodeSuite::G29() {
#if ABL_USES_GRID
+ constexpr feedRate_t min_probe_feedrate_mm_s = XY_PROBE_FEEDRATE_MIN;
xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.linearval('S', XY_PROBE_FEEDRATE));
- if (xy_probe_feedrate_mm_s == 0) xy_probe_feedrate_mm_s = XY_PROBE_FEEDRATE; // Don't let "UBL Save Slot #0" break G29
+ if (xy_probe_feedrate_mm_s < min_probe_feedrate_mm_s) {
+ xy_probe_feedrate_mm_s = min_probe_feedrate_mm_s;
+ SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Feedrate (S) too low. (Using ", min_probe_feedrate_mm_s, ")"));
+ }
const float x_min = probe.min_x(), x_max = probe.max_x(),
y_min = probe.min_y(), y_max = probe.max_y();
diff --git a/Marlin/src/inc/Conditionals-3-etc.h b/Marlin/src/inc/Conditionals-3-etc.h
index 6a1b3b799991..7f005c35396a 100644
--- a/Marlin/src/inc/Conditionals-3-etc.h
+++ b/Marlin/src/inc/Conditionals-3-etc.h
@@ -493,6 +493,9 @@
#endif
#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR)
#define ABL_USES_GRID 1
+ #ifndef XY_PROBE_FEEDRATE_MIN
+ #define XY_PROBE_FEEDRATE_MIN 60 // Minimum mm/min value for 'G29 S'
+ #endif
#endif
#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_3POINT)
#define HAS_ABL_NOT_UBL 1
From ba88365364f33db0f9b9dccdc8fe524fdce5afc6 Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Fri, 13 Dec 2024 00:30:12 +0000
Subject: [PATCH 28/43] [cron] Bump distribution date (2024-12-13)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 434c78a8789a..042bc34f24f4 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-11"
+//#define STRING_DISTRIBUTION_DATE "2024-12-13"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index 17db5694e393..a4d9a75819fb 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-11"
+ #define STRING_DISTRIBUTION_DATE "2024-12-13"
#endif
/**
From a748eaade7328e3ee2dbb59107b3f7cf46d19ad3 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Thu, 12 Dec 2024 16:37:14 -0600
Subject: [PATCH 29/43] =?UTF-8?q?=F0=9F=94=A8=20Add=20offset=5Faddress=20f?=
=?UTF-8?q?or=20convenience?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
ini/stm32f1.ini | 4 ++++
ini/stm32f4.ini | 14 ++++++++++++++
2 files changed, 18 insertions(+)
diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini
index 0978b19476a2..ef117eb2697c 100644
--- a/ini/stm32f1.ini
+++ b/ini/stm32f1.ini
@@ -95,6 +95,7 @@ board = genericSTM32F103ZE
board_build.variant = MARLIN_F103Zx
board_build.encrypt_mks = Robin.bin
board_build.offset = 0x7000
+board_build.offset_address = 0x08007000
build_flags = ${stm32_variant.build_flags}
-DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5
build_unflags = ${stm32_variant.build_unflags}
@@ -239,6 +240,7 @@ extends = stm32_variant
board = genericSTM32F103ZE
board_build.variant = MARLIN_F103Zx
board_build.offset = 0x10000
+board_build.offset_address = 0x08010000
build_flags = ${stm32_variant.build_flags}
-DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5
build_unflags = ${stm32_variant.build_unflags}
@@ -417,6 +419,7 @@ board = genericSTM32F103ZE
board_build.crypt_chitu = update.zw
board_build.variant = MARLIN_F103Zx
board_build.offset = 0x8800
+board_build.offset_address = 0x08008800
build_flags = ${stm32_variant.build_flags}
-DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5
build_unflags = ${stm32_variant.build_unflags}
@@ -434,6 +437,7 @@ board = genericSTM32F103ZE
board_build.crypt_chitu = update.cbd
board_build.variant = MARLIN_F103Zx
board_build.offset = 0x8800
+board_build.offset_address = 0x08008800
build_flags = ${stm32_variant.build_flags}
-DSTM32F1xx
build_unflags = ${stm32_variant.build_unflags}
diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini
index 7fdbc6980477..1b67be582bb0 100644
--- a/ini/stm32f4.ini
+++ b/ini/stm32f4.ini
@@ -36,6 +36,7 @@ extends = stm32_variant
platform_packages = platformio/tool-dfuutil@~1.11.0
board = marlin_FYSETC_CHEETAH_V20
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
build_flags = ${stm32_variant.build_flags} -DSTM32F401xC
upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE"
@@ -60,6 +61,7 @@ platform_packages = platformio/tool-dfuutil@~1.11.0
board = marlin_STM32F407ZGT6
board_build.variant = MARLIN_FLY_F407ZG
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
upload_protocol = dfu
#
@@ -95,6 +97,7 @@ platform_packages = platformio/tool-dfuutil@~1.11.0
board = marlin_STM32F407ZGT6
board_build.variant = MARLIN_FYSETC_SPIDER_KING407
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
upload_protocol = dfu
#
@@ -168,6 +171,7 @@ extra_scripts = ${Anet_ET4.extra_scripts}
extends = stm32_variant
board = marlin_BTT_SKR_Pro
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
build_flags = ${stm32_variant.build_flags} -DSTM32F407_5ZX
debug_tool = stlink
upload_protocol = stlink
@@ -189,6 +193,7 @@ extends = stm32_variant
board = marlin_STM32F407VGT6_CCM
board_build.variant = MARLIN_BTT_E3_RRF
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
build_flags = ${stm32_variant.build_flags}
-DSTM32F407_5VX
-DMF_RX_BUFFER_SIZE=255
@@ -202,6 +207,7 @@ extends = stm32_variant
board = marlin_STM32F407VGT6_CCM
#board_build.variant = MARLIN_BTT_E3_RRF
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
build_flags = ${stm32_variant.build_flags}
-DSTM32F407_5VX
-DMF_RX_BUFFER_SIZE=255
@@ -214,6 +220,7 @@ build_flags = ${stm32_variant.build_flags}
extends = stm32_variant
board = marlin_BTT_GTR_v1
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
build_flags = ${stm32_variant.build_flags} -DSTM32F407IX
#
@@ -232,6 +239,7 @@ build_unflags = ${env:BTT_GTR_V1_0.build_unflags} -DUSBCON -DUSBD_USE_CDC
extends = stm32_variant
board = marlin_BTT_BTT002
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
build_flags = ${stm32_variant.build_flags}
-DSTM32F407_5VX
-DHAVE_HWSERIAL2
@@ -354,6 +362,7 @@ build_flags = ${stm_flash_drive.build_flags}
extends = stm32_variant
board = marlin_STM32F407ZE
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
build_flags = ${stm32_variant.build_flags}
-DUSE_USB_HS_IN_FS
@@ -378,6 +387,7 @@ board = marlin_STM32F407ZGT6
board_build.variant = MARLIN_LERDGE
board_build.crypt_lerdge = firmware.bin
board_build.offset = 0x10000
+board_build.offset_address = 0x08010000
build_flags = ${stm32_variant.build_flags}
-DSTM32F4 -DSTM32F4xx -DTARGET_STM32F4
-DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 -DLERDGE_TFT35
@@ -440,6 +450,7 @@ platform_packages = platformio/tool-dfuutil@~1.11.0
board = rumba32_f446ve
board_build.variant = MARLIN_F446VE
board_build.offset = 0x0000
+board_build.offset_address = 0x08000000
build_flags = ${stm32_variant.build_flags}
-Os -DHAL_PCD_MODULE_ENABLED
-DDISABLE_GENERIC_SERIALUSB
@@ -840,6 +851,7 @@ extends = stm32_variant
board = marlin_STM32F446ZET_tronxy
board_build.ldscript = buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/ldscript.ld
board_build.offset = 0x10000
+board_build.offset_address = 0x08010000
build_flags = ${stm32_variant.build_flags}
-DSTM32F4xx -DUSE_USB_HS
-DUSE_USB_HS_IN_FS
@@ -873,6 +885,7 @@ monitor_speed = 115200
extends = stm32_variant
board = marlin_I3DBEEZ9
board_build.offset = 0x8000
+board_build.offset_address = 0x08008000
build_flags = ${stm32_variant.build_flags} -DSTM32F407_5ZX
debug_tool = stlink
upload_protocol = stlink
@@ -886,6 +899,7 @@ platform_packages = platformio/tool-dfuutil@~1.11.0
extends = common_stm32
board = blackpill_f401cc
board_build.offset = 0x0000
+board_build.offset_address = 0x08000000
build_flags = ${common_stm32.build_flags}
-Os -DHAL_PCD_MODULE_ENABLED
-DHAL_UART_MODULE_ENABLED
From a23212bd95e268fe29682e53cd5b7719811c5519 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Thu, 12 Dec 2024 16:26:13 -0600
Subject: [PATCH 30/43] =?UTF-8?q?=F0=9F=94=A8=20Versioned=20ststm32=20for?=
=?UTF-8?q?=20BLACKBEEZMINI=5FV1?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
ini/stm32f4.ini | 3 +--
1 file changed, 1 insertion(+), 2 deletions(-)
diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini
index 1b67be582bb0..3f7b5b63467b 100644
--- a/ini/stm32f4.ini
+++ b/ini/stm32f4.ini
@@ -894,9 +894,8 @@ upload_protocol = stlink
# BlackBeezMini (blackpill_f401cc)
#
[env:BLACKBEEZMINI_V1]
-platform = ststm32
-platform_packages = platformio/tool-dfuutil@~1.11.0
extends = common_stm32
+platform_packages = platformio/tool-dfuutil@~1.11.0
board = blackpill_f401cc
board_build.offset = 0x0000
board_build.offset_address = 0x08000000
From 94ca5487ab18647f1078847e9e1b460bb894a412 Mon Sep 17 00:00:00 2001
From: thinkyhead
Date: Mon, 16 Dec 2024 00:31:26 +0000
Subject: [PATCH 31/43] [cron] Bump distribution date (2024-12-16)
---
Marlin/Version.h | 2 +-
Marlin/src/inc/Version.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/Marlin/Version.h b/Marlin/Version.h
index 042bc34f24f4..69ec210a658b 100644
--- a/Marlin/Version.h
+++ b/Marlin/Version.h
@@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
-//#define STRING_DISTRIBUTION_DATE "2024-12-13"
+//#define STRING_DISTRIBUTION_DATE "2024-12-16"
/**
* The protocol for communication to the host. Protocol indicates communication
diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h
index a4d9a75819fb..ca04b24869c5 100644
--- a/Marlin/src/inc/Version.h
+++ b/Marlin/src/inc/Version.h
@@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
- #define STRING_DISTRIBUTION_DATE "2024-12-13"
+ #define STRING_DISTRIBUTION_DATE "2024-12-16"
#endif
/**
From 4c388d711880d64b33be5d0d8a0366f4cf5fe498 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Sun, 15 Dec 2024 18:41:42 -0600
Subject: [PATCH 32/43] =?UTF-8?q?=F0=9F=9A=B8=20Limited=20number=20of=20DG?=
=?UTF-8?q?US=20fans?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
.../src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp | 9 ++++++++-
.../src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp | 9 ++++++++-
Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 15 +++++++++++----
.../src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp | 9 ++++++++-
4 files changed, 35 insertions(+), 7 deletions(-)
diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp
index 243dbfbab6f2..575e56103e3f 100644
--- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp
+++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp
@@ -406,11 +406,18 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = {
// Fan Data
#if HAS_FAN
+ #if HOTENDS <= 4
+ #define FAN_CONTROL HOTENDS
+ #elif FAN_COUNT <= 4
+ #define FAN_CONTROL FAN_COUNT
+ #else
+ #define FAN_CONTROL 4
+ #endif
#define FAN_VPHELPER(N) \
VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.percentageToUint8, screen.sendPercentageToDisplay), \
VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \
VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, screen.sendFanStatusToDisplay),
- REPEAT(FAN_COUNT, FAN_VPHELPER)
+ REPEAT(FAN_CONTROL, FAN_VPHELPER)
#endif
// Feedrate
diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp
index 56d58a19b07f..338f6a319c87 100644
--- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp
+++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp
@@ -399,11 +399,18 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = {
// Fan Data
#if HAS_FAN
+ #if HOTENDS <= 2
+ #define FAN_CONTROL HOTENDS
+ #elif FAN_COUNT <= 2
+ #define FAN_CONTROL FAN_COUNT
+ #else
+ #define FAN_CONTROL 2
+ #endif
#define FAN_VPHELPER(N) \
VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.percentageToUint8, screen.sendPercentageToDisplay), \
VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \
VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, screen.sendFanStatusToDisplay),
- REPEAT(FAN_COUNT, FAN_VPHELPER)
+ REPEAT(FAN_CONTROL, FAN_VPHELPER)
#endif
// Feedrate
diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp
index 6429ac07e5cd..4182c3f2ca6c 100644
--- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp
+++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp
@@ -602,11 +602,18 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = {
// Fan Data
#if HAS_FAN
- #define FAN_VPHELPER(N) \
- VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.setUint8, screen.sendFanToDisplay), \
- VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \
+ #if HOTENDS <= 4
+ #define FAN_CONTROL HOTENDS
+ #elif FAN_COUNT <= 4
+ #define FAN_CONTROL FAN_COUNT
+ #else
+ #define FAN_CONTROL 4
+ #endif
+ #define FAN_VPHELPER(N) \
+ VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.percentageToUint8, screen.sendFanToDisplay), \
+ VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \
VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, screen.sendFanStatusToDisplay),
- REPEAT(FAN_COUNT, FAN_VPHELPER)
+ REPEAT(FAN_CONTROL, FAN_VPHELPER)
#endif
// Feedrate
diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp
index 8c82b63f3a41..4875020f55f7 100644
--- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp
+++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp
@@ -207,11 +207,18 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = {
// Fan Data
#if HAS_FAN
+ #if HOTENDS <= 2
+ #define FAN_CONTROL HOTENDS
+ #elif FAN_COUNT <= 2
+ #define FAN_CONTROL FAN_COUNT
+ #else
+ #define FAN_CONTROL 2
+ #endif
#define FAN_VPHELPER(N) \
VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.percentageToUint8, screen.sendPercentageToDisplay), \
VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \
VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, screen.sendFanStatusToDisplay),
- REPEAT(FAN_COUNT, FAN_VPHELPER)
+ REPEAT(FAN_CONTROL, FAN_VPHELPER)
#endif
// Feedrate
From dcc10565f8865d6400008a280fbcdff4ac8ae074 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Sun, 15 Dec 2024 20:34:18 -0600
Subject: [PATCH 33/43] =?UTF-8?q?=F0=9F=93=9D=20@section=20calibration=20?=
=?UTF-8?q?=3D>=20calibrate?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/Configuration_adv.h | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h
index 564f44df606d..806bafa2d00d 100644
--- a/Marlin/Configuration_adv.h
+++ b/Marlin/Configuration_adv.h
@@ -1020,7 +1020,7 @@
#endif // BLTOUCH
-// @section calibration
+// @section calibrate
/**
* Z Steppers Auto-Alignment
From d5dfd18c24d8d79e55893cf90b1cb5c28bc369ed Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Sun, 15 Dec 2024 16:04:23 -0600
Subject: [PATCH 34/43] =?UTF-8?q?=F0=9F=94=A8=20Scripted=20build/archive?=
=?UTF-8?q?=20multiple=20envs?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
buildroot/bin/build_all_examples | 9 +-
buildroot/bin/build_example | 148 ++++++++++++++++++++-----------
buildroot/bin/mfenvs | 33 +++++++
buildroot/bin/mftest | 2 +-
buildroot/share/git/mfhelp | 1 +
5 files changed, 139 insertions(+), 54 deletions(-)
create mode 100755 buildroot/bin/mfenvs
diff --git a/buildroot/bin/build_all_examples b/buildroot/bin/build_all_examples
index c2b0007b0c2f..595cfad839fd 100755
--- a/buildroot/bin/build_all_examples
+++ b/buildroot/bin/build_all_examples
@@ -11,6 +11,7 @@
# [-f|--nofail] - Don't stop on a failed build
# [-h|--help] - Print usage and exit
# [-l|--limit=#] - Limit the number of builds in this run
+# [-m|--many] - Build all the environments for each example
# [-n|--nobuild] - Don't actually build anything
# [-o|--output] - Redirect export / archiving to another location
# (By default export to origin config folders)
@@ -38,6 +39,7 @@ build_all_examples [-a|--archive] - Copy the binary to the export locati
[-f|--nofail] - Don't stop on a failed build
[-h|--help] - Print usage and exit
[-l|--limit=#] - Limit the number of builds in this run
+ [-m|--many] - Build all the environments for each example
[-n|--nobuild] - Don't actually build anything
[-o|--output] - Redirect export / archiving to another location
(By default export to origin config folders)
@@ -53,7 +55,7 @@ unset FIRST_CONF
EXIT_USAGE=
LIMIT=1000
-while getopts 'aB:b:cde:fhl:no:pr:sv-:' OFLAG; do
+while getopts 'aB:b:cde:fhl:mno:pr:sv-:' OFLAG; do
case "${OFLAG}" in
a) ARCHIVE=1 ; bugout "Archiving" ;;
B) CBASE=${OPTARG%/} ; bugout "Base: $CBASE" ;;
@@ -64,6 +66,7 @@ while getopts 'aB:b:cde:fhl:no:pr:sv-:' OFLAG; do
f) NOFAIL=1 ; bugout "Continue on Fail" ;;
h) EXIT_USAGE=1 ; break ;;
l) LIMIT=$OPTARG ; bugout "Limit to $LIMIT build(s)" ;;
+ m) MANY=1 ; bugout "Many Envs" ;;
n) DRYRUN=1 ; bugout "Dry Run" ;;
o) OUTBASE="${OPTARG%/}" ; bugout "Archive to $OUTBASE" ;;
p) PURGE=1 ; bugout "Purge stat file" ;;
@@ -74,6 +77,7 @@ while getopts 'aB:b:cde:fhl:no:pr:sv-:' OFLAG; do
archive) ARCHIVE=1 ; bugout "Archiving" ;;
base) CBASE=${OVAL%/} ; bugout "Base: $CBASE" ;;
branch) BRANCH=$OVAL ; bugout "Branch: $BRANCH" ;;
+ many) MANY=1 ; bugout "Many Envs" ;;
nofail) NOFAIL=1 ; bugout "Continue on Fail" ;;
resume) ISRES=1 ; FIRST_CONF=$OVAL ; bugout "Resume: $FIRST_CONF" ;;
continue) CONTINUE=1 ; bugout "Continue" ;;
@@ -179,6 +183,9 @@ find -ds "$CBASE"/config/examples -type d -name 'Configuration.h' -o -name 'Conf
# Exporting? Add -e argument
((CEXPORT)) && CARGS+=("-e" "$CEXPORT")
+ # Build many environments? Add -m argument
+ ((NOFAIL)) && CARGS+=("-m")
+
# Continue on fail? Add -f argument
((NOFAIL)) && CARGS+=("-f")
diff --git a/buildroot/bin/build_example b/buildroot/bin/build_example
index 566919abd665..623da8ac84c1 100755
--- a/buildroot/bin/build_example
+++ b/buildroot/bin/build_example
@@ -5,6 +5,7 @@
# build_example -b|--base= - Configurations root folder (e.g., ./.pio/build-BRANCH)
# -c|--config= - Sub-path of the configs to build (within config/examples)
# [-n|--index=N] - Which environment to build, by index (Based on pins.h comments)
+# [-m|--many] - Build all the board's environments listed in pins.h
# [-e|--export=N] - Use CONFIG_EXPORT N to export the config to the export location
# [-a|--archive] - Archive the build (to the export location)
# [-o|--output] - Redirect export / archiving to another location
@@ -21,6 +22,7 @@ usage() { echo "Usage:
build_example -b|--base= - Configurations root folder (e.g., ./.pio/build-BRANCH)
-c|--config= - Sub-path of the configs to build (within config/examples)
[-n|--index=N] - Which environment to build, by index (Based on pins.h comments)
+ [-m|--many] - Build all the board's environments listed in pins.h
[-e|--export=N] - Use CONFIG_EXPORT N to export the config to the export location
[-a|--archive] - Archive the build (to the export location)
[-o|--output] - Redirect export / archiving to another location
@@ -53,8 +55,9 @@ EXPNUM=
NOFAIL=
OUTBASE=
BUILDINDEX=1
+MANY=
-while getopts 'ab:c:e:fhn:o:r-:' OFLAG; do
+while getopts 'ab:c:e:fhmn:o:r-:' OFLAG; do
case "${OFLAG}" in
a) ARCHIVE=1 ;;
b) BASE="${OPTARG%/}" ;;
@@ -62,6 +65,7 @@ while getopts 'ab:c:e:fhn:o:r-:' OFLAG; do
e) EXPNUM="$OPTARG" ;;
f) NOFAIL=1 ;;
h) EXIT_USAGE=1 ; break ;;
+ m) MANY=1 ;;
n) BUILDINDEX="$OPTARG" ;;
o) OUTBASE="${OPTARG%/}" ;;
r) REVEAL=1 ;;
@@ -71,6 +75,7 @@ while getopts 'ab:c:e:fhn:o:r-:' OFLAG; do
allow) ALLOW=1 ;;
base) BASE="${OVAL%/}" ;;
config) CONFIG="${OVAL%/}" ;;
+ many) MANY=1 ;;
index) BUILDINDEX="$OVAL" ;;
export) EXPNUM="$OVAL" ;;
output) OUTBASE="${OVAL%/}" ;;
@@ -178,68 +183,107 @@ fi
((ARCHIVE)) && find "$BUILD" -type f \( "${BNAME[@]}" \) -exec rm "{}" \;
-set +e
+echo "Building example $CONFIG..."
+
+# If doing many builds get a list of all environment names,
+# which also gives us the number of environments.
+if ((MANY)); then
+ ENVLIST=$(mfenvs) # BOARD_NAME_STRING (1234): [ env1 env2 env3 ... ]
+ ENVLIST=${ENVLIST##*: [ }
+ ENVARRAY=(${ENVLIST% ]})
+ ENVCOUNT=${#ENVARRAY[*]}
+ ((ENVCOUNT)) || { alrt "mfenvs failed for this board." ; exit 1 ; }
+ echo "Found $ENVCOUNT environment(s): ${ENVARRAY[*]}"
+fi
-echo "Building example $CONFIG ..."
-mftest -s -a -n$BUILDINDEX ; ERR=$?
+# Run one or more builds based on --many
+# Build all from BUILDINDEX onward (usually 1) meaning ALL.
+# MANY with a BUILDINDEX may be useful for continuing an interrupted build.
-((ERR)) && alrt "Failed ($ERR)" || annc "Success"
+while ((1)); do
+ set +e
-set -e
+ echo "Building example $CONFIG ($BUILDINDEX)..."
+
+ # Run a build and record the error number
+ mftest -s -a -n$BUILDINDEX ; ERR=$?
+
+ # "Index out of range" can fail without an error
+ ((MANY)) && ((ERR == 66)) && ERR=0 && break # "index out of range"
+
+ # Short message reporting Error or Success
+ ((ERR)) && alrt "Failed ($ERR)" || annc "Success"
+
+ set -e
-if [[ $ERR -gt 0 ]]; then
+ if [[ $ERR -gt 0 ]]; then
+
+ # Error? For --nofail simply log. Otherwise return the error.
+ if [[ -n $NOFAIL ]]; then
+ date +"%F %T [FAIL] $CONFIG" >>./.pio/error-log.txt
+ else
+ exit $ERR
+ fi
- # Error? For --nofail simply log. Otherwise return the error.
- if [[ -n $NOFAIL ]]; then
- date +"%F %T [FAIL] $CONFIG" >>./.pio/error-log.txt
else
- exit $ERR
- fi
-else
+ # Copy exports back to the configs
+ if [[ -n $EXPNUM ]]; then
+ annc "Exporting $EXPNUM"
+ [[ -f Marlin/Config-export.h ]] && { cp Marlin/Config-export.h "$ARCSUB"/Config.h ; }
+ find "$BUILD" -type f \( "${ENAME[@]}" \) -exec cp "{}" "$ARCSUB" \;
+ fi
+
+ # When building many, create sub-folders for each build env name
+ if [[ -n $MANY && $ENVCOUNT -gt 1 ]]; then
+ ENV=${ENVARRAY[BUILDINDEX-1]}
+ ARCENVSUB="$ARCSUB/$ENV"
+ else
+ ARCENVSUB="$ARCSUB"
+ fi
+
+ # Copy potential firmware files into the config folder
+ # TODO: Consider firmware that needs an STM32F4_UPDATE folder.
+ # Currently only BOARD_CREALITY_F401RE env:STM32F401RE_creality
+ if ((ARCHIVE)); then
+ annc "Archiving"
+ find "$BUILD" -type f \( "${BNAME[@]}" \) -exec sh -c '
+ ARCDIR="$1" ; CONFIG="$2" ; FILE="$3" ; shift 3
+ NAME=${FILE##*/} ; SHRT=${NAME%.*} ; DIR=${FILE%/*}
+ ZIPX=
+ if [[ $CONFIG == *Simulator* ]]; then
+ case $(uname | tr '[:upper:]' '[:lower:]') in
+ darwin) SUB="macOS" ; ZIPX="-X" ;;
+ *linux) SUB="Linux" ;;
+ win*) SUB="Windows" ;;
+ msys*) SUB="Windows" ;;
+ cygwin*) SUB="Windows" ;;
+ mingw*) SUB="Windows" ;;
+ *) SUB='Unix' ;;
+ esac
+ ARCH=$(uname -m | tr '[:lower:]' '[:upper:]')
+ ARCDIR="$ARCDIR/$SUB-$ARCH"
+ fi
+ mkdir -p "$ARCDIR"
+ rm -f "$ARCDIR"/*.zip "$ARCDIR"/*.sha256.txt
+ cd "$DIR"
+ SHASUM=$(sha256sum "$NAME" | cut -d" " -f1)
+ echo "$CONFIG\n$SHASUM" > "$ARCDIR/$NAME.sha256.txt"
+ zip $ZIPX "$ARCDIR/$SHRT.zip" "$NAME" && rm "$NAME"
+ cd - >/dev/null
+ ' sh "$ARCENVSUB" "$CONFIG" {} +
+ fi
+
+ # Reveal the configs after the build, if requested
+ ((REVEAL)) && { annc "Revealing $ARCENVSUB" ; open "$ARCENVSUB" ; }
- # Copy exports back to the configs
- if [[ -n $EXPNUM ]]; then
- annc "Exporting $EXPNUM"
- [[ -f Marlin/Config-export.h ]] && { cp Marlin/Config-export.h "$ARCSUB"/Config.h ; }
- find "$BUILD" -type f \( "${ENAME[@]}" \) -exec cp "{}" "$ARCSUB" \;
fi
- # Copy potential firmware files into the config folder
- # TODO: Consider firmware that needs an STM32F4_UPDATE folder.
- # Currently only BOARD_CREALITY_F401RE env:STM32F401RE_creality
- if ((ARCHIVE)); then
- annc "Archiving"
- find "$BUILD" -type f \( "${BNAME[@]}" \) -exec sh -c '
- ARCSUB="$1" ; CONFIG="$2" ; FILE="$3" ; shift 3
- NAME=${FILE##*/} ; SHRT=${NAME%.*} ; DIR=${FILE%/*}
- ZIPX=
- if [[ $CONFIG == *Simulator* ]]; then
- case $(uname | tr '[:upper:]' '[:lower:]') in
- darwin) SUB="macOS" ; ZIPX="-X" ;;
- *linux) SUB="Linux" ;;
- win*) SUB="Windows" ;;
- msys*) SUB="Windows" ;;
- cygwin*) SUB="Windows" ;;
- mingw*) SUB="Windows" ;;
- *) SUB='Unix' ;;
- esac
- ARCH=$(uname -m | tr '[:lower:]' '[:upper:]')
- ARCSUB="$ARCSUB/$SUB-$ARCH"
- fi
- mkdir -p "$ARCSUB"
- rm -f "$ARCSUB"/*.zip "$ARCSUB"/*.sha256.txt
- cd "$DIR"
- SHASUM=$(sha256sum "$NAME" | cut -d" " -f1)
- echo "$CONFIG\n$SHASUM" > "$ARCSUB/$NAME.sha256.txt"
- zip $ZIPX "$ARCSUB/$SHRT.zip" "$NAME" && rm "$NAME"
- cd - >/dev/null
- ' sh "$ARCSUB" "$CONFIG" {} +
- fi
+ ((MANY)) || break # Only one build if not --many
- # Reveal the configs after the build, if requested
- ((REVEAL)) && { annc "Revealing $ARCSUB" ; open "$ARCSUB" ; }
+ # Set up for the next build, if there is one
+ ((++BUILDINDEX > ENVCOUNT)) && break
-fi
+done
exit 0
diff --git a/buildroot/bin/mfenvs b/buildroot/bin/mfenvs
new file mode 100755
index 000000000000..3c726af53c8d
--- /dev/null
+++ b/buildroot/bin/mfenvs
@@ -0,0 +1,33 @@
+#!/usr/bin/env bash
+#
+# mfenvs Print the current board and environment information
+# Output -> "SHORT_NAME (###): [ env1 env2 env3 ... ]"
+#
+
+[[ -d Marlin/src ]] || { echo "Please 'cd' to the Marlin repo root." ; exit 1 ; }
+which pio >/dev/null || { echo "Make sure 'pio' is in your execution PATH." ; exit 1 ; }
+
+errout() { echo -e "\033[0;31m$1\033[0m" ; }
+
+case $(uname | tr '[:upper:]' '[:lower:]') in
+ darwin) SYS='mac' ;;
+ *linux) SYS='lin' ;;
+ win*) SYS='win' ;;
+ msys*) SYS='win' ;;
+ cygwin*) SYS='win' ;;
+ mingw*) SYS='win' ;;
+ *) SYS='uni' ;;
+esac
+
+ACODE='/^[[:space:]]*#define[[:space:]]MOTHERBOARD[[:space:]]/ { sub(/^BOARD_/, "", $3); print $3 }'
+MB=$(awk "$ACODE" Marlin/Configuration.h 2>/dev/null)
+[[ -z $MB ]] && MB=$(awk "$ACODE" Marlin/Config.h 2>/dev/null)
+[[ -z $MB ]] && { echo "Error - Can't read MOTHERBOARD setting." ; exit 1 ; }
+BLINE=$( grep -E "define\s+BOARD_$MB\b" Marlin/src/core/boards.h )
+BNUM=$( sed -E 's/^.+BOARD_[^ ]+ +([0-9]+).+$/\1/' <<<"$BLINE" )
+[[ -z $BNUM ]] && { echo "Error - Can't find BOARD_$MB in core/boards.h." ; exit 1 ; }
+ENVS=( $( grep -EA1 "MB\(.*\b$MB\b.*\)" Marlin/src/pins/pins.h | grep -E "#include.+//.+(env|$SYS):[^ ]+" | grep -oE "(env|$SYS):[^ ]+" | sed -E "s/(env|$SYS)://" ) )
+[[ -z $ENVS ]] && { errout "Error - Can't find target(s) for $MB ($BNUM)." ; exit 1 ; }
+ECOUNT=${#ENVS[*]}
+[[ $ECOUNT == 1 ]] && EOUT=$ENVS || EOUT="${ENVS[@]}"
+echo "$MB ($BNUM): [ $EOUT ]"
diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest
index 57aa95400cec..07601654aa91 100755
--- a/buildroot/bin/mftest
+++ b/buildroot/bin/mftest
@@ -196,7 +196,7 @@ if ((AUTO_BUILD)); then
fi
else
echo "Detected \"$BDESC\" | $MB ($BNUM)."
- [[ $CHOICE > $ECOUNT ]] && { echo "Environment selection out of range." ; exit 1 ; }
+ [[ $CHOICE > $ECOUNT ]] && { echo "Environment selection out of range." ; exit 66 ; }
fi
TARGET="${ENVS[$CHOICE-1]}"
if [[ $MB == 'SIMULATED' && $TARGET == 'linux_native' ]]; then
diff --git a/buildroot/share/git/mfhelp b/buildroot/share/git/mfhelp
index cbdd6ec4ef95..bbf713a9267c 100755
--- a/buildroot/share/git/mfhelp
+++ b/buildroot/share/git/mfhelp
@@ -12,6 +12,7 @@ Marlin Firmware Commands:
mfadd ....... Fetch a remote branch from any Marlin fork
mfclean ..... Attempt to clean up merged and deleted branches
mfdoc ....... Build the website, serve locally, and browse
+ mfenvs ...... Get current board SHORT_NAME (###): [ env1 env2 ... ]
mffp ........ Push new commits directly to MarlinFirmware
mfinfo ...... Provide branch information (for the other scripts)
mfinit ...... Create an 'upstream' remote for 'MarlinFirmare'
From c0becd6ce1bb3729663811b174ca93f901601238 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Sun, 15 Dec 2024 23:25:10 -0600
Subject: [PATCH 35/43] =?UTF-8?q?=F0=9F=94=A8=20Scripted=20build/archive?=
=?UTF-8?q?=20multiple=20envs=20(2)?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
buildroot/bin/build_all_examples | 2 +-
buildroot/bin/build_example | 9 +++++----
buildroot/share/PlatformIO/scripts/signature.py | 2 +-
3 files changed, 7 insertions(+), 6 deletions(-)
diff --git a/buildroot/bin/build_all_examples b/buildroot/bin/build_all_examples
index 595cfad839fd..d50937a732ec 100755
--- a/buildroot/bin/build_all_examples
+++ b/buildroot/bin/build_all_examples
@@ -184,7 +184,7 @@ find -ds "$CBASE"/config/examples -type d -name 'Configuration.h' -o -name 'Conf
((CEXPORT)) && CARGS+=("-e" "$CEXPORT")
# Build many environments? Add -m argument
- ((NOFAIL)) && CARGS+=("-m")
+ ((MANY)) && CARGS+=("-m")
# Continue on fail? Add -f argument
((NOFAIL)) && CARGS+=("-f")
diff --git a/buildroot/bin/build_example b/buildroot/bin/build_example
index 623da8ac84c1..133f3c4cc9e0 100755
--- a/buildroot/bin/build_example
+++ b/buildroot/bin/build_example
@@ -211,22 +211,23 @@ while ((1)); do
# "Index out of range" can fail without an error
((MANY)) && ((ERR == 66)) && ERR=0 && break # "index out of range"
- # Short message reporting Error or Success
- ((ERR)) && alrt "Failed ($ERR)" || annc "Success"
-
set -e
if [[ $ERR -gt 0 ]]; then
+ alrt "Failed ($ERR)"
+
# Error? For --nofail simply log. Otherwise return the error.
if [[ -n $NOFAIL ]]; then
- date +"%F %T [FAIL] $CONFIG" >>./.pio/error-log.txt
+ date +"%F %T [FAIL] $CONFIG ($BUILDINDEX)" >>./.pio/error-log.txt
else
exit $ERR
fi
else
+ annc "Success"
+
# Copy exports back to the configs
if [[ -n $EXPNUM ]]; then
annc "Exporting $EXPNUM"
diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py
index 6ae379391096..efb8527869ea 100755
--- a/buildroot/share/PlatformIO/scripts/signature.py
+++ b/buildroot/share/PlatformIO/scripts/signature.py
@@ -364,7 +364,7 @@ def tryint(key):
with config_h.open('w') as outfile:
filegrp = { 'Configuration.h':'config:basic', 'Configuration_adv.h':'config:advanced' }
vers = build_defines["CONFIGURATION_H_VERSION"]
- dt_string = datetime.now().strftime("%Y-%m-%d at %H:%M:%S")
+ dt_string = datetime.utcnow().strftime("%Y-%m-%d at %H:%M:%S")
out_text = f'''/**
* Config.h - Marlin Firmware distilled configuration
From 2a137d67444e5de32589720930ebeba9db3b47cc Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Mon, 16 Dec 2024 14:58:03 -0600
Subject: [PATCH 36/43] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20build=20with=20Color?=
=?UTF-8?q?=20UI=20touch=20items?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
Marlin/src/lcd/menu/menu_probe_level.cpp | 6 ++----
Marlin/src/lcd/menu/menu_x_twist.cpp | 5 +++++
2 files changed, 7 insertions(+), 4 deletions(-)
diff --git a/Marlin/src/lcd/menu/menu_probe_level.cpp b/Marlin/src/lcd/menu/menu_probe_level.cpp
index 588a5b257bb4..ba806d665fe3 100644
--- a/Marlin/src/lcd/menu/menu_probe_level.cpp
+++ b/Marlin/src/lcd/menu/menu_probe_level.cpp
@@ -44,11 +44,9 @@
#include "../../feature/babystep.h"
#endif
-#if HAS_GRAPHICAL_TFT
+#if ALL(TOUCH_SCREEN, HAS_GRAPHICAL_TFT)
#include "../tft/tft.h"
- #if ENABLED(TOUCH_SCREEN)
- #include "../tft/touch.h"
- #endif
+ #include "../tft/touch.h"
#endif
#if ENABLED(LCD_BED_LEVELING) && ANY(PROBE_MANUALLY, MESH_BED_LEVELING)
diff --git a/Marlin/src/lcd/menu/menu_x_twist.cpp b/Marlin/src/lcd/menu/menu_x_twist.cpp
index 6c2ab70dbc57..a9998e3e4473 100644
--- a/Marlin/src/lcd/menu/menu_x_twist.cpp
+++ b/Marlin/src/lcd/menu/menu_x_twist.cpp
@@ -36,6 +36,11 @@
#define XATC_Y_POSITION ((probe.max_y() - probe.min_y())/2)
#endif
+#if ALL(TOUCH_SCREEN, HAS_GRAPHICAL_TFT)
+ #include "../tft/tft.h"
+ #include "../tft/touch.h"
+#endif
+
void _goto_manual_move_z(const_float_t);
float measured_z, z_offset;
From c4ef2d63e1c4651f652873b16e9e47339b66d851 Mon Sep 17 00:00:00 2001
From: Scott Lahteine
Date: Mon, 16 Dec 2024 15:30:01 -0600
Subject: [PATCH 37/43] =?UTF-8?q?=F0=9F=94=A5=20Remove=20obsolete=20suppor?=
=?UTF-8?q?t=20files?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
Followup to #15347
Originally from #10849
---
buildroot/share/vscode/avrdude.conf | 15478 --------------------
buildroot/share/vscode/avrdude_5.10_linux | Bin 1159576 -> 0 bytes
buildroot/share/vscode/avrdude_5.10_macOS | Bin 346784 -> 0 bytes
buildroot/share/vscode/avrdude_linux.conf | 15478 --------------------
buildroot/share/vscode/avrdude_macOS.conf | 15272 -------------------
5 files changed, 46228 deletions(-)
delete mode 100644 buildroot/share/vscode/avrdude.conf
delete mode 100644 buildroot/share/vscode/avrdude_5.10_linux
delete mode 100644 buildroot/share/vscode/avrdude_5.10_macOS
delete mode 100644 buildroot/share/vscode/avrdude_linux.conf
delete mode 100644 buildroot/share/vscode/avrdude_macOS.conf
diff --git a/buildroot/share/vscode/avrdude.conf b/buildroot/share/vscode/avrdude.conf
deleted file mode 100644
index c6056b4c0f60..000000000000
--- a/buildroot/share/vscode/avrdude.conf
+++ /dev/null
@@ -1,15478 +0,0 @@
-# $Id: avrdude.conf.in 916 2010-01-15 16:36:13Z joerg_wunsch $
-#
-# AVRDUDE Configuration File
-#
-# This file contains configuration data used by AVRDUDE which describes
-# the programming hardware pinouts and also provides part definitions.
-# AVRDUDE's "-C" command line option specifies the location of the
-# configuration file. The "-c" option names the programmer configuration
-# which must match one of the entry's "id" parameter. The "-p" option
-# identifies which part AVRDUDE is going to be programming and must match
-# one of the parts' "id" parameter.
-#
-# Possible entry formats are:
-#
-# programmer
-# id = [, [, ] ...] ; # are quoted strings
-# desc = ; # quoted string
-# type = par | stk500 | stk500v2 | stk500pp | stk500hvsp | stk500generic |
-# stk600 | stk600pp | stk600hvsp |
-# avr910 | butterfly | usbasp |
-# jtagmki | jtagmkii | jtagmkii_isp | jtagmkii_dw |
-# jtagmkII_avr32 | jtagmkii_pdi |
-# dragon_dw | dragon_jtag | dragon_isp | dragon_pp |
-# dragon_hvsp | dragon_pdi | arduino; # programmer type
-# baudrate = ; # baudrate for avr910-programmer
-# vcc = [, ... ] ; # pin number(s)
-# reset = ; # pin number
-# sck = ; # pin number
-# mosi = ; # pin number
-# miso = ; # pin number
-# errled = ; # pin number
-# rdyled = ; # pin number
-# pgmled = ; # pin number
-# vfyled = ; # pin number
-# ;
-#
-# part
-# id = ; # quoted string
-# desc = ; # quoted string
-# has_jtag = ; # part has JTAG i/f
-# has_debugwire = ; # part has debugWire i/f
-# has_pdi = ; # part has PDI i/f
-# has_tpi = ; # part has TPI i/f
-# devicecode = ; # deprecated, use stk500_devcode
-# stk500_devcode = ; # numeric
-# avr910_devcode = ; # numeric
-# signature = ; # signature bytes
-# chip_erase_delay = ; # micro-seconds
-# reset = dedicated | io;
-# retry_pulse = reset | sck;
-# pgm_enable = ;
-# chip_erase = ;
-# chip_erase_delay = ; # chip erase delay (us)
-# # STK500 parameters (parallel programming IO lines)
-# pagel = ; # pin name in hex, i.e., 0xD7
-# bs2 = ; # pin name in hex, i.e., 0xA0
-# serial = ; # can use serial downloading
-# parallel = ; # can use par. programming
-# # STK500v2 parameters, to be taken from Atmel's XML files
-# timeout = ;
-# stabdelay = ;
-# cmdexedelay = ;
-# synchloops = ;
-# bytedelay = ;
-# pollvalue = ;
-# pollindex = ;
-# predelay = ;
-# postdelay = ;
-# pollmethod = ;
-# mode = ;
-# delay = ;
-# blocksize = ;
-# readsize = ;
-# hvspcmdexedelay = ;
-# # STK500v2 HV programming parameters, from XML
-# pp_controlstack = , , ...; # PP only
-# hvsp_controlstack = , , ...; # HVSP only
-# hventerstabdelay = ;
-# progmodedelay = ; # PP only
-# latchcycles = ;
-# togglevtg = ;
-# poweroffdelay = ;
-# resetdelayms = ;
-# resetdelayus = ;
-# hvleavestabdelay = ;
-# resetdelay = ;
-# synchcycles = ; # HVSP only
-# chiperasepulsewidth = ; # PP only
-# chiperasepolltimeout = ;
-# chiperasetime = ; # HVSP only
-# programfusepulsewidth = ; # PP only
-# programfusepolltimeout = ;
-# programlockpulsewidth = ; # PP only
-# programlockpolltimeout = ;
-# # JTAG ICE mkII parameters, also from XML files
-# allowfullpagebitstream = ;
-# enablepageprogramming = ;
-# idr = ; # IO addr of IDR (OCD) reg.
-# rampz = ; # IO addr of RAMPZ reg.
-# spmcr = ; # mem addr of SPMC[S]R reg.
-# eecr = ; # mem addr of EECR reg.
-# # (only when != 0x3c)
-# is_avr32 = ; # AVR32 part
-#
-# memory
-# paged = ; # yes / no
-# size = ; # bytes
-# page_size = ; # bytes
-# num_pages = ; # numeric
-# min_write_delay = ; # micro-seconds
-# max_write_delay = ; # micro-seconds
-# readback_p1 = ; # byte value
-# readback_p2 = ; # byte value
-# pwroff_after_write = ; # yes / no
-# read = ;
-# write = ;
-# read_lo = ;
-# read_hi = ;
-# write_lo = ;
-# write_hi = ;
-# loadpage_lo = ;
-# loadpage_hi = ;
-# writepage = ;
-# ;
-# ;
-#
-# If any of the above parameters are not specified, the default value
-# of 0 is used for numerics or the empty string ("") for string
-# values. If a required parameter is left empty, AVRDUDE will
-# complain.
-#
-# NOTES:
-# * 'devicecode' is the device code used by the STK500 (see codes
-# listed below)
-# * Not all memory types will implement all instructions.
-# * AVR Fuse bits and Lock bits are implemented as a type of memory.
-# * Example memory types are:
-# "flash", "eeprom", "fuse", "lfuse" (low fuse), "hfuse" (high
-# fuse), "signature", "calibration", "lock"
-# * The memory type specified on the avrdude command line must match
-# one of the memory types defined for the specified chip.
-# * The pwroff_after_write flag causes avrdude to attempt to
-# power the device off and back on after an unsuccessful write to
-# the affected memory area if VCC programmer pins are defined. If
-# VCC pins are not defined for the programmer, a message
-# indicating that the device needs a power-cycle is printed out.
-# This flag was added to work around a problem with the
-# at90s4433/2333's; see the at90s4433 errata page 2 at:
-#
-# https://ww1.microchip.com/downloads/en/AppNotes/doc2574.pdf
-#
-# INSTRUCTION FORMATS
-#
-# Instruction formats are specified as a comma separated list of
-# string values containing information (bit specifiers) about each
-# of the 32 bits of the instruction. Bit specifiers may be one of
-# the following formats:
-#
-# '1' = the bit is always set on input as well as output
-#
-# '0' = the bit is always clear on input as well as output
-#
-# 'x' = the bit is ignored on input and output
-#
-# 'a' = the bit is an address bit, the bit-number matches this bit
-# specifier's position within the current instruction byte
-#
-# 'aN' = the bit is the Nth address bit, bit-number = N, i.e., a12
-# is address bit 12 on input, a0 is address bit 0.
-#
-# 'i' = the bit is an input data bit
-#
-# 'o' = the bit is an output data bit
-#
-# Each instruction must be composed of 32 bit specifiers. The
-# instruction specification closely follows the instruction data
-# provided in Atmel's data sheets for their parts.
-#
-# See below for some examples.
-#
-#
-# The following are STK500 part device codes to use for the
-# "devicecode" field of the part. These came from Atmel's software
-# section avr061.zip which accompanies the application note
-# AVR061 available from:
-#
-# https://www.microchip.com/en-us/application-notes/an2525
-#
-
-#define ATTINY10 0x10 /* the _old_ one that never existed! */
-#define ATTINY11 0x11
-#define ATTINY12 0x12
-#define ATTINY15 0x13
-#define ATTINY13 0x14
-
-#define ATTINY22 0x20
-#define ATTINY26 0x21
-#define ATTINY28 0x22
-#define ATTINY2313 0x23
-
-#define AT90S1200 0x33
-
-#define AT90S2313 0x40
-#define AT90S2323 0x41
-#define AT90S2333 0x42
-#define AT90S2343 0x43
-
-#define AT90S4414 0x50
-#define AT90S4433 0x51
-#define AT90S4434 0x52
-#define ATMEGA48 0x59
-
-#define AT90S8515 0x60
-#define AT90S8535 0x61
-#define AT90C8534 0x62
-#define ATMEGA8515 0x63
-#define ATMEGA8535 0x64
-
-#define ATMEGA8 0x70
-#define ATMEGA88 0x73
-#define ATMEGA168 0x86
-
-#define ATMEGA161 0x80
-#define ATMEGA163 0x81
-#define ATMEGA16 0x82
-#define ATMEGA162 0x83
-#define ATMEGA169 0x84
-
-#define ATMEGA323 0x90
-#define ATMEGA32 0x91
-
-#define ATMEGA64 0xA0
-
-#define ATMEGA103 0xB1
-#define ATMEGA128 0xB2
-#define AT90CAN128 0xB3
-#define AT90CAN64 0xB3
-#define AT90CAN32 0xB3
-
-#define AT86RF401 0xD0
-
-#define AT89START 0xE0
-#define AT89S51 0xE0
-#define AT89S52 0xE1
-
-# The following table lists the devices in the original AVR910
-# appnote:
-# |Device |Signature | Code |
-# +-------+----------+------+
-# |tiny12 | 1E 90 05 | 0x55 |
-# |tiny15 | 1E 90 06 | 0x56 |
-# | | | |
-# | S1200 | 1E 90 01 | 0x13 |
-# | | | |
-# | S2313 | 1E 91 01 | 0x20 |
-# | S2323 | 1E 91 02 | 0x48 |
-# | S2333 | 1E 91 05 | 0x34 |
-# | S2343 | 1E 91 03 | 0x4C |
-# | | | |
-# | S4414 | 1E 92 01 | 0x28 |
-# | S4433 | 1E 92 03 | 0x30 |
-# | S4434 | 1E 92 02 | 0x6C |
-# | | | |
-# | S8515 | 1E 93 01 | 0x38 |
-# | S8535 | 1E 93 03 | 0x68 |
-# | | | |
-# |mega32 | 1E 95 01 | 0x72 |
-# |mega83 | 1E 93 05 | 0x65 |
-# |mega103| 1E 97 01 | 0x41 |
-# |mega161| 1E 94 01 | 0x60 |
-# |mega163| 1E 94 02 | 0x64 |
-
-# Appnote AVR109 also has a table of AVR910 device codes, which
-# lists:
-# dev avr910 signature
-# ATmega8 0x77 0x1E 0x93 0x07
-# ATmega8515 0x3B 0x1E 0x93 0x06
-# ATmega8535 0x6A 0x1E 0x93 0x08
-# ATmega16 0x75 0x1E 0x94 0x03
-# ATmega162 0x63 0x1E 0x94 0x04
-# ATmega163 0x66 0x1E 0x94 0x02
-# ATmega169 0x79 0x1E 0x94 0x05
-# ATmega32 0x7F 0x1E 0x95 0x02
-# ATmega323 0x73 0x1E 0x95 0x01
-# ATmega64 0x46 0x1E 0x96 0x02
-# ATmega128 0x44 0x1E 0x97 0x02
-#
-# These codes refer to "BOOT" device codes which are apparently
-# different than standard device codes, for whatever reasons
-# (often one above the standard code).
-
-# There are several extended versions of AVR910 implementations around
-# in the Internet. These add the following codes (only devices that
-# actually exist are listed):
-
-# ATmega8515 0x3A
-# ATmega128 0x43
-# ATmega64 0x45
-# ATtiny26 0x5E
-# ATmega8535 0x69
-# ATmega32 0x72
-# ATmega16 0x74
-# ATmega8 0x76
-# ATmega169 0x78
-
-#
-# Overall avrdude defaults
-#
-default_parallel = "lpt1";
-default_serial = "com1";
-
-
-#
-# PROGRAMMER DEFINITIONS
-#
-
-programmer
- id = "arduino";
- desc = "Arduino";
- type = arduino;
-;
-
-programmer
- id = "avrisp";
- desc = "Atmel AVR ISP";
- type = stk500;
-;
-
-programmer
- id = "avrispv2";
- desc = "Atmel AVR ISP V2";
- type = stk500v2;
-;
-
-programmer
- id = "avrispmkII";
- desc = "Atmel AVR ISP mkII";
- type = stk500v2;
-;
-
-programmer
- id = "avrisp2";
- desc = "Atmel AVR ISP mkII";
- type = stk500v2;
-;
-
-programmer
- id = "buspirate";
- desc = "The Bus Pirate";
- type = buspirate;
-;
-
-# This is supposed to be the "default" STK500 entry.
-# Attempts to select the correct firmware version
-# by probing for it. Better use one of the entries
-# below instead.
-programmer
- id = "stk500";
- desc = "Atmel STK500";
- type = stk500generic;
-;
-
-programmer
- id = "stk500v1";
- desc = "Atmel STK500 Version 1.x firmware";
- type = stk500;
-;
-
-programmer
- id = "mib510";
- desc = "Crossbow MIB510 programming board";
- type = stk500;
-;
-
-programmer
- id = "stk500v2";
- desc = "Atmel STK500 Version 2.x firmware";
- type = stk500v2;
-;
-
-programmer
- id = "stk500pp";
- desc = "Atmel STK500 V2 in parallel programming mode";
- type = stk500pp;
-;
-
-programmer
- id = "stk500hvsp";
- desc = "Atmel STK500 V2 in high-voltage serial programming mode";
- type = stk500hvsp;
-;
-
-programmer
- id = "stk600";
- desc = "Atmel STK600";
- type = stk600;
-;
-
-programmer
- id = "stk600pp";
- desc = "Atmel STK600 in parallel programming mode";
- type = stk600pp;
-;
-
-programmer
- id = "stk600hvsp";
- desc = "Atmel STK600 in high-voltage serial programming mode";
- type = stk600hvsp;
-;
-
-programmer
- id = "avr910";
- desc = "Atmel Low Cost Serial Programmer";
- type = avr910;
-;
-
-programmer
- id = "usbasp";
- desc = "USBasp, https://www.fischl.de/usbasp/";
- type = usbasp;
-;
-
-programmer
- id = "usbtiny";
- desc = "USBtiny simple USB programmer, https://learn.adafruit.com/usbtinyisp";
- type = usbtiny;
-;
-
-programmer
- id = "butterfly";
- desc = "Atmel Butterfly Development Board";
- type = butterfly;
-;
-
-programmer
- id = "avr109";
- desc = "Atmel AppNote AVR109 Boot Loader";
- type = butterfly;
-;
-
-programmer
- id = "avr911";
- desc = "Atmel AppNote AVR911 AVROSP";
- type = butterfly;
-;
-
-programmer
- id = "jtagmkI";
- desc = "Atmel JTAG ICE (mkI)";
- baudrate = 115200; # default is 115200
- type = jtagmki;
-;
-
-# easier to type
-programmer
- id = "jtag1";
- desc = "Atmel JTAG ICE (mkI)";
- baudrate = 115200; # default is 115200
- type = jtagmki;
-;
-
-# easier to type
-programmer
- id = "jtag1slow";
- desc = "Atmel JTAG ICE (mkI)";
- baudrate = 19200;
- type = jtagmki;
-;
-
-programmer
- id = "jtagmkII";
- desc = "Atmel JTAG ICE mkII";
- baudrate = 19200; # default is 19200
- type = jtagmkii;
-;
-
-# easier to type
-programmer
- id = "jtag2slow";
- desc = "Atmel JTAG ICE mkII";
- baudrate = 19200; # default is 19200
- type = jtagmkii;
-;
-
-# JTAG ICE mkII @ 115200 Bd
-programmer
- id = "jtag2fast";
- desc = "Atmel JTAG ICE mkII";
- baudrate = 115200;
- type = jtagmkii;
-;
-
-# make the fast one the default, people will love that
-programmer
- id = "jtag2";
- desc = "Atmel JTAG ICE mkII";
- baudrate = 115200;
- type = jtagmkii;
-;
-
-# JTAG ICE mkII in ISP mode
-programmer
- id = "jtag2isp";
- desc = "Atmel JTAG ICE mkII in ISP mode";
- baudrate = 115200;
- type = jtagmkii_isp;
-;
-
-# JTAG ICE mkII in debugWire mode
-programmer
- id = "jtag2dw";
- desc = "Atmel JTAG ICE mkII in debugWire mode";
- baudrate = 115200;
- type = jtagmkii_dw;
-;
-
-# JTAG ICE mkII in AVR32 mode
-programmer
- id = "jtagmkII_avr32";
- desc = "Atmel JTAG ICE mkII im AVR32 mode";
- baudrate = 115200;
- type = jtagmkii_avr32;
-;
-
-# JTAG ICE mkII in AVR32 mode
-programmer
- id = "jtag2avr32";
- desc = "Atmel JTAG ICE mkII im AVR32 mode";
- baudrate = 115200;
- type = jtagmkii_avr32;
-;
-
-# JTAG ICE mkII in PDI mode
-programmer
- id = "jtag2pdi";
- desc = "Atmel JTAG ICE mkII PDI mode";
- baudrate = 115200;
- type = jtagmkii_pdi;
-;
-
-# AVR Dragon in JTAG mode
-programmer
- id = "dragon_jtag";
- desc = "Atmel AVR Dragon in JTAG mode";
- baudrate = 115200;
- type = dragon_jtag;
-;
-
-# AVR Dragon in ISP mode
-programmer
- id = "dragon_isp";
- desc = "Atmel AVR Dragon in ISP mode";
- baudrate = 115200;
- type = dragon_isp;
-;
-
-# AVR Dragon in PP mode
-programmer
- id = "dragon_pp";
- desc = "Atmel AVR Dragon in PP mode";
- baudrate = 115200;
- type = dragon_pp;
-;
-
-# AVR Dragon in HVSP mode
-programmer
- id = "dragon_hvsp";
- desc = "Atmel AVR Dragon in HVSP mode";
- baudrate = 115200;
- type = dragon_hvsp;
-;
-
-# AVR Dragon in debugWire mode
-programmer
- id = "dragon_dw";
- desc = "Atmel AVR Dragon in debugWire mode";
- baudrate = 115200;
- type = dragon_dw;
-;
-
-# AVR Dragon in PDI mode
-programmer
- id = "dragon_pdi";
- desc = "Atmel AVR Dragon in PDI mode";
- baudrate = 115200;
- type = dragon_pdi;
-;
-
-programmer
- id = "pavr";
- desc = "Jason Kyle's pAVR Serial Programmer";
- type = avr910;
-;
-
-# Parallel port programmers.
-
-programmer
- id = "bsd";
- desc = "Brian Dean's Programmer, https://savannah.nongnu.org/projects/avrdude";
- type = par;
- vcc = 2, 3, 4, 5;
- reset = 7;
- sck = 8;
- mosi = 9;
- miso = 10;
-;
-
-programmer
- id = "stk200";
- desc = "STK200";
- type = par;
- buff = 4, 5;
- sck = 6;
- mosi = 7;
- reset = 9;
- miso = 10;
-;
-
-# The programming dongle used by the popular Ponyprog
-# utility. It is almost similar to the STK200 one,
-# except that there is a LED indicating that the
-# programming is currently in progress.
-
-programmer
- id = "pony-stk200";
- desc = "Pony Prog STK200";
- type = par;
- buff = 4, 5;
- sck = 6;
- mosi = 7;
- reset = 9;
- miso = 10;
- pgmled = 8;
-;
-
-programmer
- id = "dt006";
- desc = "Dontronics DT006";
- type = par;
- reset = 4;
- sck = 5;
- mosi = 2;
- miso = 11;
-;
-
-programmer
- id = "bascom";
- desc = "Bascom SAMPLE programming cable";
- type = par;
- reset = 4;
- sck = 5;
- mosi = 2;
- miso = 11;
-;
-
-programmer
- id = "alf";
- desc = "Nightshade ALF-PgmAVR, http://nightshade.homeip.net/";
- type = par;
- vcc = 2, 3, 4, 5;
- buff = 6;
- reset = 7;
- sck = 8;
- mosi = 9;
- miso = 10;
- errled = 1;
- rdyled = 14;
- pgmled = 16;
- vfyled = 17;
-;
-
-programmer
- id = "sp12";
- desc = "Steve Bolt's Programmer";
- type = par;
- vcc = 4,5,6,7,8;
- reset = 3;
- sck = 2;
- mosi = 9;
- miso = 11;
-;
-
-programmer
- id = "picoweb";
- desc = "Picoweb Programming Cable, http://www.picoweb.net/";
- type = par;
- reset = 2;
- sck = 3;
- mosi = 4;
- miso = 13;
-;
-
-programmer
- id = "abcmini";
- desc = "ABCmini Board, aka Dick Smith HOTCHIP";
- type = par;
- reset = 4;
- sck = 3;
- mosi = 2;
- miso = 10;
-;
-
-programmer
- id = "futurlec";
- desc = "Futurlec.com programming cable.";
- type = par;
- reset = 3;
- sck = 2;
- mosi = 1;
- miso = 10;
-;
-
-
-# From the contributor of the "xil" jtag cable:
-# The "vcc" definition isn't really vcc (the cable gets its power from
-# the programming circuit) but is necessary to switch one of the
-# buffer lines (trying to add it to the "buff" lines doesn't work).
-# With this, TMS connects to RESET, TDI to MOSI, TDO to MISO and TCK
-# to SCK (plus vcc/gnd of course)
-programmer
- id = "xil";
- desc = "Xilinx JTAG cable";
- type = par;
- mosi = 2;
- sck = 3;
- reset = 4;
- buff = 5;
- miso = 13;
- vcc = 6;
-;
-
-
-programmer
- id = "dapa";
- desc = "Direct AVR Parallel Access cable";
- type = par;
- vcc = 3;
- reset = 16;
- sck = 1;
- mosi = 2;
- miso = 11;
-;
-
-programmer
- id = "atisp";
- desc = "AT-ISP V1.1 programming cable for AVR-SDK1 from micro-research.co.th";
- type = par;
- reset = ~6;
- sck = ~8;
- mosi = ~7;
- miso = ~10;
-;
-
-programmer
- id = "ere-isp-avr";
- desc = "ERE ISP-AVR ";
- type = par;
- reset = ~4;
- sck = 3;
- mosi = 2;
- miso = 10;
-;
-
-programmer
- id = "blaster";
- desc = "Altera ByteBlaster";
- type = par;
- sck = 2;
- miso = 11;
- reset = 3;
- mosi = 8;
- buff = 14;
-;
-
-# It is almost same as pony-stk200, except vcc on pin 5 to auto
-# disconnect port download on http://www.electropol.fr
-programmer
- id = "frank-stk200";
- desc = "Frank STK200";
- type = par;
- vcc = 5;
- sck = 6;
- mosi = 7;
- reset = 9;
- miso = 10;
- pgmled = 8;
-;
-
-# The AT98ISP Cable is a simple parallel dongle for AT89 family.
-# https://www.microchip.com/wwwAppNotes/AppNotes.aspx?appnote=en592141
-programmer
-id = "89isp";
-desc = "Atmel at89isp cable";
-type = par;
-reset = 17;
-sck = 1;
-mosi = 2;
-miso = 10;
-;
-
-
-#
-# some ultra cheap programmers use bitbanging on the
-# serialport.
-#
-# PC - DB9 - Pins for RS232:
-#
-# GND 5 -- |O
-# | O| <- 9 RI
-# DTR 4 <- |O |
-# | O| <- 8 CTS
-# TXD 3 <- |O |
-# | O| -> 7 RTS
-# RXD 2 -> |O |
-# | O| <- 6 DSR
-# DCD 1 -> |O
-#
-# Using RXD is currently not supported.
-# Using RI is not supported under Win32 but is supported under Posix.
-
-# serial ponyprog design (dasa2 in uisp)
-# reset=!txd sck=rts mosi=dtr miso=cts
-
-programmer
- id = "ponyser";
- desc = "design ponyprog serial, reset=!txd sck=rts mosi=dtr miso=cts";
- type = serbb;
- reset = ~3;
- sck = 7;
- mosi = 4;
- miso = 8;
-;
-
-# Same as above, different name
-# reset=!txd sck=rts mosi=dtr miso=cts
-
-programmer
- id = "siprog";
- desc = "Lancos SI-Prog ";
- type = serbb;
- reset = ~3;
- sck = 7;
- mosi = 4;
- miso = 8;
-;
-
-# unknown (dasa in uisp)
-# reset=rts sck=dtr mosi=txd miso=cts
-
-programmer
- id = "dasa";
- desc = "serial port banging, reset=rts sck=dtr mosi=txd miso=cts";
- type = serbb;
- reset = 7;
- sck = 4;
- mosi = 3;
- miso = 8;
-;
-
-# unknown (dasa3 in uisp)
-# reset=!dtr sck=rts mosi=txd miso=cts
-
-programmer
- id = "dasa3";
- desc = "serial port banging, reset=!dtr sck=rts mosi=txd miso=cts";
- type = serbb;
- reset = ~4;
- sck = 7;
- mosi = 3;
- miso = 8;
-;
-
-# C2N232i (jumper configuration "auto")
-# reset=dtr sck=!rts mosi=!txd miso=!cts
-
-programmer
- id = "c2n232i";
- desc = "serial port banging, reset=dtr sck=!rts mosi=!txd miso=!cts";
- type = serbb;
- reset = 4;
- sck = ~7;
- mosi = ~3;
- miso = ~8;
-;
-
-#
-# PART DEFINITIONS
-#
-
-#------------------------------------------------------------
-# ATtiny11
-#------------------------------------------------------------
-
-# This is an HVSP-only device.
-
-part
- id = "t11";
- desc = "ATtiny11";
- stk500_devcode = 0x11;
- signature = 0x1e 0x90 0x04;
- chip_erase_delay = 20000;
-
- timeout = 200;
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00,
- 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78,
- 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 0;
- resetdelayus = 50;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 64;
- blocksize = 64;
- readsize = 256;
- delay = 5;
- ;
-
- memory "flash"
- size = 1024;
- blocksize = 128;
- readsize = 256;
- delay = 3;
- ;
-
- memory "signature"
- size = 3;
- ;
-
- memory "lock"
- size = 1;
- ;
-
- memory "calibration"
- size = 1;
- ;
-
- memory "fuse"
- size = 1;
- ;
-;
-
-#------------------------------------------------------------
-# ATtiny12
-#------------------------------------------------------------
-
-part
- id = "t12";
- desc = "ATtiny12";
- stk500_devcode = 0x12;
- avr910_devcode = 0x55;
- signature = 0x1e 0x90 0x05;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00,
- 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78,
- 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00;
- hventerstabdelay = 100;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 0;
- resetdelayus = 50;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 64;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 x x x x x x x x",
- "x x a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 x x x x x x x x",
- "x x a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 8;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "flash"
- size = 1024;
- min_write_delay = 4500;
- max_write_delay = 20000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 5;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x o o x";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "fuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 x x x x x x x x",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-;
-
-#------------------------------------------------------------
-# ATtiny13
-#------------------------------------------------------------
-
-part
- id = "t13";
- desc = "ATtiny13";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x0E, 0x1E;
- eeprom_instr = 0xBB, 0xFE, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x0E, 0xB4, 0x0E, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
- stk500_devcode = 0x14;
- signature = 0x1e 0x90 0x07;
- chip_erase_delay = 4000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66,
- 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78,
- 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 0;
- resetdelayus = 90;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 64;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x",
- "x x a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x",
- "x x a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 5;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 1024;
- page_size = 32;
- num_pages = 32;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 0 0 0 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 0 0 0 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 0 0 0 a8",
- " a7 a6 a5 a4 x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 2;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 a0 o o o o o o o o";
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- ;
-
-;
-
-
-#------------------------------------------------------------
-# ATtiny15
-#------------------------------------------------------------
-
-part
- id = "t15";
- desc = "ATtiny15";
- stk500_devcode = 0x13;
- avr910_devcode = 0x56;
- signature = 0x1e 0x90 0x06;
- chip_erase_delay = 8200;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00,
- 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78,
- 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00;
- hventerstabdelay = 100;
- hvspcmdexedelay = 5;
- synchcycles = 6;
- latchcycles = 16;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 0;
- resetdelayus = 50;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 64;
- min_write_delay = 8200;
- max_write_delay = 8200;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 x x x x x x x x",
- "x x a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 x x x x x x x x",
- "x x a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 10;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "flash"
- size = 1024;
- min_write_delay = 4100;
- max_write_delay = 4100;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 5;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x o o x";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "fuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 x x x x x x x x",
- "x x x x x x x x o o o o x x o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x",
- "x x x x x x x x i i i i 1 1 i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-;
-
-#------------------------------------------------------------
-# AT90s1200
-#------------------------------------------------------------
-
-part
- id = "1200";
- desc = "AT90S1200";
- stk500_devcode = 0x33;
- avr910_devcode = 0x13;
- signature = 0x1e 0x90 0x01;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 1;
- bytedelay = 0;
- pollindex = 0;
- pollvalue = 0xFF;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 15;
- chiperasepolltimeout = 0;
- programfusepulsewidth = 2;
- programfusepolltimeout = 0;
- programlockpulsewidth = 0;
- programlockpolltimeout = 1;
-
- memory "eeprom"
- size = 64;
- min_write_delay = 4000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 x x x x x x x x",
- "x x a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 x x x x x x x x",
- "x x a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 20;
- blocksize = 32;
- readsize = 256;
- ;
- memory "flash"
- size = 1024;
- min_write_delay = 4000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x02;
- delay = 15;
- blocksize = 128;
- readsize = 256;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- ;
- memory "lock"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90s4414
-#------------------------------------------------------------
-
-part
- id = "4414";
- desc = "AT90S4414";
- stk500_devcode = 0x50;
- avr910_devcode = 0x28;
- signature = 0x1e 0x92 0x01;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 15;
- chiperasepolltimeout = 0;
- programfusepulsewidth = 2;
- programfusepolltimeout = 0;
- programlockpulsewidth = 0;
- programlockpolltimeout = 1;
-
- memory "eeprom"
- size = 256;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0x80;
- readback_p2 = 0x7f;
- read = " 1 0 1 0 0 0 0 0 x x x x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0 x x x x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 64;
- readsize = 256;
- ;
- memory "flash"
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0x7f;
- readback_p2 = 0x7f;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 64;
- readsize = 256;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
- ;
-
-#------------------------------------------------------------
-# AT90s2313
-#------------------------------------------------------------
-
-part
- id = "2313";
- desc = "AT90S2313";
- stk500_devcode = 0x40;
- avr910_devcode = 0x20;
- signature = 0x1e 0x91 0x01;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 15;
- chiperasepolltimeout = 0;
- programfusepulsewidth = 2;
- programfusepolltimeout = 0;
- programlockpulsewidth = 0;
- programlockpolltimeout = 1;
-
- memory "eeprom"
- size = 128;
- min_write_delay = 4000;
- max_write_delay = 9000;
- readback_p1 = 0x80;
- readback_p2 = 0x7f;
- read = "1 0 1 0 0 0 0 0 x x x x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 x x x x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 64;
- readsize = 256;
- ;
- memory "flash"
- size = 2048;
- min_write_delay = 4000;
- max_write_delay = 9000;
- readback_p1 = 0x7f;
- readback_p2 = 0x7f;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x i i x",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
- ;
-
-#------------------------------------------------------------
-# AT90s2333
-#------------------------------------------------------------
-
-part
- id = "2333";
-##### WARNING: No XML file for device 'AT90S2333'! #####
- desc = "AT90S2333";
- stk500_devcode = 0x42;
- avr910_devcode = 0x34;
- signature = 0x1e 0x91 0x05;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 15;
- chiperasepolltimeout = 0;
- programfusepulsewidth = 2;
- programfusepolltimeout = 0;
- programlockpulsewidth = 0;
- programlockpolltimeout = 1;
-
- memory "eeprom"
- size = 128;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0x00;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 x x x x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 x x x x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "flash"
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- pwroff_after_write = yes;
- read = "0 1 0 1 0 0 0 0 x x x x x x x x",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i",
- "x x x x x x x x x x x x x x x x";
- ;
- memory "lock"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x o o x";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- ;
- ;
-
-
-#------------------------------------------------------------
-# AT90s2343 (also AT90s2323 and ATtiny22)
-#------------------------------------------------------------
-
-part
- id = "2343";
- desc = "AT90S2343";
- stk500_devcode = 0x43;
- avr910_devcode = 0x4c;
- signature = 0x1e 0x91 0x03;
- chip_erase_delay = 18000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00,
- 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78,
- 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00;
- hventerstabdelay = 100;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 0;
- poweroffdelay = 25;
- resetdelayms = 0;
- resetdelayus = 50;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 128;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0x00;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0",
- "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0",
- "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 64;
- readsize = 256;
- ;
- memory "flash"
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 128;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x o o o x x x x o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 1 1 1 1 i",
- "x x x x x x x x x x x x x x x x";
- ;
- memory "lock"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x o o o x x x x o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- ;
- ;
-
-
-#------------------------------------------------------------
-# AT90s4433
-#------------------------------------------------------------
-
-part
- id = "4433";
- desc = "AT90S4433";
- stk500_devcode = 0x51;
- avr910_devcode = 0x30;
- signature = 0x1e 0x92 0x03;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 15;
- chiperasepolltimeout = 0;
- programfusepulsewidth = 2;
- programfusepolltimeout = 0;
- programlockpulsewidth = 0;
- programlockpolltimeout = 1;
-
- memory "eeprom"
- size = 256;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0x00;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0 x x x x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0 x x x x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
- memory "flash"
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- pwroff_after_write = yes;
- read = "0 1 0 1 0 0 0 0 x x x x x x x x",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i",
- "x x x x x x x x x x x x x x x x";
- ;
- memory "lock"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x o o x";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90s4434
-#------------------------------------------------------------
-
-part
- id = "4434";
-##### WARNING: No XML file for device 'AT90S4434'! #####
- desc = "AT90S4434";
- stk500_devcode = 0x52;
- avr910_devcode = 0x6c;
- signature = 0x1e 0x92 0x02;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- memory "eeprom"
- size = 256;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0x00;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0 x x x x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0 x x x x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
- ;
- memory "flash"
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- read = "0 1 0 1 0 0 0 0 x x x x x x x x",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i",
- "x x x x x x x x x x x x x x x x";
- ;
- memory "lock"
- size = 1;
- min_write_delay = 9000;
- max_write_delay = 20000;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x o o x";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90s8515
-#------------------------------------------------------------
-
-part
- id = "8515";
- desc = "AT90S8515";
- stk500_devcode = 0x60;
- avr910_devcode = 0x38;
- signature = 0x1e 0x93 0x01;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- resetdelay = 15;
- chiperasepulsewidth = 15;
- chiperasepolltimeout = 0;
- programfusepulsewidth = 2;
- programfusepolltimeout = 0;
- programlockpulsewidth = 0;
- programlockpolltimeout = 1;
-
- memory "eeprom"
- size = 512;
- min_write_delay = 4000;
- max_write_delay = 9000;
- readback_p1 = 0x80;
- readback_p2 = 0x7f;
- read = " 1 0 1 0 0 0 0 0 x x x x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0 x x x x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
- memory "flash"
- size = 8192;
- min_write_delay = 4000;
- max_write_delay = 9000;
- readback_p1 = 0x7f;
- readback_p2 = 0x7f;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
- ;
-
-#------------------------------------------------------------
-# AT90s8535
-#------------------------------------------------------------
-
-part
- id = "8535";
- desc = "AT90S8535";
- stk500_devcode = 0x61;
- avr910_devcode = 0x68;
- signature = 0x1e 0x93 0x03;
- chip_erase_delay = 20000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 15;
- chiperasepolltimeout = 0;
- programfusepulsewidth = 2;
- programfusepolltimeout = 0;
- programlockpulsewidth = 0;
- programlockpolltimeout = 1;
-
- memory "eeprom"
- size = 512;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0x00;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0 x x x x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0 x x x x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
- memory "flash"
- size = 8192;
- min_write_delay = 9000;
- max_write_delay = 20000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write_lo = " 0 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- write_hi = " 0 1 0 0 1 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 128;
- readsize = 256;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "fuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x x x o";
- write = "1 0 1 0 1 1 0 0 1 0 1 1 1 1 1 i",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x o o x x x x x x";
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega103
-#------------------------------------------------------------
-
-part
- id = "m103";
- desc = "ATMEGA103";
- stk500_devcode = 0xB1;
- avr910_devcode = 0x41;
- signature = 0x1e 0x97 0x01;
- chip_erase_delay = 112000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x8E, 0x9E, 0x2E, 0x3E, 0xAE, 0xBE,
- 0x4E, 0x5E, 0xCE, 0xDE, 0x6E, 0x7E, 0xEE, 0xDE,
- 0x66, 0x76, 0xE6, 0xF6, 0x6A, 0x7A, 0xEA, 0x7A,
- 0x7F, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 15;
- chiperasepolltimeout = 0;
- programfusepulsewidth = 2;
- programfusepolltimeout = 0;
- programlockpulsewidth = 0;
- programlockpolltimeout = 10;
-
- memory "eeprom"
- size = 4096;
- min_write_delay = 4000;
- max_write_delay = 9000;
- readback_p1 = 0x80;
- readback_p2 = 0x7f;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 22000;
- max_write_delay = 56000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x11;
- delay = 70;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "fuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 x x x x x x x x",
- "x x x x x x x x x x o x o 1 o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 1 i 1 i i",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x o o x";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# ATmega64
-#------------------------------------------------------------
-
-part
- id = "m64";
- desc = "ATMEGA64";
- has_jtag = yes;
- stk500_devcode = 0xA0;
- avr910_devcode = 0x45;
- signature = 0x1e 0x96 0x02;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x22;
- spmcr = 0x68;
- allowfullpagebitstream = yes;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 20;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 4;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-
-
-#------------------------------------------------------------
-# ATmega128
-#------------------------------------------------------------
-
-part
- id = "m128";
- desc = "ATMEGA128";
- has_jtag = yes;
- stk500_devcode = 0xB2;
- avr910_devcode = 0x43;
- signature = 0x1e 0x97 0x02;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x22;
- spmcr = 0x68;
- rampz = 0x3b;
- allowfullpagebitstream = yes;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 12;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 4;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90CAN128
-#------------------------------------------------------------
-
-part
- id = "c128";
- desc = "AT90CAN128";
- has_jtag = yes;
- stk500_devcode = 0xB3;
-# avr910_devcode = 0x43;
- signature = 0x1e 0x97 0x81;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- eecr = 0x3f;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90CAN64
-#------------------------------------------------------------
-
-part
- id = "c64";
- desc = "AT90CAN64";
- has_jtag = yes;
- stk500_devcode = 0xB3;
-# avr910_devcode = 0x43;
- signature = 0x1e 0x96 0x81;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- eecr = 0x3f;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90CAN32
-#------------------------------------------------------------
-
-part
- id = "c32";
- desc = "AT90CAN32";
- has_jtag = yes;
- stk500_devcode = 0xB3;
-# avr910_devcode = 0x43;
- signature = 0x1e 0x95 0x81;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- eecr = 0x3f;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 256;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# ATmega16
-#------------------------------------------------------------
-
-part
- id = "m16";
- desc = "ATMEGA16";
- has_jtag = yes;
- stk500_devcode = 0x82;
- avr910_devcode = 0x74;
- signature = 0x1e 0x94 0x03;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 100;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- resetdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = yes;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 512;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x04;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 16384;
- page_size = 128;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "calibration"
- size = 4;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# ATmega164P
-#------------------------------------------------------------
-
-# close to ATmega16
-
-part
- id = "m164p";
- desc = "ATMEGA164P";
- has_jtag = yes;
- stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one
- avr910_devcode = 0x74;
- signature = 0x1e 0x94 0x0a;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 512;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 16384;
- page_size = 128;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# ATmega324P
-#------------------------------------------------------------
-
-# similar to ATmega164P
-
-part
- id = "m324p";
- desc = "ATMEGA324P";
- has_jtag = yes;
- stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one
- avr910_devcode = 0x74;
- signature = 0x1e 0x95 0x08;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# ATmega644
-#------------------------------------------------------------
-
-# similar to ATmega164
-
-part
- id = "m644";
- desc = "ATMEGA644";
- has_jtag = yes;
- stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one
- avr910_devcode = 0x74;
- signature = 0x1e 0x96 0x09;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega644P
-#------------------------------------------------------------
-
-# similar to ATmega164p
-
-part
- id = "m644p";
- desc = "ATMEGA644P";
- has_jtag = yes;
- stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one
- avr910_devcode = 0x74;
- signature = 0x1e 0x96 0x0a;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-
-
-#------------------------------------------------------------
-# ATmega1284P
-#------------------------------------------------------------
-
-# similar to ATmega164p
-
-part
- id = "m1284p";
- desc = "ATMEGA1284P";
- has_jtag = yes;
- stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one
- avr910_devcode = 0x74;
- signature = 0x1e 0x97 0x05;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-
-
-#------------------------------------------------------------
-# ATmega162
-#------------------------------------------------------------
-
-part
- id = "m162";
- desc = "ATMEGA162";
- has_jtag = yes;
- stk500_devcode = 0x83;
- avr910_devcode = 0x63;
- signature = 0x1e 0x94 0x04;
- chip_erase_delay = 9000;
- pagel = 0xd7;
- bs2 = 0xa0;
-
- idr = 0x04;
- spmcr = 0x57;
- allowfullpagebitstream = yes;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- memory "flash"
- paged = yes;
- size = 16384;
- page_size = 128;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
-
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
-
- ;
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 512;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
-
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 16000;
- max_write_delay = 16000;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 16000;
- max_write_delay = 16000;
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 16000;
- max_write_delay = 16000;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x 1 1 1 1 1 i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 16000;
- max_write_delay = 16000;
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
-
- read = "0 0 1 1 0 0 0 0 0 0 x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-;
-
-
-
-#------------------------------------------------------------
-# ATmega163
-#------------------------------------------------------------
-
-part
- id = "m163";
- desc = "ATMEGA163";
- stk500_devcode = 0x81;
- avr910_devcode = 0x64;
- signature = 0x1e 0x94 0x02;
- chip_erase_delay = 32000;
- pagel = 0xd7;
- bs2 = 0xa0;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 30;
- programfusepulsewidth = 0;
- programfusepolltimeout = 2;
- programlockpulsewidth = 0;
- programlockpolltimeout = 2;
-
-
- memory "eeprom"
- size = 512;
- min_write_delay = 4000;
- max_write_delay = 4000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
- mode = 0x41;
- delay = 20;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 16384;
- page_size = 128;
- num_pages = 128;
- min_write_delay = 16000;
- max_write_delay = 16000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x11;
- delay = 20;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o x x o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i 1 1 i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x 1 o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x 1 1 1 1 1 i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x 0 x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega169
-#------------------------------------------------------------
-
-part
- id = "m169";
- desc = "ATMEGA169";
- has_jtag = yes;
- stk500_devcode = 0x85;
- avr910_devcode = 0x78;
- signature = 0x1e 0x94 0x05;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 512;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 16384;
- page_size = 128;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega329
-#------------------------------------------------------------
-
-part
- id = "m329";
- desc = "ATMEGA329";
- has_jtag = yes;
-# stk500_devcode = 0x85; # no STK500 support, only STK500v2
-# avr910_devcode = 0x?; # try the ATmega169 one:
- avr910_devcode = 0x75;
- signature = 0x1e 0x95 0x03;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega329P
-#------------------------------------------------------------
-# Identical to ATmega329 except of the signature
-
-part
- id = "m329p";
- desc = "ATMEGA329P";
- has_jtag = yes;
-# stk500_devcode = 0x85; # no STK500 support, only STK500v2
-# avr910_devcode = 0x?; # try the ATmega169 one:
- avr910_devcode = 0x75;
- signature = 0x1e 0x95 0x0b;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega3290
-#------------------------------------------------------------
-
-# identical to ATmega329
-
-part
- id = "m3290";
- desc = "ATMEGA3290";
- has_jtag = yes;
-# stk500_devcode = 0x85; # no STK500 support, only STK500v2
-# avr910_devcode = 0x?; # try the ATmega169 one:
- avr910_devcode = 0x75;
- signature = 0x1e 0x95 0x04;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a3 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega3290P
-#------------------------------------------------------------
-
-# identical to ATmega3290 except of the signature
-
-part
- id = "m3290p";
- desc = "ATMEGA3290P";
- has_jtag = yes;
-# stk500_devcode = 0x85; # no STK500 support, only STK500v2
-# avr910_devcode = 0x?; # try the ATmega169 one:
- avr910_devcode = 0x75;
- signature = 0x1e 0x95 0x0c;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a3 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega649
-#------------------------------------------------------------
-
-part
- id = "m649";
- desc = "ATMEGA649";
- has_jtag = yes;
-# stk500_devcode = 0x85; # no STK500 support, only STK500v2
-# avr910_devcode = 0x?; # try the ATmega169 one:
- avr910_devcode = 0x75;
- signature = 0x1e 0x96 0x03;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega6490
-#------------------------------------------------------------
-
-# identical to ATmega649
-
-part
- id = "m6490";
- desc = "ATMEGA6490";
- has_jtag = yes;
-# stk500_devcode = 0x85; # no STK500 support, only STK500v2
-# avr910_devcode = 0x?; # try the ATmega169 one:
- avr910_devcode = 0x75;
- signature = 0x1e 0x96 0x04;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega32
-#------------------------------------------------------------
-
-part
- id = "m32";
- desc = "ATMEGA32";
- has_jtag = yes;
- stk500_devcode = 0x91;
- avr910_devcode = 0x72;
- signature = 0x1e 0x95 0x02;
- chip_erase_delay = 9000;
- pagel = 0xd7;
- bs2 = 0xa0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = yes;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x04;
- delay = 10;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 4;
- read = "0 0 1 1 1 0 0 0 0 0 x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega161
-#------------------------------------------------------------
-
-part
- id = "m161";
- desc = "ATMEGA161";
- stk500_devcode = 0x80;
- avr910_devcode = 0x60;
- signature = 0x1e 0x94 0x01;
- chip_erase_delay = 28000;
- pagel = 0xd7;
- bs2 = 0xa0;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 0;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 30;
- programfusepulsewidth = 0;
- programfusepolltimeout = 2;
- programlockpulsewidth = 0;
- programlockpolltimeout = 2;
-
- memory "eeprom"
- size = 512;
- min_write_delay = 3400;
- max_write_delay = 3400;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 5;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 16384;
- page_size = 128;
- num_pages = 128;
- min_write_delay = 14000;
- max_write_delay = 14000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 16;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "fuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 0 0 0 0 x x x x x x x x",
- "x x x x x x x x x o x o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x",
- "x x x x x x x x 1 i 1 i i i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# ATmega8
-#------------------------------------------------------------
-
-part
- id = "m8";
- desc = "ATMEGA8";
- stk500_devcode = 0x70;
- avr910_devcode = 0x76;
- signature = 0x1e 0x93 0x07;
- pagel = 0xd7;
- bs2 = 0xc2;
- chip_erase_delay = 10000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 2;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- resetdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 512;
- page_size = 4;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 20;
- blocksize = 128;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 0 x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 0 x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 10;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 4;
- read = "0 0 1 1 1 0 0 0 0 0 x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-
-#------------------------------------------------------------
-# ATmega8515
-#------------------------------------------------------------
-
-part
- id = "m8515";
- desc = "ATMEGA8515";
- stk500_devcode = 0x63;
- avr910_devcode = 0x3A;
- signature = 0x1e 0x93 0x06;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 512;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 0 x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 0 x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 4;
- read = "0 0 1 1 1 0 0 0 0 0 x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-
-
-#------------------------------------------------------------
-# ATmega8535
-#------------------------------------------------------------
-
-part
- id = "m8535";
- desc = "ATMEGA8535";
- stk500_devcode = 0x64;
- avr910_devcode = 0x69;
- signature = 0x1e 0x93 0x08;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 6;
- togglevtg = 0;
- poweroffdelay = 0;
- resetdelayms = 0;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 512;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- mode = 0x04;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 0 x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 0 x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 2000;
- max_write_delay = 2000;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 4;
- read = "0 0 1 1 1 0 0 0 0 0 x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# ATtiny26
-#------------------------------------------------------------
-
-part
- id = "t26";
- desc = "ATTINY26";
- stk500_devcode = 0x21;
- avr910_devcode = 0x5e;
- signature = 0x1e 0x91 0x09;
- pagel = 0xb3;
- bs2 = 0xb2;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC,
- 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC,
- 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C,
- 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 2;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 128;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 x x x x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 x x x x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- mode = 0x04;
- delay = 10;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 2048;
- page_size = 32;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 x x x x",
- " x x x x x x x x";
-
- mode = 0x21;
- delay = 6;
- blocksize = 16;
- readsize = 256;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x x o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x x x x i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 4;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
-;
-
-
-#------------------------------------------------------------
-# ATtiny261
-#------------------------------------------------------------
-# Close to ATtiny26
-
-part
- id = "t261";
- desc = "ATTINY261";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x00, 0x10;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
-# stk500_devcode = 0x21;
-# avr910_devcode = 0x5e;
- signature = 0x1e 0x91 0x0c;
- pagel = 0xb3;
- bs2 = 0xb2;
- chip_erase_delay = 4000;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC,
- 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC,
- 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C,
- 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 2;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no;
- size = 128;
- page_size = 4;
- num_pages = 32;
- min_write_delay = 4000;
- max_write_delay = 4000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
-
- read = "1 0 1 0 0 0 0 0 x x x x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 x x x x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 2048;
- page_size = 32;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
-
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x x x x a9 a8",
- " a7 a6 a5 a4 x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x x o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x x x x o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
-;
-
-
-#------------------------------------------------------------
-# ATtiny461
-#------------------------------------------------------------
-# Close to ATtiny261
-
-part
- id = "t461";
- desc = "ATTINY461";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x00, 0x10;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
-# stk500_devcode = 0x21;
-# avr910_devcode = 0x5e;
- signature = 0x1e 0x92 0x08;
- pagel = 0xb3;
- bs2 = 0xb2;
- chip_erase_delay = 4000;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC,
- 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC,
- 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C,
- 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 2;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no;
- size = 256;
- page_size = 4;
- num_pages = 64;
- min_write_delay = 4000;
- max_write_delay = 4000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
-
- read = " 1 0 1 0 0 0 0 0 x x x x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0 x x x x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 4096;
- page_size = 64;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
-
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x x o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x x x x o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
-;
-
-
-#------------------------------------------------------------
-# ATtiny861
-#------------------------------------------------------------
-# Close to ATtiny461
-
-part
- id = "t861";
- desc = "ATTINY861";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x00, 0x10;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
-# stk500_devcode = 0x21;
-# avr910_devcode = 0x5e;
- signature = 0x1e 0x93 0x0d;
- pagel = 0xb3;
- bs2 = 0xb2;
- chip_erase_delay = 4000;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 0;
-
- pp_controlstack =
- 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC,
- 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC,
- 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C,
- 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 2;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no;
- size = 512;
- num_pages = 128;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
-
- read = " 1 0 1 0 0 0 0 0 x x x x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0 x x x x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
-
- read_lo = " 0 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 x x x x x x x x",
- "x x x x x x x x x x x x x x o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i",
- "x x x x x x x x x x x x x x x x";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x x x x o";
- min_write_delay = 4500;
- max_write_delay = 4500;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
-;
-
-
-#------------------------------------------------------------
-# ATmega48
-#------------------------------------------------------------
-
-part
- id = "m48";
- desc = "ATMEGA48";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x59;
-# avr910_devcode = 0x;
- signature = 0x1e 0x92 0x05;
- pagel = 0xd7;
- bs2 = 0xc2;
- chip_erase_delay = 45000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- resetdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no;
- page_size = 4;
- size = 256;
- min_write_delay = 3600;
- max_write_delay = 3600;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 5;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 4096;
- page_size = 64;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x x x x o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# ATmega88
-#------------------------------------------------------------
-
-part
- id = "m88";
- desc = "ATMEGA88";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x73;
-# avr910_devcode = 0x;
- signature = 0x1e 0x93 0x0a;
- pagel = 0xd7;
- bs2 = 0xc2;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- resetdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no;
- page_size = 4;
- size = 512;
- min_write_delay = 3600;
- max_write_delay = 3600;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 5;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x x o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega168
-#------------------------------------------------------------
-
-part
- id = "m168";
- desc = "ATMEGA168";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x86;
- # avr910_devcode = 0x;
- signature = 0x1e 0x94 0x06;
- pagel = 0xd7;
- bs2 = 0xc2;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- resetdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no;
- page_size = 4;
- size = 512;
- min_write_delay = 3600;
- max_write_delay = 3600;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 x x x x a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 5;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 16384;
- page_size = 128;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 128;
- readsize = 256;
-
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x x o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-;
-
-#------------------------------------------------------------
-# ATtiny88
-#------------------------------------------------------------
-
-part
- id = "t88";
- desc = "attiny88";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x73;
-# avr910_devcode = 0x;
- signature = 0x1e 0x93 0x11;
- pagel = 0xd7;
- bs2 = 0xc2;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- resetdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no;
- page_size = 4;
- size = 64;
- min_write_delay = 3600;
- max_write_delay = 3600;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 5;
- blocksize = 4;
- readsize = 64;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x x o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega328P
-#------------------------------------------------------------
-
-part
- id = "m328p";
- desc = "ATMEGA328P";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x86;
- # avr910_devcode = 0x;
- signature = 0x1e 0x95 0x0F;
- pagel = 0xd7;
- bs2 = 0xc2;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- resetdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no;
- page_size = 4;
- size = 1024;
- min_write_delay = 3600;
- max_write_delay = 3600;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 5;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 128;
- readsize = 256;
-
- ;
-
- memory "lfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "hfuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
- ;
-
- memory "efuse"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x x x x x x o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
- ;
-
- memory "lock"
- size = 1;
- min_write_delay = 4500;
- max_write_delay = 4500;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-;
-
-#------------------------------------------------------------
-# ATtiny2313
-#------------------------------------------------------------
-
-part
- id = "t2313";
- desc = "ATtiny2313";
- has_debugwire = yes;
- flash_instr = 0xB2, 0x0F, 0x1F;
- eeprom_instr = 0xBB, 0xFE, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBA, 0x0F, 0xB2, 0x0F, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
- stk500_devcode = 0x23;
-## Use the ATtiny26 devcode:
- avr910_devcode = 0x5e;
- signature = 0x1e 0x91 0x0a;
- pagel = 0xD4;
- bs2 = 0xD6;
- reset = io;
- chip_erase_delay = 9000;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0E, 0x1E, 0x2E, 0x3E, 0x2E, 0x3E,
- 0x4E, 0x5E, 0x4E, 0x5E, 0x6E, 0x7E, 0x6E, 0x7E,
- 0x26, 0x36, 0x66, 0x76, 0x2A, 0x3A, 0x6A, 0x7A,
- 0x2E, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 128;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 2048;
- page_size = 32;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
-# The information in the data sheet of April/2004 is wrong, this works:
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
-# The information in the data sheet of April/2004 is wrong, this works:
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
-# The information in the data sheet of April/2004 is wrong, this works:
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-# ATtiny2313 has Signature Bytes: 0x1E 0x91 0x0A.
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-# The Tiny2313 has calibration data for both 4 MHz and 8 MHz.
-# The information in the data sheet of April/2004 is wrong, this works:
-
- memory "calibration"
- size = 2;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90PWM2
-#------------------------------------------------------------
-
-part
- id = "pwm2";
- desc = "AT90PWM2";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x65;
-## avr910_devcode = ?;
- signature = 0x1e 0x93 0x81;
- pagel = 0xD8;
- bs2 = 0xE2;
- reset = io;
- chip_erase_delay = 9000;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 512;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-# AT90PWM2 has Signature Bytes: 0x1E 0x93 0x81.
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90PWM3
-#------------------------------------------------------------
-
-# Completely identical to AT90PWM2 (including the signature!)
-
-part
- id = "pwm3";
- desc = "AT90PWM3";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x65;
-## avr910_devcode = ?;
- signature = 0x1e 0x93 0x81;
- pagel = 0xD8;
- bs2 = 0xE2;
- reset = io;
- chip_erase_delay = 9000;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 512;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
-# AT90PWM2 has Signature Bytes: 0x1E 0x93 0x81.
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90PWM2B
-#------------------------------------------------------------
-# Same as AT90PWM2 but different signature.
-
-part
- id = "pwm2b";
- desc = "AT90PWM2B";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x65;
-## avr910_devcode = ?;
- signature = 0x1e 0x93 0x83;
- pagel = 0xD8;
- bs2 = 0xE2;
- reset = io;
- chip_erase_delay = 9000;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 512;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90PWM3B
-#------------------------------------------------------------
-
-# Completely identical to AT90PWM2B (including the signature!)
-
-part
- id = "pwm3b";
- desc = "AT90PWM3B";
- has_debugwire = yes;
- flash_instr = 0xB6, 0x01, 0x11;
- eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00,
- 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF,
- 0x99, 0xF9, 0xBB, 0xAF;
- stk500_devcode = 0x65;
-## avr910_devcode = ?;
- signature = 0x1e 0x93 0x83;
- pagel = 0xD8;
- bs2 = 0xE2;
- reset = io;
- chip_erase_delay = 9000;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- size = 512;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 64;
- readsize = 256;
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATtiny25
-#------------------------------------------------------------
-
-part
- id = "t25";
- desc = "ATtiny25";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x02, 0x12;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
-## no STK500 devcode in XML file, use the ATtiny45 one
- stk500_devcode = 0x14;
-## avr910_devcode = ?;
-## Try the AT90S2313 devcode:
- avr910_devcode = 0x20;
- signature = 0x1e 0x91 0x08;
- reset = io;
- chip_erase_delay = 4500;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66,
- 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78,
- 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00;
- hventerstabdelay = 100;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 128;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 2048;
- page_size = 32;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-# ATtiny25 has Signature Bytes: 0x1E 0x91 0x08.
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 2;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATtiny45
-#------------------------------------------------------------
-
-part
- id = "t45";
- desc = "ATtiny45";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x02, 0x12;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
- stk500_devcode = 0x14;
-## avr910_devcode = ?;
-## Try the AT90S2313 devcode:
- avr910_devcode = 0x20;
- signature = 0x1e 0x92 0x06;
- reset = io;
- chip_erase_delay = 4500;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66,
- 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78,
- 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 256;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 4096;
- page_size = 64;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-# ATtiny45 has Signature Bytes: 0x1E 0x92 0x08. (Data sheet 2586C-AVR-06/05 (doc2586.pdf) indicates otherwise!)
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 2;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATtiny85
-#------------------------------------------------------------
-
-part
- id = "t85";
- desc = "ATtiny85";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x02, 0x12;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
-## no STK500 devcode in XML file, use the ATtiny45 one
- stk500_devcode = 0x14;
-## avr910_devcode = ?;
-## Try the AT90S2313 devcode:
- avr910_devcode = 0x20;
- signature = 0x1e 0x93 0x0b;
- reset = io;
- chip_erase_delay = 4500;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66,
- 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78,
- 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00;
- hventerstabdelay = 100;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 512;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8",
- "a8 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-# ATtiny85 has Signature Bytes: 0x1E 0x93 0x08.
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 2;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega640
-#------------------------------------------------------------
-# Almost same as ATmega1280, except for different memory sizes
-
-part
- id = "m640";
- desc = "ATMEGA640";
- signature = 0x1e 0x96 0x08;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega1280
-#------------------------------------------------------------
-
-part
- id = "m1280";
- desc = "ATMEGA1280";
- signature = 0x1e 0x97 0x03;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega1281
-#------------------------------------------------------------
-# Identical to ATmega1280
-
-part
- id = "m1281";
- desc = "ATMEGA1281";
- signature = 0x1e 0x97 0x04;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega2560
-#------------------------------------------------------------
-
-part
- id = "m2560";
- desc = "ATMEGA2560";
- signature = 0x1e 0x98 0x01;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 262144;
- page_size = 256;
- num_pages = 1024;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- load_ext_addr = " 0 1 0 0 1 1 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 0 a16",
- " 0 0 0 0 0 0 0 0";
-
- mode = 0x41;
- delay = 10;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega2561
-#------------------------------------------------------------
-
-part
- id = "m2561";
- desc = "ATMEGA2561";
- signature = 0x1e 0x98 0x02;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 262144;
- page_size = 256;
- num_pages = 1024;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- load_ext_addr = " 0 1 0 0 1 1 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 0 a16",
- " 0 0 0 0 0 0 0 0";
-
- mode = 0x41;
- delay = 10;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega128RFA1
-#------------------------------------------------------------
-# Identical to ATmega2561 but half the ROM
-
-part
- id = "m128rfa1";
- desc = "ATMEGA128RFA1";
- signature = 0x1e 0xa7 0x01;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xE2;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATtiny24
-#------------------------------------------------------------
-
-part
- id = "t24";
- desc = "ATtiny24";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x07, 0x17;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
-## no STK500 devcode in XML file, use the ATtiny45 one
- stk500_devcode = 0x14;
-## avr910_devcode = ?;
-## Try the AT90S2313 devcode:
- avr910_devcode = 0x20;
- signature = 0x1e 0x91 0x0b;
- reset = io;
- chip_erase_delay = 4500;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66,
- 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78,
- 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F;
- hventerstabdelay = 100;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 0;
- resetdelayus = 70;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 128;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x",
- "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 2048;
- page_size = 32;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x x a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-# ATtiny24 has Signature Bytes: 0x1E 0x91 0x0B.
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x x x x x x x i i";
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATtiny44
-#------------------------------------------------------------
-
-part
- id = "t44";
- desc = "ATtiny44";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x07, 0x17;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
-## no STK500 devcode in XML file, use the ATtiny45 one
- stk500_devcode = 0x14;
-## avr910_devcode = ?;
-## Try the AT90S2313 devcode:
- avr910_devcode = 0x20;
- signature = 0x1e 0x92 0x07;
- reset = io;
- chip_erase_delay = 4500;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66,
- 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78,
- 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F;
- hventerstabdelay = 100;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 0;
- resetdelayus = 70;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 256;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x",
- "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 4096;
- page_size = 64;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-# ATtiny44 has Signature Bytes: 0x1E 0x92 0x07.
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x x x x x x x i i";
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATtiny84
-#------------------------------------------------------------
-
-part
- id = "t84";
- desc = "ATtiny84";
- has_debugwire = yes;
- flash_instr = 0xB4, 0x07, 0x17;
- eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D,
- 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC,
- 0x99, 0xE1, 0xBB, 0xAC;
-## no STK500 devcode in XML file, use the ATtiny45 one
- stk500_devcode = 0x14;
-## avr910_devcode = ?;
-## Try the AT90S2313 devcode:
- avr910_devcode = 0x20;
- signature = 0x1e 0x93 0x0c;
- reset = io;
- chip_erase_delay = 4500;
-
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- hvsp_controlstack =
- 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66,
- 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78,
- 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10,
- 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F;
- hventerstabdelay = 100;
- hvspcmdexedelay = 0;
- synchcycles = 6;
- latchcycles = 1;
- togglevtg = 1;
- poweroffdelay = 25;
- resetdelayms = 0;
- resetdelayus = 70;
- hvleavestabdelay = 100;
- resetdelay = 25;
- chiperasepolltimeout = 40;
- chiperasetime = 0;
- programfusepolltimeout = 25;
- programlockpolltimeout = 25;
-
- memory "eeprom"
- size = 512;
- paged = no;
- page_size = 4;
- min_write_delay = 4000;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8",
- "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o";
-
- write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8",
- "a8 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x x x x",
- " x a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 4;
- readsize = 256;
- ;
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 64;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 x x x x x",
- " x x x a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 32;
- readsize = 256;
- ;
-# ATtiny84 has Signature Bytes: 0x1E 0x93 0x0C.
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
-
- memory "lock"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x x x x x x x i i";
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x x x x i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega32u4
-#------------------------------------------------------------
-
-part
- id = "m32u4";
- desc = "ATmega32U4";
- signature = 0x1e 0x95 0x87;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90USB646
-#------------------------------------------------------------
-
-part
- id = "usb646";
- desc = "AT90USB646";
- signature = 0x1e 0x96 0x82;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90USB647
-#------------------------------------------------------------
-# identical to AT90USB646
-
-part
- id = "usb647";
- desc = "AT90USB647";
- signature = 0x1e 0x96 0x82;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90USB1286
-#------------------------------------------------------------
-
-part
- id = "usb1286";
- desc = "AT90USB1286";
- signature = 0x1e 0x97 0x82;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90USB1287
-#------------------------------------------------------------
-# identical to AT90USB1286
-
-part
- id = "usb1287";
- desc = "AT90USB1287";
- signature = 0x1e 0x97 0x82;
- has_jtag = yes;
-# stk500_devcode = 0xB2;
-# avr910_devcode = 0x43;
- chip_erase_delay = 9000;
- pagel = 0xD7;
- bs2 = 0xA0;
- reset = dedicated;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "x x x x x x x x x x x x x x x x";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- rampz = 0x3b;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 4096;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " x x x x a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 x x x a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 131072;
- page_size = 256;
- num_pages = 512;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 x x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 256;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x x x x x i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 x x x x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 x x x x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-
-#------------------------------------------------------------
-# AT90USB162
-#------------------------------------------------------------
-
-part
- id = "usb162";
- desc = "AT90USB162";
- has_jtag = no;
- has_debugwire = yes;
- signature = 0x1e 0x94 0x82;
- chip_erase_delay = 9000;
- reset = io;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
- pagel = 0xD7;
- bs2 = 0xC6;
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 512;
- num_pages = 128;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 16384;
- page_size = 128;
- num_pages = 128;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# AT90USB82
-#------------------------------------------------------------
-# Changes against AT90USB162 (beside IDs)
-# memory "flash"
-# size = 8192;
-# num_pages = 64;
-
-part
- id = "usb82";
- desc = "AT90USB82";
- has_jtag = no;
- has_debugwire = yes;
- signature = 0x1e 0x93 0x82;
- chip_erase_delay = 9000;
- reset = io;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "x x x x x x x x x x x x x x x x";
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x",
- "x x x x x x x x x x x x x x x x";
- pagel = 0xD7;
- bs2 = 0xC6;
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 512;
- num_pages = 128;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 0 0 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 20;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 8192;
- page_size = 128;
- num_pages = 64;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0x00;
- readback_p2 = 0x00;
- read_lo = " 0 0 1 0 0 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " x x x x x x x x",
- " x x a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- "a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 x x x x x x",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 6;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "x x x x x x x x i i i i i i i i";
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "x x x x x x x x o o o o o o o o";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x",
- "x x x x x x x x 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "calibration"
- size = 1;
- read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x",
- "x x x x x x a1 a0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega325
-#------------------------------------------------------------
-
-part
- id = "m325";
- desc = "ATMEGA325";
- signature = 0x1e 0x95 0x05;
- has_jtag = yes;
-# stk500_devcode = 0x??; # No STK500v1 support?
-# avr910_devcode = 0x??; # Try the ATmega16 one
- avr910_devcode = 0x74;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 0 0 0 0 0",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 0 0 0 0 0",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega645
-#------------------------------------------------------------
-
-part
- id = "m645";
- desc = "ATMEGA645";
- signature = 0x1E 0x96 0x05;
- has_jtag = yes;
-# stk500_devcode = 0x??; # No STK500v1 support?
-# avr910_devcode = 0x??; # Try the ATmega16 one
- avr910_devcode = 0x74;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 8;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 0 0 0 0 0",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 0 0 0 0 0",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " 0 0 0 0 0 0 0 0";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega3250
-#------------------------------------------------------------
-
-part
- id = "m3250";
- desc = "ATMEGA3250";
- signature = 0x1E 0x95 0x06;
- has_jtag = yes;
-# stk500_devcode = 0x??; # No STK500v1 support?
-# avr910_devcode = 0x??; # Try the ATmega16 one
- avr910_devcode = 0x74;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 4; /* for parallel programming */
- size = 1024;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 0 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 0 0 0 0 a9 a8",
- " a7 a6 a5 a4 a3 a2 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 32768;
- page_size = 128;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 0 0 0 0 0",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 0 0 0 0 0",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " 0 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATmega6450
-#------------------------------------------------------------
-
-part
- id = "m6450";
- desc = "ATMEGA6450";
- signature = 0x1E 0x96 0x06;
- has_jtag = yes;
-# stk500_devcode = 0x??; # No STK500v1 support?
-# avr910_devcode = 0x??; # Try the ATmega16 one
- avr910_devcode = 0x74;
- pagel = 0xd7;
- bs2 = 0xa0;
- chip_erase_delay = 9000;
- pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1",
- "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0";
-
- chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0";
-
- timeout = 200;
- stabdelay = 100;
- cmdexedelay = 25;
- synchloops = 32;
- bytedelay = 0;
- pollindex = 3;
- pollvalue = 0x53;
- predelay = 1;
- postdelay = 1;
- pollmethod = 1;
-
- pp_controlstack =
- 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F,
- 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F,
- 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B,
- 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00;
- hventerstabdelay = 100;
- progmodedelay = 0;
- latchcycles = 5;
- togglevtg = 1;
- poweroffdelay = 15;
- resetdelayms = 1;
- resetdelayus = 0;
- hvleavestabdelay = 15;
- chiperasepulsewidth = 0;
- chiperasepolltimeout = 10;
- programfusepulsewidth = 0;
- programfusepolltimeout = 5;
- programlockpulsewidth = 0;
- programlockpolltimeout = 5;
-
- idr = 0x31;
- spmcr = 0x57;
- allowfullpagebitstream = no;
-
- memory "eeprom"
- paged = no; /* leave this "no" */
- page_size = 8; /* for parallel programming */
- size = 2048;
- min_write_delay = 9000;
- max_write_delay = 9000;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read = " 1 0 1 0 0 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- write = " 1 1 0 0 0 0 0 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_lo = " 1 1 0 0 0 0 0 1",
- " 0 0 0 0 0 0 0 0",
- " 0 0 0 0 0 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 1 1 0 0 0 0 1 0",
- " 0 0 0 0 0 a10 a9 a8",
- " a7 a6 a5 a4 a3 0 0 0",
- " x x x x x x x x";
-
- mode = 0x41;
- delay = 10;
- blocksize = 4;
- readsize = 256;
- ;
-
- memory "flash"
- paged = yes;
- size = 65536;
- page_size = 256;
- num_pages = 256;
- min_write_delay = 4500;
- max_write_delay = 4500;
- readback_p1 = 0xff;
- readback_p2 = 0xff;
- read_lo = " 0 0 1 0 0 0 0 0",
- " a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- read_hi = " 0 0 1 0 1 0 0 0",
- " a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " o o o o o o o o";
-
- loadpage_lo = " 0 1 0 0 0 0 0 0",
- " 0 0 0 0 0 0 0 0",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- loadpage_hi = " 0 1 0 0 1 0 0 0",
- " 0 0 0 0 0 0 0 0",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " i i i i i i i i";
-
- writepage = " 0 1 0 0 1 1 0 0",
- " a15 a14 a13 a12 a11 a10 a9 a8",
- " a7 a6 a5 a4 a3 a2 a1 a0",
- " 0 0 0 0 0 0 0 0";
-
- mode = 0x41;
- delay = 10;
- blocksize = 128;
- readsize = 256;
- ;
-
- memory "lock"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "x x x x x x x x x x o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 1 1 i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "lfuse"
- size = 1;
- read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "hfuse"
- size = 1;
- read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 i i i i i i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "efuse"
- size = 1;
-
- read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
-
- write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0",
- "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i";
- min_write_delay = 9000;
- max_write_delay = 9000;
- ;
-
- memory "signature"
- size = 3;
- read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 a1 a0 o o o o o o o o";
- ;
-
- memory "calibration"
- size = 1;
-
- read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0",
- "0 0 0 0 0 0 0 0 o o o o o o o o";
- ;
- ;
-
-#------------------------------------------------------------
-# ATXMEGA64A1
-#------------------------------------------------------------
-
-part
- id = "x64a1";
- desc = "ATXMEGA64A1";
- signature = 0x1e 0x96 0x4e;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00010000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00001000;
- offset = 0x0080f000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00001000;
- offset = 0x00810000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00011000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA128A1
-#------------------------------------------------------------
-
-part
- id = "x128a1";
- desc = "ATXMEGA128A1";
- signature = 0x1e 0x97 0x4c;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00020000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0081e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00820000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00022000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA128A1REVD
-#------------------------------------------------------------
-
-part
- id = "x128a1d";
- desc = "ATXMEGA128A1REVD";
- signature = 0x1e 0x97 0x41;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00020000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0081e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00820000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00022000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA192A1
-#------------------------------------------------------------
-
-part
- id = "x192a1";
- desc = "ATXMEGA192A1";
- signature = 0x1e 0x97 0x4e;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00030000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0082e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00830000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00032000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA256A1
-#------------------------------------------------------------
-
-part
- id = "x256a1";
- desc = "ATXMEGA256A1";
- signature = 0x1e 0x98 0x46;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x1000;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00040000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0083e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00840000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00042000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA64A3
-#------------------------------------------------------------
-
-part
- id = "x64a3";
- desc = "ATXMEGA64A3";
- signature = 0x1e 0x96 0x42;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00010000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00001000;
- offset = 0x0080f000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00001000;
- offset = 0x00810000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00011000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA128A3
-#------------------------------------------------------------
-
-part
- id = "x128a3";
- desc = "ATXMEGA128A3";
- signature = 0x1e 0x97 0x42;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00020000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0081e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00820000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00022000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA192A3
-#------------------------------------------------------------
-
-part
- id = "x192a3";
- desc = "ATXMEGA192A3";
- signature = 0x1e 0x97 0x44;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00030000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0082e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00830000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00032000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA256A3
-#------------------------------------------------------------
-
-part
- id = "x256a3";
- desc = "ATXMEGA256A3";
- signature = 0x1e 0x98 0x42;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x1000;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00040000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0083e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00840000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00042000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA256A3B
-#------------------------------------------------------------
-
-part
- id = "x256a3b";
- desc = "ATXMEGA256A3B";
- signature = 0x1e 0x98 0x43;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x1000;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00040000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0083e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00840000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00042000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA16A4
-#------------------------------------------------------------
-
-part
- id = "x16a4";
- desc = "ATXMEGA16A4";
- signature = 0x1e 0x94 0x41;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0400;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00004000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00001000;
- offset = 0x00803000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00001000;
- offset = 0x00804000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00005000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA32A4
-#------------------------------------------------------------
-
-part
- id = "x32a4";
- desc = "ATXMEGA32A4";
- signature = 0x1e 0x95 0x41;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0400;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00008000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00001000;
- offset = 0x00807000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00001000;
- offset = 0x00808000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00009000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA64A4
-#------------------------------------------------------------
-
-part
- id = "x64a4";
- desc = "ATXMEGA64A4";
- signature = 0x1e 0x96 0x46;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00010000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00001000;
- offset = 0x0080f000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00001000;
- offset = 0x00810000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00011000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-#------------------------------------------------------------
-# ATXMEGA128A4
-#------------------------------------------------------------
-
-part
- id = "x128a4";
- desc = "ATXMEGA128A4";
- signature = 0x1e 0x97 0x46;
- has_jtag = yes;
- has_pdi = yes;
- nvm_base = 0x01c0;
-
- memory "eeprom"
- size = 0x0800;
- offset = 0x08c0000;
- page_size = 0x20;
- readsize = 0x100;
- ;
-
- memory "application"
- size = 0x00020000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "apptable"
- size = 0x00002000;
- offset = 0x0081e000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "boot"
- size = 0x00002000;
- offset = 0x00820000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "flash"
- size = 0x00022000;
- offset = 0x0800000;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "prodsig"
- size = 0x200;
- offset = 0x8e0200;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "usersig"
- size = 0x200;
- offset = 0x8e0400;
- page_size = 0x100;
- readsize = 0x100;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x1000090;
- ;
-
- memory "fuse0"
- size = 1;
- offset = 0x8f0020;
- ;
-
- memory "fuse1"
- size = 1;
- offset = 0x8f0021;
- ;
-
- memory "fuse2"
- size = 1;
- offset = 0x8f0022;
- ;
-
- memory "fuse4"
- size = 1;
- offset = 0x8f0024;
- ;
-
- memory "fuse5"
- size = 1;
- offset = 0x8f0025;
- ;
-
- memory "lock"
- size = 1;
- offset = 0x8f0027;
- ;
-;
-
-
-#------------------------------------------------------------
-# AVR32UC3A0512
-#------------------------------------------------------------
-
-part
- id = "ucr2";
- desc = "32UC3A0512";
- signature = 0xED 0xC0 0x3F;
- has_jtag = yes;
- is_avr32 = yes;
-
- memory "flash"
- paged = yes;
- page_size = 512; # bytes
- readsize = 512; # bytes
- num_pages = 1024; # could be set dynamicly
- size = 0x00080000; # could be set dynamicly
- offset = 0x80000000;
- ;
-;
-
-#------------------------------------------------------------
-# ATtiny4
-#------------------------------------------------------------
-
-part
- id = "t4";
- desc = "ATtiny4";
- signature = 0x1e 0x8f 0x0a;
- has_tpi = yes;
-
- memory "flash"
- size = 512;
- offset = 0x4000;
- page_size = 16;
- blocksize = 128;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x3fc0;
- ;
-
- memory "fuse"
- size = 1;
- offset = 0x3f40;
- blocksize = 4;
- ;
-
- memory "calibration"
- size = 1;
- offset = 0x3f80;
- ;
-
- memory "lockbits"
- size = 1;
- offset = 0x3f00;
- ;
-;
-
-
-#------------------------------------------------------------
-# ATtiny5
-#------------------------------------------------------------
-
-part
- id = "t5";
- desc = "ATtiny5";
- signature = 0x1e 0x8f 0x09;
- has_tpi = yes;
-
- memory "flash"
- size = 512;
- offset = 0x4000;
- page_size = 16;
- blocksize = 128;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x3fc0;
- ;
-
- memory "fuse"
- size = 1;
- offset = 0x3f40;
- blocksize = 4;
- ;
-
- memory "calibration"
- size = 1;
- offset = 0x3f80;
- ;
-
- memory "lockbits"
- size = 1;
- offset = 0x3f00;
- ;
-;
-
-
-#------------------------------------------------------------
-# ATtiny9
-#------------------------------------------------------------
-
-part
- id = "t8";
- desc = "ATtiny9";
- signature = 0x1e 0x90 0x08;
- has_tpi = yes;
-
- memory "flash"
- size = 1024;
- offset = 0x4000;
- page_size = 16;
- blocksize = 128;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x3fc0;
- ;
-
- memory "fuse"
- size = 1;
- offset = 0x3f40;
- blocksize = 4;
- ;
-
- memory "calibration"
- size = 1;
- offset = 0x3f80;
- ;
-
- memory "lockbits"
- size = 1;
- offset = 0x3f00;
- ;
-;
-
-
-#------------------------------------------------------------
-# ATtiny10
-#------------------------------------------------------------
-
-part
- id = "t10";
- desc = "ATtiny10";
- signature = 0x1e 0x90 0x03;
- has_tpi = yes;
-
- memory "flash"
- size = 1024;
- offset = 0x4000;
- page_size = 16;
- blocksize = 128;
- ;
-
- memory "signature"
- size = 3;
- offset = 0x3fc0;
- ;
-
- memory "fuse"
- size = 1;
- offset = 0x3f40;
- blocksize = 4;
- ;
-
- memory "calibration"
- size = 1;
- offset = 0x3f80;
- ;
-
- memory "lockbits"
- size = 1;
- offset = 0x3f00;
- ;
-;
-
-
diff --git a/buildroot/share/vscode/avrdude_5.10_linux b/buildroot/share/vscode/avrdude_5.10_linux
deleted file mode 100644
index 0b7f3fda43501321935378999e219175e706ef87..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001
literal 1159576
zcmbrn349dA5
zGvl}r@j{>aP&`mPcpeBmg@iyBJUKiNRN_6uatQ(vg#CT1duDesuX{7aMs)m=0C)LYO;sEorn}(-9bq?ui)5^~D*ffEtS}gk0V##88sz1z%j@Y+i^jkH)cZ%+^lzkAZhpE^MnC$KaOtP?
zSMNkhw;m@6o&NL)3~bS#dc9jvkNEum`jf694%gaCB$q8`aYX&8k3-+;s=NAK+qZh+
zRn=8fe6?5A=J&g*-?e?FPwjIx>o?IS+`+>}F#^;ZT~x$#2L2I@${VhjGiC0?uEP#o
z?+LB^^6jOks_q*`Ww+s`kwmcD@oy~t^}6_xZk3}Zq!%2LyS@A3v2y`R
z`14ORekO#o(a@RThtcqv;N23?8Ipj`&IEKOC4lcj56;x?(+S{b1D=I{=ARh=oQclc
z3EJ(Sfd5_z@JA((Lq-DpZ3*yiP5|GKfX;6T@QV}R|C~S$z65k0PJq8D0o;{9ZZ9Oj
zACsWnw-WGwdjfcA0{W>5=#NZ*zcB&*WeMQ#C4i4k&~A1D`3y)v=eh)R1}4DIOhEt3
z1pPfH0sTn{;Fp6=7XF!kE=|DC!wKLYC4d(uXtxRto@xI6nE-w$0i8|>+TET2-a7%E
zqy%zak$|5Q3Ee4K#J@dWTW3E;C5wEK91b{|Us&q+Y%wFLMVCBXM5
zfPazzesh9xxita2F#$ir63FMV1nu?%ohC2R15Cb$*!3EwikJ^pbGzs-bifj>2w
z+^2q)am6D`#!al4R&jULbZ^D9ktKtwr%tIDIpMDA3d^{0cTb)=W!!Y{glXP!<2dRW
z5o@N-v{X;Mo5+@PveT!Q-&^4Yh3Vd!@|s!W$|v1xneLs2Bw#hus-}1=8Ejnf&Esl(
z-f~Oj)S8MZgfgXkat%GFl~0;xsi~MYZR#{ssRF@*f^pNQmrs~dX(^vNWlBXkk*}Os
zQSIf_tL~mMp_)@*t$^+Fd#Pw#<%B8}R8&)yX%!QytEZL&Z(`LH%fzY~RAZu#HR+u?
zk#gRtj92f}YD?Ah3106kOL^t=3UAf)nu>~vmdd*;ywfe^I+bbF#5PL3Rg){GSteIZ
zMuw>1fA9zXr%WA(1}Au{rcSYV%TWrF(=4DewZ>~HudbLd4M@}#gIK`bRG-&U$wh2D%u_j22mF3k_r&n;Wui7#>#!&f$=@lfyapTIpvuY~F-9^n)dlge=SkUH#X?LR*
zhJ2c(YHGQ+nu;b(o$kGB)|3g8Y0#%nX~zjhM5D-LL+b%XV(QEo
zLV4|kag|jV>#Eu4eua0&UA{_4V+wkL+6LCys7>XgHf~%k^ubHxGkNL^^b&dpKFX;I
z8l0f%5RzQ`biE^u)+WH@2~e0yUZ9JJI!z)Yo+fxJYOB1K!JguQgT`Im=juLrvGjGZ
zRPMF$WV}2Myrz#Kjk%wMeM<`amx3q#M?1YU{bys)4u-OhNYlSF{Racd;HmgcEyVxp
zq(Rz4{Qf=|=nsdu-R^E?fnX@Z9|c(w`ttOn0F!Ix`r(F9+u!OKkW
z%^G}?3BF5%*P7sp2Cp~4|I*-#P4IK}@^N2gg7?tit4#2I8hn!pK1_q}Fv0KA;ED-8
zMT57Q;PW(i>ZJDae?)_4n&AJ^;Mpel3Jorr;Q!U&WhVG18hnxozDtAGn&1%)UT=b*
z(BO+r@U!=6ayG#)(%`F1@ZK7HlL>p!+9&jee>LewoVYr`EI|M?Ifzg3HMq
zKg$I7+c-Si1aGAcEPirK@Un9_e!dCr)#wzO;5r@A1fQkhmzv=98obN|Zydw<8E=Bu
zYy3|7^)Byky$Rk(hX?p+FvB%|7MtKpHTp|T@EVQI
zG84R2qqD*UU#8JnWr82PmGjeRf~N|c|4khd7o~7wwsR`ae!!I+zyJ_(8CU~hvXOan?rQz3@
z;MZ&LS`)lgqf=*s>-hC1_+xdvUkxU>PG_+RuG3j!f){H1EHlB=HGWo@;5vStDekpI
z%j-|wewKO=K*P^66Mn16;VVq=QVqV!1aBR}@f%I>tRfEIWP%qC;_xjdc*8)A&Qz}F
zbk?dJjWRwr8Q_;O2>-Rk0Pkaf?=Zk`Ho#jAa7|@dX{*K$oqf|8sQ#nJ9SN?PBvz!y
z7YR;hrLi9^9!YS`G_#`Y$-G}3k)!y4{*z;Xa|!U0d;^?o6o(fY;3+y0JVgVX+SY$c
z4RGW6b(sN9Jn28<4RBposBDq}jsQdKr^W!Mvr_%1)&TFU1M#dgz_lv@thC+$KgWRI
zV1R2!^Q?5S0j|eVs9=c!-o-#?nE`H$Kd&&ryBhFU8Q>WPc%uPsH^4U;;O80OTMY2?
z4e%WXc%}i~YJelU9s5xX@C##5_)!M60nRz*g@p!qPXoSafYX_x{!?mzXX`*b%M9>d
z2Kaab{0aknk^$b^0IxB?uQb4G4e+ZB@Hzv$uK`|ffae(C4F-6w0lwG(zuEv_Vt`*`
zfG;z^uQk9|7~pvZ_$mXO&Z6|6Mg#mh9f;>913cdV-(r9l7~ne$@cssPs{ww!0j?O}
z0}Swk2DsAzZ!^GeFu*OE{U@7uqXC|3fEOCz=?1vV0M9hQ2O8j62KXQYJlg_#l{OgQn(NHqiw$tig=O$11~|VN#T!{>fNQQZD_CKGYg+{d
zUuA$(yk7qi{d-eI*>+^G!y*P7y-Cq6qJKkbvtDe8=3QFkuta-0@LT9!h!o`~QMuY0
z#ZS)*DNindx`pM>r93VDY9q^^MR{8C)fFtCM0r~3)g>%{+>Jaf@oEFhAEG=h?P?v%
z@1Z=Yw_3yUKT)2Ra&%HoAR{ustqhZjqi?yb
z&!T)Q%U?)&S{l_YEPpQLX-QNYS^g}_(^9CeVEH7<(-NpIVfo{Okf)_jZD9FBlqZ*1
ztz-E;l&2+7tzr3}C{IhDI-ccsQl6GPwUp(zQJ$7MwUFgMraUciY7Wb*Q!t&=*o|X``k>$^#JS`pS3YJfzJS`dO5|%$c5P4cE)CQJ6M0r{w
z)H;^mLwQ;n)EbumiSo20sN-3FC*^4=P)k{U8|7&UPzzc9W6G21S94f?J>|*dt640+
zhVo?U)pVABhw^0NRSV0%PWhWDfABaPf69}oS6f;B8OoE1SGTbIBFYb^d?U+K{mKU9
z*$=n3&i7#iJ#yOT*!8+)+p7~`edV;m+wch4t$!z3){;TZZB(v8i|Z(@9L8i6<-8Oa
zYS*ovkbV2L$rjgW*%rA8ltRwH#mJ5Vk>w9i{;Kz`L4G7?H>12LcQcBdE07dJS3PY{
zwv2GCw2G3~(Iysn9Bni16IOP4*BaR7wYeT1YqyByTPj`t0mCh#Q1q8uC~7PciarNt
z(cZ}@JLncx?h@8zOmkazisjqf!n%p0EUtnL-b=)g?L$YhMOc?o4Bqu-SW#Te3NbC&_8YW6T|{v93E@ce=(kYf@SWQ-LmJ
zmod3K`eJfSE_O(R%VifPDWMljZ9qMFE7fq0rivl^u}$$BKLd}~cnzsap?iRhhwE0?
z=-kb&QLd3L>F-e^MCr&HCi4s_$z_Ns&zu=guo)0a8__ntUy7lLZFliqD8q!!?wet
zK>|Nv+aFp=4BJ)$i+=u#s}m^M6~o!ArCc8|KDV_+qiAncU*Gg;eR2N;L)j6xa!CMm
zc})!Q=NdZZcL`6lgdrHfCsg;XsFa>{(1lG=3Rk+NHyk&xwA+!Re0B_-4>>>Cnq+A~
zeOfk^%>;w*(O(Qb%Rr2zD7A>vZe>p`J=9reB?DNFRPw~7T@e1D4Nn_d3D
zt*(|70rKmIicsXPx3hUPXCt~Cy7&q7JnVKb&k0X5Kj@v?kqOLRaLq*k$tDvLb0_g+
z?g=5Kiy^n8mQb*>(kTAUIx>
z!JMa{Q3yN$uc0pAA_QxZ2-{YVbg&^qql}B$Gj%YlGl|u?9%(q9FA-g^k)>Y2@yD{t7qe2%_5(m!Lk^wN
z7o3aoNU$s0?gbR}L{GtbZ(3b{i!U|UC-%!T3Z#W-EbrVO<)sPF-4>G)$@A*_ma6pQn)Y&=Dnb
zoW&AsbV*?$SPe(I?n7>Pgup786TkDjTTofIJwk8`oBxkHXvr3(ANZPKKT5{1_MD>u
z$7_Js3BiY;k$&eAsw)JCkzK+($|5^Ij21gl-x_
zwT{4)>>lhFXx3&zX%@jNP%5ecVAlVHlZ^aqhR~ouJYo>bHrk4AgCcy7QqjNaAPtwd
zGc4_u*eNL2t%4Dgotsdo^qxq(^l$1ETeW
z7s`9?Q!<5RWn`8sF!0o`r=gW7lBfvaVH)^B4xXifuhYQya&WZ<&eFj2t`msdsewCb
zU?+hwL$c7{zpz0ffn_^Utwt$QrqE)dojv@Uxb9;yC4h!fhs?~sr_(UFfi@aya(?-hP$HLvz4
z_OvL%d_k?AsC7uV&34siNi>P-R-rCviqNe_5`%0@X1(%aF~Lwbl!5^op%xSZuM{Hs
zn&a)do_e45=P-IWODN}GwFBrtsYmB9<=S8tbqDiP2piO2COjfcn88MAqY(HElL;lV
zUXqOxnLK|l^0`M@-BzYQw%c@!GGO?fv%rZ}SWw2uJ;I!)iQ+Y#nKvaVLU0z<
zdSC-NTSgC1c0Sr4JcZJ(fL#I8*RP8+eLk4>I~^d5P6e2El~)ezb!?TW`Xd@urw}xh
z7OF&LxVY&;@IPdBLbfsR6S%2d0)U5x6msgx+gi&s-To?Uk}ja-hdCBa#b^QJXfeln
z&43jI7KC#rBa=6KGtHFRGUW!aLer#62k0C;14^rC*6+N#gfagKvxUxAIN=*P;UysK
zk{WdmdV#k3BIo|sO`r^K7wgl5{lJWzb~XrswTYnM38k$@x$9PlYww4YDAj5FdI#_nn8wIw(ZFW+oZbbTp@QN-(Dd%#UTn;
z(Uoz?K@NE-4r$|%MS#HmGt#)4&sLC)Lj6}*s?e$zrA)Xn&G$PO4rP3;!Yn&FXf77=
zSJ8u_;J(`PA>=`voYK39&D>x*TW0d+g}LR-z>XF6tXOIh0>x;;?{sl$k3*+jt4S)N
zG}e(`l=}-4k!-&duA_21QrtOfulm;pGe5I
z)k8?VMmlOdp^1*^VyN0N%@dmAxDR@G&vlR!+kk!Rk-jPQNI#0w9*=a&0~4C5TsaBs
zmtpn2%>&0RRR|o1bo^~6gy0WI6y-uS#)7tG-X+lG8<<{`SI>h`12}R1
zgVvziaitKv3lf27h5AN;R=5O+931=BlNhV4kZ{$Wh%lV!A9S7zw?)3
z3>65D$8Ls7=R44RBY>!N0dIadTsy-oTzUW;XryGPk8nWoVgy!#jkAdP2YKyXd5n2C
zYU`745~?0057gTaBK78i$+0l(1F!)2owpMw!h-LaGCMEU=mr^GnBm|oOsw2}s4@{%
zo`xNvUQ09Ka4hl#z3=d=^U^lrad+kW+)rf8JLcNSVXR<$K6Z
z_|9=b!m0i?sMDY5E7hIL35mgdzW2x}hv+TpwcKTX;acJ+tv|69vVV<5${>CRSW@N-
z77O>se%%+1xZh1He*4%wu#8;#l92wubB*;Sm)}J9NYr
zLhJ}b1#%YxQCpWoX>W4$emYTF>n+MtgkH!tBhJV*M9}61Yi!3)h7v~c5yWYf`Fk0~
zWkAW@yoO40k1F>7sE&r)hqm5gmD2|ER_gF_6XQtfhX&-K6JhcKA7XL>Gr%zIgA7Y|
z7vkcTzd#6{*R>EOtuDVZuF{TBSS4g1&AW;EZq(O%y8|3>F+PtJ83!Qr;0>hen&ZYM
zB^5@aa~8r-uK-WBQ~Zd8o~kbAGCgoLYo%UO+7*bh!GHV~P`(oHR#`7aMmlc-(3C4D
zV89DVwLvHFFS!3M>042Ty%QE3gUxq$`b-F34N18C^W4dZKMkEC
ztQ<5|SUIA`msTtft99ph5(1YouG0R(mLDA&4mL2v!_iO}!xvi$cSdL`>;e)bl=dmt
z{_knIyxlcM2p;BYpMlz%yx2TbmZF-vm#fG_C{z|97~lrWV=)Wda4)kX*LbiU|1ZF3
zeI!tdq=RlrrRW7LMe=>z?$doQ!kZ2})GP`9;@jl%AAmhx$QH^WV9bhOl9wV%KKeC-
ze$8aNFlgT_VZm5f0WsupOcP;|?-N5_GRp`*&{H+e^6V!ptlan9p8
zY|w|oUgS115qUx{Ir@S%Wj^LTELEAsCt&L_0T>D``(!3wLQ%1>HUoCn;vdj3O9+gE
zNx*8xTJo}%YV?+_<1IDtmS!1SdV{xQZ`aZ>xGc&~J*cIPN`KzcD2#&EQW08W&G=X|
z_vy`SK_m=A)r&VXCIH}X4dy*a=YjZ
z%?xhWOfPCCLu;n`v}Q4JY`Vd0TNw>5%2NJd4(I#KV+L#-kHh{PO1gm17f!5=T0H25#
zQoVBKZ>OEZvG3;C=>~i9=kLJUz>T4TpcQ)L;#iA7Q^B)kv*J)l~M@o#vJoIdvb1<
zvvF|lWv$0uoJVpA#|9i|$3wuOUE+K^-7@!difEOXLPVXr5Lg0tws)X#*gM!^1Htkd
z3R0o}yj$JCIiKW0(I(jGXMaQI`m(mu8aSqUCF|o_eT@Xx48pnzYnS8RKJcN`F9DTpY19n2^q-?CZs3`vCzD^QJdI#;u<`cWgur>+5!}Rg
z*j+FLs+CD1&yI?G4Zr9o5MIEb&gd1apB=!tK7$_lg{1NXD1f`qxV&qLp6uMpu~QBG
zyc5_E#0RXz*%2jcE{Yk1TokGga}s%+!~#y@ssF?Tt6W4RLTMR%dTvAsnyLhzZl#Vx
zMflWeL<+5`d{_POiX=;9yK+4&5HEfK#Y%N6!`VnUvhyFjy_?^Tx3`>#gwkH((;kZeQ-Dz38ZzA4HU*Pa`GkDzfTJF@m2++*XCv?K7&DW>4DVet#!Xl`$1&Y4r=4Is
z`@C6bRg~?ksTt{8*D4k*843~zEXrx?f#jQv_Ag*O+IM1}Fz%IQqyo3VBoVzD&|A*w
zk!=9Is&@2Fz^`HSrV+h?ptm`jiR9rJy)vSAFSE_gH+bQ@@#*jS5N6JzTti5^nW1q$
z#E}*lkg(BJ(g~%9#@Bt|t1IX0Vc>zUtyC-4&vKowod{3)?gL-Boa!Nc)+&uZf?j`(
z-Zao_rbt#OuaMJwpdG!gI=zR1gxxG#zMS7*&ieX%jAk{_Ea81^uKI|K;iRl=?_dXA7OQzM*aZC%IP$^u{w-85mtjurbcw5s08u+x^Z(3U;$8p+mq@?f5K~$O2cEYa1gDVglx?qr1k`RQFZl)N>PWt-=X20X2vK!$5R1>r&UsWP
zWIymme14vdR@LpWe$-SJ2p(tAEPL{sj8TuyC|0G`-9TLi)XF~k@oz)!zG7+Xouc%U
z=>O$l=}6f0<4aI6l;&p-=Xa2F)c*OU4$GfHcQ-AU&To4I|Fd)j9729gDB8=y%?T3g8UsxTFFB3H$3ph5Bq!PViz8-%)mo^N&M#Yt
zq(+?1-$FaFTizvX5vP&)#nK=8A~Klt&%YtFxw658UvNhJ^W*rgk)v>MKSDYwN{8e7
zZ~tBj>Xw2h|F5Ump;W4J=sPqL+~uu6Nk5c;o5OGyavNbIxSebK9$uIK?}=gC!zibp
zux*Z(5&{n*FJ0xOn$Z6qc=$J@=WeE$wRUAdU5F+$`Cfn35Ma*hC#T(jrxXd|xQFz6?2`v@sArz+_HY2qk|Dt9x4#ljJgHpR6s2UhM;O->*0
zB3+njTLg!8bygOv`Mwt045C;mrA@|D=w<82A2;%ch{wF_Pzlz_ylzP6Hu`@&dM?{(
zeqbEF5#@^qBN_P@pWo77n4-@^s!TvkF~YVhfWTIz5O3hjbmc-nChQ^M8-3T93kR#p)>7I7EE)NfKjg8KcnlMWc0E8_JoY~3G)g4e+&H|
zfol(a{z2NF_Inmd{i@eVDyYgSdO}MVLng{>l4;DKit^bQfR$81+QV8VmYOq_a%x{5
z(I(166$S^|LZHDei>xT`0pz$Uy!s8ydBM-VchL5|tZnC~Fa&EV^tKfns*K5P#N0F4
zSI7f8ZMd$3a253Nc#^L|gprVEVRSwbrQejUU(=E?DAjX)ibDuI4$7h&T!G%vG2AO8
zP1-2EN^t1_ogDfQYsAJQc6KEMKcGTr7)B#zpTY6B-AP)`e}cvu9EfQ09|84Vg-IBV
ztOCv`3W*{9$58DbpmXtUu98ovSaqY35Kyn+sD6%mB~Uf7D(N~&^)4U-HHx4UsFnfM
z6Dlf$TJ+S>m7jNjDAvBHnulMC_bc5VB$5|a2BW-w{?aI~0GHQdQY4bozYTIKG|TDj
zxSSfmz*#iX2%J3LlLZXbetCQOWD+Wq&l5mBi=&ov)Ms^j
z2)#N8HDV;ydq5YcyZP2WAE=sqp3u>iWQvcfYY?vHs2hQ*iF})mu9Olo6L~U;
z{Ksw4Xan8EJM$b44Ln6h2@k!FE?_+_l&W0MT!
z`_rkcJ6b?lI-m1Dprja4ktOo@c1`Z-8o$e>R~q`B!oIpU-1+r9i`=
zRiTnD|C3N#uJSi<)V+M4e3ET`(a?94mz{a2Q-YW=*@)cOfUKk1Y(OkDAf@OR-H$Am
zPQ`{Lzny8#CgZ-Y5CTMa>KIl7m-Llv&%|KUZM_u$yZk3@LXf^9N|)fW#L#Woe
z1tB5a*$lfvMW+y^Zc2|_#MWQW^~qlNvdyW*{;(BmfDm|w#4cY?_cit_pRpO{c4WHh
zJGyWc!~2CtPDZzEyjyo($Tae8y+<$t5!7H3q2bInSnnr^C;x_g!=(fGx#*6_yEBZs
zL)8u_-efjlB(lhm1rY+Rr73P6Rgvo~%bvzV6}1M~qPw^7{+9e`r2
zf?+|colvan*K?RbT)*DrIAbXwvQrG*Tn5bDnN0jE0OLkxN(_A-LuXj4Io8KI76$32
z7~W{$Dc^h^^P}P390rROsKa@dzaXBSBRP>{%fO=aL+)nfnp~1?-hde5T|k7VWbzM~
zb&(D$FZHA_g%Es}v@4W%4BrW)W35B*;r@(gz{~Na`S{W6aJwC&ck|ubA{7Lu&ApXgK6
z9m^f}NJK08L>;Cu9mL)2%Ex_x7on9TBU0WCq@n1mSU@MGft^fYK?uVitBI8E
zrAXSVe1VH{*wO!s?-86icItWBX2i8hG2LBnY10<5VpIS}q_)c;_B+S9>GFole;ju!
z$R7W1E;o4l@D|dhP{>SnhBJ5zH=_kkTvy`~P`~{)mP22uFPh+}N4Ox63eyXXxeSU<
zqROY?SiPAnK;Cc=$VIH~VU!mC)M-&S=-TC44M~{Tr5MU_Z#QdjLDKodiVN
zu*n?Q4?xskhx#RPmP%tJmVyLT$pq3fKmz;AVfc0SmCIt7vv^~6qANS6aNM$&;~vWj(_)r6_L{NoJ(Jk73)Ds#E6Q1@Vi^@6eobV6en+xY9ko9kh
zMz*t6I!;fwCom=t?4{QLVNbegZ%RDtC<7pOS8yAYzZ)5qbh;BH1ik{8F5K2Z_H9vgIQ
zJvDH=udwhnBs^Ay`)_zhpv96!?`Qar=lK4>H0X@e`0?c5ELe#4m0eIikDLQOI~UWj
zUNr?Fs~zd?(D-OEX1*0?+$GYlI0KKQ!@n3mN$K53l(x8p4>Cqq9$TN%+1Fh6Tb6e{6=Z27d>`RxuyeWx4Q6?y
z&%9TO*%Z)Ile62&YVlb_3kbXBBAu>k8F=?PnG9PtVNv;M$knIg0
z*g(o*FqHbbRgQ%vh*e^MV_sLNNoNc!9gJAi%RrBhf9^INi1s>bGhM6SVzsEXz|`%(
z3nS&e9%!M_$t~8b*zkrf0g}HZ#dWl?qxWp-YZ30H`UPePkRpeaiWVZ_#u}upk8E*-
zyBK@z2W;gw(jKJsq!8RshF`9N1N(O|JUfu1puz#=9FW1*_NjCTl&*d3S3Dcp5p3`g
z^d5P#U%f6xk`^-f7{@@!Pul>+{QTiBhIzp4az;x>@N}U~wFAT=C>xE^E`Oc2q
zU8K!oaI-I4eIK+~|HX1!F4d(~MZW4SfjGhHv|jk=QDgVIRC+vpb@2)7$
zsbEX!%CNUtOul#y)sUTEor6cn{yh0bjWBs0No95f7jl%_Hen=AVkH@m9(@Fh4C{#{
z5gK!C>{76mc=T_`HYg0&U)jFsY+NesfLe@S=>V3=+Dx-GWB=#oXfktrF>
z6#lr1g^R|{0Too2qk_Kw
zbQW{`fxy>?0qgp9!qZ-639}fReLOkAIR68_zG}WnSY^Cp;5oLF_zp+<&@8emQXERpoHvVQ{!&VC(uSxW(2a`9)ALSX4bAaJ+x
zJqAORA7NEuj-9U)?xPdcG0lnxEEv~MvJbem8ru(-i7;A)w6=+S{)C)2pv%fgQfoHJ
z*+Pa_SW?J~%M9%Dey6-jt-_YULr9OD%j%Iq#|m|a1qlBYg|*E`-2<&zKBewN5ASjh
zOv}4XyiUHqF+(gT%bTwJ8(mqqgp>t0tQJwfLJgFKN37dJF^oLTrN&gTV7>1k@!pa`
zo0Ex-OgNw=((fhGUbK9zgI*bQI~*B6hixjP%fBa)*7XSNdT>+)jyqufP*PaiQj7yk
zR++P_5={6YWng7bOBN{jvLY^CpAd0fDg}4Gn{))c0@|YzBk?nH`Wah~4YUyZcI-cBXeJEv7Q)`l|U_Gu3W4u{UXe6lf!A=-L@;Qq_72pXm3pW<`)Dr1H
zN%=2s>w)5?Uy`v=@mPOX&WDl=33bjYF2_Q!AHsv_RbFHR)&!FPmp|{NPIQtZ1WI7o
z=(=C-wjrTwPtxvRmoL`pUW&L_v~DVv+;|7qzaAs@weL4{X=vEpvkj=0p`q%NsmiLg
zqzbz|Qbc)^k|F0;|Dw75#~SFE=CA$2rcNPdBE{n`L+hAn{{)&AJb-~uW%Elc_}+(r
zL0&RYnB_#E|GEyiIvIv(!-~F3xd8Gkkt@)^@5)t>Gx<2_o^rfN>872)WGbNOS}u5@
zE}jKR;z}XEVW^x9F(49>=JI1M2kFnfc*;-E>f+y+=|9oMx0VXXfx!l*5~V{!Df4mi
z@ScryRHbbPtqvmjc!klC&CtOEc#}(c57wk87!?-2i7r!Nw(YTsHWE5HeariMu
zFjru(-B<{7X!x!TP0b+eOl2v0C6*t79I>Mmn|{Nl7fZbI2*4gVQ8^{Fk~WuEzi=0P
zH7^%@INZ38dhL)<$`=3nbKSjm7F#idBe$n&<7b*@Xv?9#agy5D#d-&4Y>e6i62%O}
z%2wu<+6;>uN0HNqBun41BEPYuleO4m1us%eeqPHz*i@ZDf810XX*z+@g#8AcDc-t|K}qjRIhPu@&I!pcsC?U{TJ-9$M=Gb%r+P
zf~&p*dA=Uz#B^p(jL&CsUo?M}db}9ys@*VlWJifz!}&Xv*HL*CLT9_t$Sc~`>=MM`
zFkrJWGcaJ+Lq(WSl}_u}){MQ8t33PP_Un~A*c~d32Di=27v-C4#qvXS19GFj+)(K$
zxW*DR+F<%!+q7aY`Rw
zkInjU+R5Q%n
zOb?y|K3@W`FC;3;a=f#ssX+>VNm|LoDIC;*+&oVL12L=Lx|=8bEAm`_c|D`V{y3UD5{Z
zhp0!G390!g6#^@f#T4rXe2n;;OYkV68NM3{*U=WMwx^j)gvDr?
zCV8Q*0H=*U<|gbCh!>)|Mfr%P;0LJA;mTDkR)$4G%YURzdCX#WZ1CN3MPX6!7a>3g
zlh~dc#*`+p7#mTy)G7q&gP&xu4TFmLz}~peg0Nj5VxmSPEtu{n-D
zLLdc6dDK|EQ{2CuSkjhK%uIIvZDFcs|98xjP^2~Rll*fq5)=lY?>-Q2x$m@7urbFPw%^|N3IY51`=1SxSG*wq@Kcht&NkR^Xl&m%b()A%)!2McO2R9WQb1lcb5naO8
zl}R7YhRAVT9OoI1GbY~cVrg@+v`M*yI2nWH&$Rv^5;JN9JS%Ct8}7G%Z@woq)^Rym
z-^*yr-jl+NkdYVeBrcMtmq0$#sXTTarhUj+v;c?eHYhSqnLKa+
zGjYOhE3B_}T#mwvs1PsXP@xWY0N&{g@ScDl3!RRCnUNKKbvKimmUbd?zme<_!VO>>
zPBsNwYB9p}Vif!?Ex?9%ZQ7q=DvRGGUE}&nr#;2e*L1B%I)cMAY*0?Pq)(NX5F^C?
z6fe(XzVed>dU+nR#jUc;YlED3-!2(B3`od
z-+%Xj`A^G-jTue11s6gWx!UQfa`DP&6s~jY?YcFFZ&C-YsG5~b6YhWV2-FDB!UvH;
z_K&gYDUw=Ux41?zD)`<{BOQipBOUf{;2$1A1QF)}}TOmI9r9Q4Xlb
zPB7GbhDt`26Xp|UHX)u5-DmqFYr3&ThaG!Qcb>5lrYfoQ!2%ka<*Z{9
z9p__cT1nbKeHD-i_#P`DWdi*AAm~_Z>g?MEwt10ea^Sni1pyZ
z2FKh|4t+ue3V%%o^Hi}B@s&Uj?P6_)`&?p&PhyLNnu~_;OQPogh8%DKQIthiQQzGTUG_AK1`iH&Pf1!C6mwdC^EgdNm
zR<>{l9*cg{$<$uoqN@sh4Fp!sfnB6a+V4MM^J#||x>Dc^Qo8;_AykT6$m3fwNkEkYbj@jU}wt&=v&
zwmRS;ZjplZd;m@2xSJ>`zAChsPK`A;(EcJt`5Lwo*lWTzH|o((w53nrixtRX
z6+R@CZSv+;3fWD#N}6^djcn$V&b}qKoN$W
zC~)pY*XCYCG$dy$(x?G^+h<5dSsc%QqI~{^q|synQ}|x%JjfIGIB1^|w!H#W`ibmR
z7QUs;!qfLF#nKUog02mJ4b_50q&4F-v0yr8DzosO1e=Z%5xar;Ls-Bg*VZDWM>ev2
z!`diXW1A2}{NZ~ki_t9ZcugWxP1Be>L3t
z!%)#DSyG|3ZmgBmM_-Qm7FyNU2Y_?8xg{8+-v-sET!-^|t3vM@cnYxE;X6w}r6W;z
z_V8JCak0a2%#=pVg8PoL34QxhxEBGj15dvga}3(bUQ~9i21mHljn88R`y$2m=&0I{
zSG^fkH7n0wFI&qhLMK%#u$eqVdC?#rmRpw7uoOvu2*IC0Rv#E)!Sl!&2FKUiG%)8t
zFHhfBt9PSXgF7^YHrB4AO;&t_=3`Z2v@o~8Wy2BH!7soid|HiB1pJC5aec
zSZBh@e~vIC9E7<&?@yAv^S&o>)Pdzm+hsSrN#mUN*Wn)88B_H2Xp{|$L56ZkAx-oE
zYEi$?x<&2Bl&KC$h&Q%JL}Lej}qJfqpNh`
z?A#M$r{)ao=~zb>3g*evr^CFy_ctH^2p9Z
zhv<RgXHxM-l#R~n&5N`W+d|AKSU8*RYk89oZ}A51Ln2884DE7ttFIt;B+
z@)~%6J+cw$W)S`E59*h*1k~1KVZ1r3qd|%@awW}HL;Ngv8~?aV6?W9aA*JV
zEU(*tqt$mn+6uetmTyh<|JZSRE3Q&Bg$8yMiq|)_B_G@2Z%n2WgM&pue1>x+{#YWa
zyE`>$6zWrbAF}A3+hRGk)qP1*eQM<2%v#6$1IfAAYYGu8AHbvYbE*!TndP14zcI0AHL
zuxoC7UolSBU7zah3d-JBjZoh{x~$j0qm5_a4>vd>>6Hz}D#Ty1nZGl!xBbNbGk3|}
z*NjbZ?x2rm{$k?O$B*}uq<5SD#uSWS6P&b;5FA!?h|2|exsL4s?c|d3O+~ohvAy-C
zOH>=#XL(&dA=ND-GJ9wq@0y<$IMeK^6vcS)UH;T9H#edc~xV
zo&!uDe|;4CcnL7LKDI2=_3>GxjQYs#N6PEin;q=?PEhW9;qgT9AwSX&@=sPFtj>&h
zv$vG;n&9||lYt&d%-rYCr2n5Fp-CasYPI*S?FS+WV+C$Fr5-vNMunW2Z>cC0fL<_RnFUV><(9nAHI>3Mq}6UmYWcre@mDgz)qZYh$Gg1&3_Q8a%Q8^>cb
z0~5V)c+YOr7J`J>m#a5E}!K{8pAwj{UI
z%%aGD&+86Ltt_OC-(U2lUhNVb_@Vd@WF;3BLfuQodqNl6U^|f>HNh`ANu_SN
zWFp%7?q$f$zhS)pM9O>$oEY5}jL5}%*@(;oi4y5Yw$1*LQKrRXU!C$Cs$=QI2S1@a
zY(B{N_VK#z$a+F~