diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index d04725afad95..a7294b818702 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 8 -// 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 (3*60) +// Feedrate for the first approach when double-probing (MULTIPLE_PROBING == 2) +#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) +// Feedrate for the "accurate" probe of each point +#define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2) // (mm/min) /** * Probe Activation Switch diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e406361498c3..ee85e3e03dda 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 diff --git a/Marlin/Version.h b/Marlin/Version.h index 07a14787202a..a524fbe07d62 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-18" /** * The protocol for communication to the host. Protocol indicates communication 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/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/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 7c8289b7de80..3b922dd54ffc 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -392,7 +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 < 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-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/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 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/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c53f7c31d4fe..a7de3fedb7f1 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 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.)" + #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 diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ade37929b247..00da50516875 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-18" #endif /** 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 */ 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/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 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/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 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(); } 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/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; 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/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()); 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]) 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 diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 96295d7db586..217405eae645 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; } @@ -1496,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(); @@ -1526,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); @@ -1566,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) { @@ -1582,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)); @@ -1598,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)); @@ -1665,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; @@ -1779,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(); @@ -1790,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(); @@ -1801,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) @@ -1845,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) @@ -1973,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 @@ -2105,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 @@ -3778,7 +3859,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()); 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 diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 8658191dbe22..0a3584e622c3 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,321 +21,29 @@ */ #pragma once -#include "env_validate.h" - -#if HOTENDS > 3 || E_STEPPERS > 3 - #error "FYSETC S6 supports up to 3 hotends / E steppers." -#endif - -#ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "FYSETC S6" -#endif -#ifndef DEFAULT_MACHINE_NAME - #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#endif - -// Avoid conflict with TIMER_TONE defined in variant -#define STEP_TIMER 10 - -// -// EEPROM Emulation -// -#if NO_EEPROM_SELECTED - #define FLASH_EEPROM_EMULATION - //#define I2C_EEPROM -#endif - -#if ENABLED(FLASH_EEPROM_EMULATION) - // Decrease delays and flash wear by spreading writes across the - // 128 kB sector allocated for EEPROM emulation. - #define FLASH_EEPROM_LEVELING -#elif ENABLED(I2C_EEPROM) - #define MARLIN_EEPROM_SIZE 0x1000 // 4K -#endif - -// -// Servos -// -#ifndef SERVO0_PIN - #define SERVO0_PIN PA3 -#endif - -// -// Limit Switches -// -#define X_MIN_PIN PB14 -#define X_MAX_PIN PA1 -#define Y_MIN_PIN PB13 -#define Y_MAX_PIN PA2 -#define Z_MIN_PIN PA0 -#define Z_MAX_PIN PA3 - -// -// Filament Sensor -// share with X_MAX_PIN -// -#ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA1 -#endif +#define BOARD_INFO_NAME "FYSETC S6" // // Steppers // -#define X_STEP_PIN PE11 -#define X_DIR_PIN PE10 -#ifndef X_ENABLE_PIN - #define X_ENABLE_PIN PE12 -#endif -#define X_CS_PIN PE7 - -#define Y_STEP_PIN PD8 -#define Y_DIR_PIN PB12 -#define Y_ENABLE_PIN PD9 -#define Y_CS_PIN PE15 - -#define Z_STEP_PIN PD14 -#define Z_DIR_PIN PD13 -#define Z_ENABLE_PIN PD15 -#define Z_CS_PIN PD10 - -#define E0_STEP_PIN PD5 -#define E0_DIR_PIN PD6 -#define E0_ENABLE_PIN PD4 -#define E0_CS_PIN PD7 - -#define E1_STEP_PIN PE6 -#define E1_DIR_PIN PC13 -#define E1_ENABLE_PIN PE5 -#define E1_CS_PIN PC14 - -#define E2_STEP_PIN PE2 -#define E2_DIR_PIN PE4 -#define E2_ENABLE_PIN PE3 -#define E2_CS_PIN PC15 +#define X_ENABLE_PIN PE12 #if HAS_TMC_UART // // TMC2208/TMC2209 stepper drivers // - - #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN PE9 - #endif - #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN PE8 - #endif - #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN PE14 - #endif - #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN PE13 - #endif - #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN PD11 - #endif - #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN PD12 - #endif - #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN PD3 - #endif - #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN PA15 - #endif - #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN PC4 - #endif - #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN PC5 - #endif - #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN PE1 - #endif - #ifndef E2_SERIAL_RX_PIN - #define E2_SERIAL_RX_PIN PE0 - #endif -#endif - -// -// Temperature Sensors -// -#define TEMP_0_PIN PC0 -#define TEMP_1_PIN PC1 -#define TEMP_2_PIN PC2 -#ifndef TEMP_BED_PIN - #define TEMP_BED_PIN PC3 -#endif - -// -// Heaters / Fans -// -#ifndef HEATER_0_PIN - #define HEATER_0_PIN PB3 -#endif -#ifndef HEATER_1_PIN - #define HEATER_1_PIN PB4 -#endif -#ifndef HEATER_2_PIN - #define HEATER_2_PIN PB15 -#endif -#ifndef HEATER_BED_PIN - #define HEATER_BED_PIN PC8 -#endif - -#ifndef FAN0_PIN - #define FAN0_PIN PB0 -#endif -#ifndef FAN1_PIN - #define FAN1_PIN PB1 -#endif -#define FAN2_PIN PB2 - -// -// Misc. Functions -// -//#define LED_PIN PB14 -//#define PS_ON_PIN PE11 -//#define KILL_PIN PC5 - -/** - * ------ ------ - * PC9 | 1 2 | PA8 PA6 | 1 2 | PA5 - * PC11 | 3 4 | PD2 PC6 | 3 4 | PA4 - * PC10 5 6 | PC12 PC7 5 6 | PA7 - * PD0 | 7 8 | PD1 PB10 | 7 8 | RESET - * GND | 9 10 | 5V GND | 9 10 | 5V - * ------ ------ - * EXP1 EXP2 - */ -#define EXP1_01_PIN PC9 -#define EXP1_02_PIN PA8 -#define EXP1_03_PIN PC11 -#define EXP1_04_PIN PD2 -#define EXP1_05_PIN PC10 -#define EXP1_06_PIN PC12 -#define EXP1_07_PIN PD0 -#define EXP1_08_PIN PD1 - -#define EXP2_01_PIN PA6 -#define EXP2_02_PIN PA5 -#define EXP2_03_PIN PC6 -#define EXP2_04_PIN PA4 -#define EXP2_05_PIN PC7 -#define EXP2_06_PIN PA7 -#define EXP2_07_PIN PB10 -#define EXP2_08_PIN -1 // RESET - -// -// SPI / SD Card -// -#define SD_SCK_PIN EXP2_02_PIN -#define SD_MISO_PIN EXP2_01_PIN -#define SD_MOSI_PIN EXP2_06_PIN - -#define SDSS EXP2_04_PIN -#define SD_DETECT_PIN EXP2_07_PIN - -// -// LCD / Controller -// - -#if ENABLED(FYSETC_242_OLED_12864) - - #define BTN_EN1 EXP1_01_PIN - #define BTN_EN2 EXP1_08_PIN - #define BTN_ENC EXP1_02_PIN - - #define BEEPER_PIN EXP2_03_PIN - - #define LCD_PINS_DC EXP1_06_PIN - #define LCD_PINS_RS EXP2_05_PIN // LCD_RST - #define DOGLCD_CS EXP1_04_PIN - #define DOGLCD_MOSI EXP1_05_PIN - #define DOGLCD_SCK EXP1_03_PIN - #define DOGLCD_A0 LCD_PINS_DC - #define FORCE_SOFT_SPI - - #define KILL_PIN -1 // NC - #define BOARD_NEOPIXEL_PIN EXP1_07_PIN - -#elif HAS_WIRED_LCD - - #define BEEPER_PIN EXP1_01_PIN - #define BTN_ENC EXP1_02_PIN - - #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_07_PIN - - #define BTN_EN1 EXP1_03_PIN - #define BTN_EN2 EXP1_05_PIN - - #define LCD_PINS_EN EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - - #else - - #define LCD_PINS_RS EXP1_04_PIN - - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - - #define LCD_SDSS EXP2_04_PIN - - #define LCD_PINS_EN EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN - - #if ENABLED(FYSETC_MINI_12864) - // See https://wiki.fysetc.com/Mini12864_Panel - #define DOGLCD_CS EXP1_03_PIN - #define DOGLCD_A0 EXP1_04_PIN - #if ENABLED(FYSETC_GENERIC_12864_1_1) - #define LCD_BACKLIGHT_PIN EXP1_07_PIN - #endif - #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) - #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_06_PIN - #endif - #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_07_PIN - #endif - #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_08_PIN - #endif - #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_06_PIN - #endif - #endif - - #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_06_PIN - #define LCD_PINS_D6 EXP1_07_PIN - #define LCD_PINS_D7 EXP1_08_PIN - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif - #endif - - #endif - -#endif // HAS_WIRED_LCD - -// Alter timing for graphical display -#if IS_U8GLIB_ST7920 - #define BOARD_ST7920_DELAY_1 96 - #define BOARD_ST7920_DELAY_2 48 - #define BOARD_ST7920_DELAY_3 640 -#endif - -#ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PB6 -#endif -#ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PB5 -#endif -#ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PB7 -#endif -#ifndef RGB_LED_W_PIN - #define RGB_LED_W_PIN -1 -#endif + #define X_SERIAL_TX_PIN PE9 + #define X_SERIAL_RX_PIN PE8 + #define Y_SERIAL_TX_PIN PE14 + #define Y_SERIAL_RX_PIN PE13 + #define Z_SERIAL_TX_PIN PD11 + #define Z_SERIAL_RX_PIN PD12 + #define E0_SERIAL_TX_PIN PD3 + #define E0_SERIAL_RX_PIN PA15 + #define E1_SERIAL_TX_PIN PC4 + #define E1_SERIAL_RX_PIN PC5 + #define E2_SERIAL_TX_PIN PE1 + #define E2_SERIAL_RX_PIN PE0 +#endif + +#include "pins_FYSETC_S6_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h index 9d9eb1d37cf9..7d0823046bd0 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -23,15 +23,6 @@ #define BOARD_INFO_NAME "FYSETC S6 2.0" -// -// EEPROM Emulation -// -#if NO_EEPROM_SELECTED - #undef NO_EEPROM_SELECTED - //#define FLASH_EEPROM_EMULATION - #define I2C_EEPROM -#endif - // // Steppers // @@ -60,4 +51,4 @@ #define TMC_SPI_SCK PE12 #endif -#include "pins_FYSETC_S6.h" +#include "pins_FYSETC_S6_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_common.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_common.h new file mode 100644 index 000000000000..b016db655c60 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_common.h @@ -0,0 +1,294 @@ +/** + * 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 + +#include "env_validate.h" + +#if HOTENDS > 3 || E_STEPPERS > 3 + #error "FYSETC S6 supports up to 3 hotends / E steppers." +#endif + +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +#endif + +// Avoid conflict with TIMER_TONE defined in variant +#define STEP_TIMER 10 + +// +// EEPROM Emulation +// +#if NO_EEPROM_SELECTED + #undef NO_EEPROM_SELECTED + //#define FLASH_EEPROM_EMULATION + #define I2C_EEPROM +#endif + +#if ENABLED(FLASH_EEPROM_EMULATION) + // Decrease delays and flash wear by spreading writes across the + // 128 kB sector allocated for EEPROM emulation. + #define FLASH_EEPROM_LEVELING +#elif ENABLED(I2C_EEPROM) + #define MARLIN_EEPROM_SIZE 0x1000 // 4K +#endif + +// +// Servos +// +#ifndef SERVO0_PIN + #define SERVO0_PIN PA3 +#endif + +// +// Limit Switches +// +#define X_MIN_PIN PB14 +#define X_MAX_PIN PA1 +#define Y_MIN_PIN PB13 +#define Y_MAX_PIN PA2 +#define Z_MIN_PIN PA0 +#define Z_MAX_PIN PA3 + +// +// Filament Sensor +// share with X_MAX_PIN +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PA1 +#endif + +// +// Steppers +// +#define X_STEP_PIN PE11 +#define X_DIR_PIN PE10 +//#define X_ENABLE_PIN +#define X_CS_PIN PE7 + +#define Y_STEP_PIN PD8 +#define Y_DIR_PIN PB12 +#define Y_ENABLE_PIN PD9 +#define Y_CS_PIN PE15 + +#define Z_STEP_PIN PD14 +#define Z_DIR_PIN PD13 +#define Z_ENABLE_PIN PD15 +#define Z_CS_PIN PD10 + +#define E0_STEP_PIN PD5 +#define E0_DIR_PIN PD6 +#define E0_ENABLE_PIN PD4 +#define E0_CS_PIN PD7 + +#define E1_STEP_PIN PE6 +#define E1_DIR_PIN PC13 +#define E1_ENABLE_PIN PE5 +#define E1_CS_PIN PC14 + +#define E2_STEP_PIN PE2 +#define E2_DIR_PIN PE4 +#define E2_ENABLE_PIN PE3 +#define E2_CS_PIN PC15 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC0 +#define TEMP_1_PIN PC1 +#define TEMP_2_PIN PC2 +#ifndef TEMP_BED_PIN + #define TEMP_BED_PIN PC3 +#endif + +// +// Heaters / Fans +// +#ifndef HEATER_0_PIN + #define HEATER_0_PIN PB3 +#endif +#ifndef HEATER_1_PIN + #define HEATER_1_PIN PB4 +#endif +#ifndef HEATER_2_PIN + #define HEATER_2_PIN PB15 +#endif +#ifndef HEATER_BED_PIN + #define HEATER_BED_PIN PC8 +#endif + +#ifndef FAN0_PIN + #define FAN0_PIN PB0 +#endif +#ifndef FAN1_PIN + #define FAN1_PIN PB1 +#endif +#define FAN2_PIN PB2 + +// +// Misc. Functions +// +//#define LED_PIN PB14 +//#define PS_ON_PIN PE11 +//#define KILL_PIN PC5 + +/** + * ------ ------ + * PC9 | 1 2 | PA8 PA6 | 1 2 | PA5 + * PC11 | 3 4 | PD2 PC6 | 3 4 | PA4 + * PC10 5 6 | PC12 PC7 5 6 | PA7 + * PD0 | 7 8 | PD1 PB10 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN PC9 +#define EXP1_02_PIN PA8 +#define EXP1_03_PIN PC11 +#define EXP1_04_PIN PD2 +#define EXP1_05_PIN PC10 +#define EXP1_06_PIN PC12 +#define EXP1_07_PIN PD0 +#define EXP1_08_PIN PD1 + +#define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PC6 +#define EXP2_04_PIN PA4 +#define EXP2_05_PIN PC7 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PB10 +#define EXP2_08_PIN -1 // RESET + +// +// SPI / SD Card +// +#define SD_SCK_PIN EXP2_02_PIN +#define SD_MISO_PIN EXP2_01_PIN +#define SD_MOSI_PIN EXP2_06_PIN + +#define SDSS EXP2_04_PIN +#define SD_DETECT_PIN EXP2_07_PIN + +// +// LCD / Controller +// + +#if ENABLED(FYSETC_242_OLED_12864) + + #define BTN_EN1 EXP1_01_PIN + #define BTN_EN2 EXP1_08_PIN + #define BTN_ENC EXP1_02_PIN + + #define BEEPER_PIN EXP2_03_PIN + + #define LCD_PINS_DC EXP1_06_PIN + #define LCD_PINS_RS EXP2_05_PIN // LCD_RST + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_MOSI EXP1_05_PIN + #define DOGLCD_SCK EXP1_03_PIN + #define DOGLCD_A0 LCD_PINS_DC + #define FORCE_SOFT_SPI + + #define KILL_PIN -1 // NC + #define BOARD_NEOPIXEL_PIN EXP1_07_PIN + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN + + #if ENABLED(CR10_STOCKDISPLAY) + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + + #define LCD_PINS_EN EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #else + + #define LCD_PINS_RS EXP1_04_PIN + + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + + #define LCD_SDSS EXP2_04_PIN + + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + + #if ENABLED(FYSETC_MINI_12864) + // See https://wiki.fysetc.com/Mini12864_Panel + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #if ENABLED(FYSETC_GENERIC_12864_1_1) + #define LCD_BACKLIGHT_PIN EXP1_07_PIN + #endif + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_06_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_07_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_08_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_06_PIN + #endif + #endif + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif + + #endif + +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if IS_U8GLIB_ST7920 + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 640 +#endif + +#ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN PB6 +#endif +#ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN PB5 +#endif +#ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN PB7 +#endif +#ifndef RGB_LED_W_PIN + #define RGB_LED_W_PIN -1 +#endif diff --git a/README.md b/README.md index 4d835685d105..160c288aad82 100644 --- a/README.md +++ b/README.md @@ -9,6 +9,7 @@ CI Status GitHub Sponsors
+ Follow marlinfw.org on Bluesky Follow MarlinFirmware on Mastodon

diff --git a/buildroot/bin/build_all_examples b/buildroot/bin/build_all_examples index c2b0007b0c2f..d50937a732ec 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 + ((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 566919abd665..133f3c4cc9e0 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,108 @@ 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" + + set -e + + if [[ $ERR -gt 0 ]]; then -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 ($BUILDINDEX)" >>./.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 + annc "Success" + + # 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/PlatformIO/scripts/preprocessor.py b/buildroot/share/PlatformIO/scripts/preprocessor.py index d409f32f27b7..bda00dfd2717 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 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 diff --git a/buildroot/share/PlatformIO/scripts/schema.py b/buildroot/share/PlatformIO/scripts/schema.py index d5179d43b5ed..d23e5c4716dc 100755 --- a/buildroot/share/PlatformIO/scripts/schema.py +++ b/buildroot/share/PlatformIO/scripts/schema.py @@ -183,18 +183,28 @@ class Parse: # - The line starts with '======' so just skip it. # def use_comment(c, opt, sec, bufref): - if c.startswith(':'): # If the comment starts with : then it has magic JSON - d = c[1:].strip() # Strip the leading : - cbr = c.rindex('}') if d.startswith('{') else c.rindex(']') if d.startswith('[') else 0 + ''' + c - The comment line to parse + opt - Options JSON string to return (if not updated) + sec - Section to return (if not updated) + bufref - The comment buffer to add to + ''' + sc = c.strip() # Strip for special patterns + if sc.startswith(':'): # If the comment starts with : then it has magic JSON + d = sc[1:].strip() # Strip the leading : and spaces + # Look for a JSON container + cbr = sc.rindex('}') if d.startswith('{') else sc.rindex(']') if d.startswith('[') else 0 if cbr: - opt, cmt = c[1:cbr+1].strip(), c[cbr+1:].strip() + opt, cmt = sc[1:cbr+1].strip(), sc[cbr+1:].strip() if cmt != '': bufref.append(cmt) else: - opt = c[1:].strip() - elif c.startswith('@section'): # Start a new section - sec = c[8:].strip() - elif not c.startswith('========'): - bufref.append(c) + opt = sc[1:].strip() # Some literal value not in a JSON container? + else: + m = re.match(r'@section\s*(.+)', sc) # Start a new section? + if m: + sec = m[1] + elif not sc.startswith('========'): + bufref.append(c) # Anything else is part of the comment return opt, sec # For slash comments, capture consecutive slash comments. @@ -225,7 +235,7 @@ def use_comment(c, opt, sec, bufref): # Collect temperature sensors if state == Parse.GET_SENSORS: - sens = re.match(r'^(-?\d+)\s*:\s*(.+)$', cline) + sens = re.match(r'^\s*(-?\d+)\s*:\s*(.+)$', cline) if sens: s2 = sens[2].replace("'", "''") options_json += f"{sens[1]}:'{sens[1]} - {s2}', " @@ -433,6 +443,17 @@ def dump_json(schema:dict, jpath:Path): def dump_yaml(schema:dict, ypath:Path): import yaml + + # Custom representer for all multi-line strings + def str_literal_representer(dumper, data): + if '\n' in data: # Check for multi-line strings + # Add a newline to trigger '|+' + if not data.endswith('\n'): data += '\n' + return dumper.represent_scalar('tag:yaml.org,2002:str', data, style='|') + return dumper.represent_scalar('tag:yaml.org,2002:str', data) + + yaml.add_representer(str, str_literal_representer) + with ypath.open('w', encoding='utf-8') as yfile: yaml.dump(schema, yfile, default_flow_style=False, width=120, indent=2) diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py index 6ae379391096..f47d509baba4 100755 --- a/buildroot/share/PlatformIO/scripts/signature.py +++ b/buildroot/share/PlatformIO/scripts/signature.py @@ -206,15 +206,21 @@ def tryint(key): print(red + "Error: " + str(exc)) conf_schema = None + optorder = ('MOTHERBOARD','SERIAL_PORT','BAUDRATE','USE_WATCHDOG','THERMAL_PROTECTION_HOTENDS','THERMAL_PROTECTION_HYSTERESIS','THERMAL_PROTECTION_PERIOD','BUFSIZE','BLOCK_BUFFER_SIZE','MAX_CMD_SIZE','EXTRUDERS','TEMP_SENSOR_0','TEMP_HYSTERESIS','HEATER_0_MINTEMP','HEATER_0_MAXTEMP','PREHEAT_1_TEMP_HOTEND','BANG_MAX','PIDTEMP','PID_K1','PID_MAX','PID_FUNCTIONAL_RANGE','DEFAULT_KP','DEFAULT_KI','DEFAULT_KD','X_DRIVER_TYPE','Y_DRIVER_TYPE','Z_DRIVER_TYPE','E0_DRIVER_TYPE','X_BED_SIZE','X_MIN_POS','X_MAX_POS','Y_BED_SIZE','Y_MIN_POS','Y_MAX_POS','Z_MIN_POS','Z_MAX_POS','X_HOME_DIR','Y_HOME_DIR','Z_HOME_DIR','X_MIN_ENDSTOP_HIT_STATE','Y_MIN_ENDSTOP_HIT_STATE','Z_MIN_ENDSTOP_HIT_STATE','DEFAULT_AXIS_STEPS_PER_UNIT','AXIS_RELATIVE_MODES','DEFAULT_MAX_FEEDRATE','DEFAULT_MAX_ACCELERATION','HOMING_FEEDRATE_MM_M','HOMING_BUMP_DIVISOR','X_ENABLE_ON','Y_ENABLE_ON','Z_ENABLE_ON','E_ENABLE_ON','INVERT_X_DIR','INVERT_Y_DIR','INVERT_Z_DIR','INVERT_E0_DIR','STEP_STATE_E','STEP_STATE_X','STEP_STATE_Y','STEP_STATE_Z','DISABLE_X','DISABLE_Y','DISABLE_Z','DISABLE_E','PROPORTIONAL_FONT_RATIO','DEFAULT_NOMINAL_FILAMENT_DIA','JUNCTION_DEVIATION_MM','DEFAULT_ACCELERATION','DEFAULT_TRAVEL_ACCELERATION','DEFAULT_RETRACT_ACCELERATION','DEFAULT_MINIMUMFEEDRATE','DEFAULT_MINTRAVELFEEDRATE','MINIMUM_PLANNER_SPEED','MIN_STEPS_PER_SEGMENT','DEFAULT_MINSEGMENTTIME','BED_OVERSHOOT','BUSY_WHILE_HEATING','DEFAULT_EJERK','DEFAULT_KEEPALIVE_INTERVAL','DEFAULT_LEVELING_FADE_HEIGHT','DISABLE_OTHER_EXTRUDERS','DISPLAY_CHARSET_HD44780','EEPROM_BOOT_SILENT','EEPROM_CHITCHAT','ENDSTOPPULLUPS','EXTRUDE_MAXLENGTH','EXTRUDE_MINTEMP','HOST_KEEPALIVE_FEATURE','HOTEND_OVERSHOOT','JD_HANDLE_SMALL_SEGMENTS','LCD_INFO_SCREEN_STYLE','LCD_LANGUAGE','MAX_BED_POWER','MESH_INSET','MIN_SOFTWARE_ENDSTOPS','MAX_SOFTWARE_ENDSTOPS','MIN_SOFTWARE_ENDSTOP_X','MIN_SOFTWARE_ENDSTOP_Y','MIN_SOFTWARE_ENDSTOP_Z','MAX_SOFTWARE_ENDSTOP_X','MAX_SOFTWARE_ENDSTOP_Y','MAX_SOFTWARE_ENDSTOP_Z','PREHEAT_1_FAN_SPEED','PREHEAT_1_LABEL','PREHEAT_1_TEMP_BED','PREVENT_COLD_EXTRUSION','PREVENT_LENGTHY_EXTRUDE','PRINTJOB_TIMER_AUTOSTART','PROBING_MARGIN','SHOW_BOOTSCREEN','SOFT_PWM_SCALE','STRING_CONFIG_H_AUTHOR','TEMP_BED_HYSTERESIS','TEMP_BED_RESIDENCY_TIME','TEMP_BED_WINDOW','TEMP_RESIDENCY_TIME','TEMP_WINDOW','VALIDATE_HOMING_ENDSTOPS','XY_PROBE_FEEDRATE','Z_CLEARANCE_BETWEEN_PROBES','Z_CLEARANCE_DEPLOY_PROBE','Z_CLEARANCE_MULTI_PROBE','ARC_SUPPORT','AUTO_REPORT_TEMPERATURES','AUTOTEMP','AUTOTEMP_OLDWEIGHT','BED_CHECK_INTERVAL','DEFAULT_STEPPER_TIMEOUT_SEC','DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT','DISABLE_IDLE_X','DISABLE_IDLE_Y','DISABLE_IDLE_Z','DISABLE_IDLE_E','E0_AUTO_FAN_PIN','ENCODER_100X_STEPS_PER_SEC','ENCODER_10X_STEPS_PER_SEC','ENCODER_RATE_MULTIPLIER','EXTENDED_CAPABILITIES_REPORT','EXTRUDER_AUTO_FAN_SPEED','EXTRUDER_AUTO_FAN_TEMPERATURE','FANMUX0_PIN','FANMUX1_PIN','FANMUX2_PIN','FASTER_GCODE_PARSER','HOMING_BUMP_MM','MAX_ARC_SEGMENT_MM','MIN_ARC_SEGMENT_MM','MIN_CIRCLE_SEGMENTS','N_ARC_CORRECTION','SERIAL_OVERRUN_PROTECTION','SLOWDOWN','SLOWDOWN_DIVISOR','TEMP_SENSOR_BED','THERMAL_PROTECTION_BED_HYSTERESIS','THERMOCOUPLE_MAX_ERRORS','TX_BUFFER_SIZE','WATCH_BED_TEMP_INCREASE','WATCH_BED_TEMP_PERIOD','WATCH_TEMP_INCREASE','WATCH_TEMP_PERIOD') + + def optsort(x, optorder): + return optorder.index(x) if x in optorder else float('inf') + # - # CONFIG_EXPORT 2 = config.ini, 5 = Config.h + # CONFIG_EXPORT 102 = config.ini, 105 = Config.h # Get sections using the schema class # if extended_dump and config_dump in (2, 5): if not conf_schema: exit(1) # Start with a preferred @section ordering - preorder = ('info','user','machine','extruder','bed temp','fans','stepper drivers','geometry','homing','endstops','probes','lcd','interface','host','reporting') + preorder = ('test','custom','info','machine','eeprom','stepper drivers','multi stepper','idex','extruder','geometry','homing','kinematics','motion','motion control','endstops','filament runout sensors','probe type','probes','bltouch','leveling','temperature','hotend temp','mpctemp','pid temp','mpc temp','bed temp','chamber temp','fans','tool change','advanced pause','calibrate','calibration','media','lcd','lights','caselight','interface','custom main menu','custom config menu','custom buttons','develop','debug matrix','delta','scara','tpara','polar','polargraph','cnc','nozzle park','nozzle clean','gcode','serial','host','filament width','i2c encoders','i2cbus','joystick','multi-material','nanodlp','network','photo','power','psu control','reporting','safety','security','servos','stats','tmc/config','tmc/hybrid','tmc/serial','tmc/smart','tmc/spi','tmc/stallguard','tmc/status','tmc/stealthchop','tmc/tmc26x','units','volumetrics','extras') + sections = { key:{} for key in preorder } # Group options by schema @section @@ -229,7 +235,7 @@ def tryint(key): sections[sect][name] = ddict # - # CONFIG_EXPORT 2 = config.ini + # CONFIG_EXPORT 2 or 102 = config.ini # if config_dump == 2: print(yellow + "Generating config.ini ...") @@ -337,7 +343,9 @@ def tryint(key): sani = re.sub(r'[- ]+', '_', skey).lower() outfile.write(f"\n[config:{sani}]\n") opts = sections[skey] - for name in sorted(opts): + opts_keys = sorted(opts.keys(), key=lambda x: optsort(x, optorder)) + for name in opts_keys: + if name in ignore: continue val = opts[name]['value'] if val == '': val = 'on' #print(f" {name} = {val}") @@ -348,14 +356,16 @@ def tryint(key): # Standard export just dumps config:basic and config:advanced sections for header in real_config: outfile.write(f'\n[{filegrp[header]}]\n') - for name in sorted(real_config[header]): + opts = real_config[header] + opts_keys = sorted(opts.keys(), key=lambda x: optsort(x, optorder)) + for name in opts_keys: if name in ignore: continue - val = real_config[header][name]['value'] + val = opts[name]['value'] if val == '': val = 'on' outfile.write(ini_fmt.format(name.lower(), val) + '\n') # - # CONFIG_EXPORT 5 = Config.h + # CONFIG_EXPORT 5 or 105 = Config.h # if config_dump == 5: print(yellow + "Generating Config-export.h ...") @@ -364,7 +374,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 @@ -382,7 +392,8 @@ def tryint(key): #print(f" skey: {skey}") opts = sections[skey] headed = False - for name in sorted(opts): + opts_keys = sorted(opts.keys(), key=lambda x: optsort(x, optorder)) + for name in opts_keys: if name in ignore: continue val = opts[name]['value'] if not headed: @@ -395,17 +406,19 @@ def tryint(key): # Dump config options in just two sections, by file for header in real_config: out_text += f'\n/**\n * Overrides for {header}\n */\n' - for name in sorted(real_config[header]): + opts = real_config[header] + opts_keys = sorted(opts.keys(), key=lambda x: optsort(x, optorder)) + for name in opts_keys: if name in ignore: continue - val = real_config[header][name]['value'] + val = opts[name]['value'] out_text += define_fmt.format(name, val).strip() + '\n' outfile.write(out_text) # - # CONFIG_EXPORT 3 = schema.json, 4 = schema.yml + # CONFIG_EXPORT 3 = schema.json, 13 = schema_grouped.json, 4 = schema.yml # - if config_dump in (3, 4): + if config_dump in (3, 4, 13): if conf_schema: # @@ -434,7 +447,7 @@ def tryint(key): schema.dump_yaml(conf_schema, build_path / 'schema.yml') # - # Produce a JSON file for CONFIGURATION_EMBEDDING or CONFIG_EXPORT == 1 + # Produce a JSON file for CONFIGURATION_EMBEDDING or CONFIG_EXPORT == 1 or 101 # Skip if an identical JSON file was already present. # if not same_hash and (config_dump == 1 or 'CONFIGURATION_EMBEDDING' in build_defines): @@ -502,5 +515,12 @@ def tryint(key): if __name__ == "__main__": # Build required. From command line just explain usage. - print("Use schema.py to export JSON and YAML from the command-line.") - print("Build Marlin with CONFIG_EXPORT 2 to export 'config.ini'.") + print("*** THIS SCRIPT USED BY common-dependencies.py ***\n\n" + + "Current options for config and schema export:\n" + + " - marlin_config.json : Build Marlin with CONFIG_EXPORT 1 or 101. (Use CONFIGURATION_EMBEDDING for 'mc.zip')\n" + + " - config.ini : Build Marlin with CONFIG_EXPORT 2 or 102.\n" + + " - schema.json : Run 'schema.py json' (CONFIG_EXPORT 3).\n" + + " - schema_grouped.json : Run 'schema.py group' (CONFIG_EXPORT 13).\n" + + " - schema.yml : Run 'schema.py yml' (CONFIG_EXPORT 4).\n" + + " - Config-export.h : Build Marlin with CONFIG_EXPORT 5 or 105.\n" + ) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h index d3e9e08bba0e..2167e2ad9cc4 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h @@ -31,7 +31,7 @@ extern "C" { #define PA0 PIN_A0 // | 0 | A0 | | | | | #define PA1 PIN_A1 // | 1 | A1 | | | | | #define PA2 PIN_A2 // | 2 | A2 | USART2_TX | | | | -#define PA3 PIN_A3 // | 2 | A2, DAC_OUT1** | USART2_RX | | | | +#define PA3 PIN_A3 // | 2 | A3, DAC_OUT1** | USART2_RX | | | | #define PA4 PIN_A4 // | 4 | A4, DAC_OUT2** | | | SPI1_SS | | #define PA5 PIN_A5 // | 5 | A5 | | | SPI1_SCK | | #define PA6 PIN_A6 // | 6 | A6 | | | SPI1_MISO | | 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' 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 0b7f3fda4350..000000000000 Binary files a/buildroot/share/vscode/avrdude_5.10_linux and /dev/null differ diff --git a/buildroot/share/vscode/avrdude_5.10_macOS b/buildroot/share/vscode/avrdude_5.10_macOS deleted file mode 100644 index dbcfc997e4b3..000000000000 Binary files a/buildroot/share/vscode/avrdude_5.10_macOS and /dev/null differ diff --git a/buildroot/share/vscode/avrdude_linux.conf b/buildroot/share/vscode/avrdude_linux.conf deleted file mode 100644 index f43d8da0ea4e..000000000000 --- a/buildroot/share/vscode/avrdude_linux.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 = "/dev/parport0"; -default_serial = "/dev/ttyS0"; - - -# -# 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_macOS.conf b/buildroot/share/vscode/avrdude_macOS.conf deleted file mode 100644 index e2ff7cac984c..000000000000 --- a/buildroot/share/vscode/avrdude_macOS.conf +++ /dev/null @@ -1,15272 +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 = "unknown"; -default_serial = "unknown"; - - -# -# 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; -; - - -# -# 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/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} + + -