From 41d31ca6f97ecb48e2bb623af6f27c0965f9ed68 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 6 Dec 2023 09:50:05 -0500 Subject: [PATCH 001/109] general small fixes/tweaks remove whitespace, add hyphen (-) remove unused `INLINE_USART_IRQ` optimize code --- Marlin/Configuration_adv.h | 3 +-- Marlin/src/HAL/HC32/MarlinSerial.cpp | 2 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 2 +- Marlin/src/module/motion.cpp | 1 - Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h | 2 -- Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp | 2 +- docs/Cutter.md | 16 ++++++++-------- 7 files changed, 12 insertions(+), 16 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 5871c99a215f..54365a7418fb 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3876,7 +3876,7 @@ // @section reporting // Extra options for the M114 "Current Position" report -//#define M114_DETAIL // Use 'M114` for details to check planner calculations +//#define M114_DETAIL // Use 'M114' for details to check planner calculations //#define M114_REALTIME // Real current position based on forward kinematics //#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed. @@ -3888,7 +3888,6 @@ * Spend 28 bytes of SRAM to optimize the G-code parser */ #define FASTER_GCODE_PARSER - #if ENABLED(FASTER_GCODE_PARSER) //#define GCODE_QUOTED_STRINGS // Support for quoted string parameters #endif diff --git a/Marlin/src/HAL/HC32/MarlinSerial.cpp b/Marlin/src/HAL/HC32/MarlinSerial.cpp index 168533f66439..eb203f79d3ba 100644 --- a/Marlin/src/HAL/HC32/MarlinSerial.cpp +++ b/Marlin/src/HAL/HC32/MarlinSerial.cpp @@ -27,7 +27,7 @@ /** * Not every MarlinSerial instance should handle emergency parsing, as - * it would not make sense to parse GCode from TMC responses + * it would not make sense to parse G-Code from TMC responses */ constexpr bool serial_handles_emergency(int port) { return false diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 8d4aa9106bfa..db9419a8a7d6 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -749,7 +749,7 @@ void _drawFeedrate() { DWINUI::drawString(DWIN_FONT_STAT, hmiData.colorIndicator, hmiData.colorBackground, 116 + 4 * STAT_CHR_W + 2, 384, F(" %")); } else { - _value = CEIL(feedrate_mm_s * feedrate_percentage / 100); + _value = CEIL(MMS_SCALED(feedrate_mm_s)); dwinDrawBox(1, hmiData.colorBackground, 116 + 5 * STAT_CHR_W + 2, 384, 20, 20); } DWINUI::drawInt(DWIN_FONT_STAT, hmiData.colorIndicator, hmiData.colorBackground, 3, 116 + 2 * STAT_CHR_W, 384, _value); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 74ba41ccf699..6d374b07d20f 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -77,7 +77,6 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" - #if ENABLED(BD_SENSOR) #include "../feature/bedlevel/bdl/bdl.h" #endif diff --git a/Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h b/Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h index 2f3998b45fcf..c0d9c87baad8 100644 --- a/Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h +++ b/Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h @@ -32,8 +32,6 @@ #define DEFAULT_MACHINE_NAME "Aquila" #endif -#define INLINE_USART_IRQ - #define NO_MAPLE_WARNING // Disable warning when compiling with Maple env #include "../stm32f1/pins_CREALITY_V4.h" diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp index 889b8560aa01..016500d2d68c 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp @@ -201,7 +201,7 @@ uint8_t USB::ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bReque * Keep sending INs and writes data to memory area pointed by 'data' * rcode 0 if no errors. rcode 01-0f is relayed from dispatchPkt(). Rcode f0 means RCVDAVIRQ error, fe = USB xfer timeout */ -uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval /*= 0*/) { +uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval/*=0*/) { EpInfo *pep = nullptr; uint16_t nak_limit = 0; diff --git a/docs/Cutter.md b/docs/Cutter.md index c78b0551a0ac..f044b83948f4 100644 --- a/docs/Cutter.md +++ b/docs/Cutter.md @@ -24,10 +24,10 @@ The following flow charts depict the flow control logic for spindle and laser op │M3 S-Value│ │Dir !same ?│ │Stepper │ │Spindle │ │stop & wait│ │processes │ ┌──┤Clockwise ├──┤ & start ├──┤moves │ - ┌─────┐ │ │ │ │spindle │ │ │ - │GCode│ │ └──────────┘ └───────────┘ └───────────┘ - │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ - └─────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ + ┌──────┐ │ │ │ │spindle │ │ │ + │G-Code│ │ └──────────┘ └───────────┘ └───────────┘ + │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ + └──────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ ├──┤Spindle ├──┤stop & wait├──┤processes │ │ │Counter │ │& start │ │moves │ │ │Clockwise │ │spindle │ │ │ @@ -51,10 +51,10 @@ The following flow charts depict the flow control logic for spindle and laser op │ │ │ │completion │ │ │ │ └──────────┘ └─────────────┘ └───────────┘ │ ┌──────────┐ ┌───────────┐ ┌───────────┐ ┌────────────┐ ┌────────────┐ ┌────────────┐ ┌───────────┐ - ┌─────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ - │GCode│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ - │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ - └─────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ + ┌──────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ + │G-Code│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ + │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ + └──────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ │ └──────────┘ └───────────┘ └───────────┘ └────────────┘ └────────────┘ └────────────┘ └───────────┘ │ ┌──────────┐ ┌───────────┐ ┌────────────────┐ ┌───────────┐ │ │M4 I │ │Gx F-Value │ │Planner │ │Stepper │ From f93e12a77e9adbe6e9e8b96b7386d35fa87b4b85 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 7 Dec 2023 04:54:25 -0500 Subject: [PATCH 002/109] Update Probe Offset dependencies have `HAS_Z_OFFSET_ITEM` defined in one file undef PROBE_OFFSET_ZMIN when ProUI is disabled --- Marlin/src/inc/Conditionals_LCD.h | 6 ++++-- Marlin/src/inc/Conditionals_post.h | 6 +++++- Marlin/src/lcd/e3v2/creality/dwin.cpp | 11 ++--------- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 4 ---- Marlin/src/lcd/e3v2/proui/dwin.cpp | 4 ---- Marlin/src/lcd/e3v2/proui/dwin_defines.h | 4 ---- 6 files changed, 11 insertions(+), 24 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 955b8fd960f4..caef0d5fe0f2 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1466,8 +1466,10 @@ #undef Z_PROBE_ERROR_TOLERANCE #undef MULTIPLE_PROBING #undef EXTRA_PROBING - #undef PROBE_OFFSET_ZMIN - #undef PROBE_OFFSET_ZMAX + #if DISABLED(DWIN_LCD_PROUI) + #undef PROBE_OFFSET_ZMIN + #undef PROBE_OFFSET_ZMAX + #endif #undef PAUSE_BEFORE_DEPLOY_STOW #undef PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED #undef PROBING_HEATERS_OFF diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 09e020dab885..0a8c5a37d84b 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2946,7 +2946,11 @@ /** * Bed Probe dependencies */ -#if ANY(MESH_BED_LEVELING, HAS_BED_PROBE) +#if ANY(BABYSTEPPING, HAS_BED_PROBE) + #define HAS_ZOFFSET_ITEM 1 +#endif + +#if ANY(PROBE_SELECTED, HAS_ZOFFSET_ITEM) #ifndef PROBE_OFFSET_ZMIN #define PROBE_OFFSET_ZMIN -20 #endif diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 274390189107..1422184e6b15 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -33,12 +33,9 @@ //#define USE_STRING_HEADINGS //#define USE_STRING_TITLES -#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) +#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_UBL) #define HAS_ONESTEP_LEVELING 1 -#endif - -#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) - #define HAS_ZOFFSET_ITEM 1 + #include "../../../feature/bedlevel/bedlevel.h" #endif #if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) @@ -68,10 +65,6 @@ #include "../../../feature/host_actions.h" #endif -#if HAS_ONESTEP_LEVELING - #include "../../../feature/bedlevel/bedlevel.h" -#endif - #if HAS_BED_PROBE #include "../../../module/probe.h" #endif diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index be8605e3bba0..06eae4d8e776 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -54,10 +54,6 @@ #include "../../../feature/host_actions.h" #endif -#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) - #define HAS_ZOFFSET_ITEM 1 -#endif - #if HAS_LEVELING #include "../../../feature/bedlevel/bedlevel.h" #endif diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index db9419a8a7d6..9e90ce075ef1 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -68,10 +68,6 @@ #include "../../../feature/host_actions.h" #endif -#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) - #define HAS_ONESTEP_LEVELING 1 -#endif - #if HAS_MESH || (HAS_LEVELING && HAS_ZOFFSET_ITEM) #include "../../../feature/bedlevel/bedlevel.h" #include "bedlevel_tools.h" diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 1b987906ae87..1e7d5a97663b 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -50,10 +50,6 @@ #define JUST_BABYSTEP 1 #endif -#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) - #define HAS_ZOFFSET_ITEM 1 -#endif - #define defColorBackground RGB( 1, 12, 8) #define defColorCursor RGB(20, 49, 31) #define defColorTitleBg RGB( 0, 23, 16) From c10d5dc21761a01ee87e9dfd1984332f6096bfa4 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 7 Dec 2023 05:13:46 -0500 Subject: [PATCH 003/109] edit Conditionals_post.h --- Marlin/src/inc/Conditionals_post.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 0a8c5a37d84b..999eab2f15a4 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2946,11 +2946,11 @@ /** * Bed Probe dependencies */ -#if ANY(BABYSTEPPING, HAS_BED_PROBE) +#if ANY(BABYSTEPPING, PROBE_SELECTED) #define HAS_ZOFFSET_ITEM 1 #endif -#if ANY(PROBE_SELECTED, HAS_ZOFFSET_ITEM) +#if HAS_ZOFFSET_ITEM #ifndef PROBE_OFFSET_ZMIN #define PROBE_OFFSET_ZMIN -20 #endif From 87dbb8e20747d8c1df404371f6c70f0dd109ba2b Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Thu, 7 Dec 2023 12:05:33 -0800 Subject: [PATCH 004/109] Fix Cutter.md, more gcode => G-code --- docs/Cutter.md | 88 +++++++++++++++++++++++++------------------------- 1 file changed, 44 insertions(+), 44 deletions(-) diff --git a/docs/Cutter.md b/docs/Cutter.md index f044b83948f4..623beb21f4d3 100644 --- a/docs/Cutter.md +++ b/docs/Cutter.md @@ -4,7 +4,7 @@ With Marlin version 2.0.9.x or higher, Laser improvements were introduced that e ### Architecture -Laser selectable feature capability is defined through 4 global mode flags within gcode ,laser/spindle, planner and stepper routines. The default mode maintains the standard laser function. G-Codes are received, processed and parsed to determine what mode to set through M3, M4 and M5 commands. When the inline mode parameter set is detected, laser power processing will be driven through the planner and stepper routines. Handling of the initial power values and settings are performed by G-Code parsing and the laser/spindle routines. +Laser selectable feature capability is defined through 4 global mode flags within G-code ,laser/spindle, planner and stepper routines. The default mode maintains the standard laser function. G-Codes are received, processed and parsed to determine what mode to set through M3, M4 and M5 commands. When the inline mode parameter set is detected, laser power processing will be driven through the planner and stepper routines. Handling of the initial power values and settings are performed by G-Code parsing and the laser/spindle routines. Inline power feeds from the block->inline_power variable into the planner's laser.power when in continuous power mode. Further power adjustment will be applied if the laser power trap feature is active otherwise laser.power is used as set in the stepper for the entire block. When laser power trap is active the power levels are step incremented during acceleration and step decremented during deceleration. @@ -20,52 +20,52 @@ The following flow charts depict the flow control logic for spindle and laser op #### Spindle Mode Logic: - ┌──────────┐ ┌───────────┐ ┌───────────┐ - │M3 S-Value│ │Dir !same ?│ │Stepper │ - │Spindle │ │stop & wait│ │processes │ - ┌──┤Clockwise ├──┤ & start ├──┤moves │ - ┌──────┐ │ │ │ │spindle │ │ │ - │G-Code│ │ └──────────┘ └───────────┘ └───────────┘ - │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ - └──────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ - ├──┤Spindle ├──┤stop & wait├──┤processes │ - │ │Counter │ │& start │ │moves │ - │ │Clockwise │ │spindle │ │ │ - │ └──────────┘ └───────────┘ └───────────┘ - │ ┌──────────┐ ┌────────┐ - │ │M5 │ │Wait for│ - │ │Spindle ├──┤move & │ - └──┤Stop │ │disable │ - └──────────┘ └────────┘ - ┌──────────┐ ┌──────────┐ - Sensors─────┤Fault ├──┤Disable │ - └──────────┘ │power │ - └──────────┘ + ┌──────────┐ ┌───────────┐ ┌───────────┐ + │M3 S-Value│ │Dir !same ?│ │Stepper │ + │Spindle │ │stop & wait│ │processes │ + ┌──┤Clockwise ├──┤ & start ├──┤moves │ + ┌──────┐ │ │ │ │spindle │ │ │ + │G-Code│ │ └──────────┘ └───────────┘ └───────────┘ + │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ + └──────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ + ├──┤Spindle ├──┤stop & wait├──┤processes │ + │ │Counter │ │& start │ │moves │ + │ │Clockwise │ │spindle │ │ │ + │ └──────────┘ └───────────┘ └───────────┘ + │ ┌──────────┐ ┌────────┐ + │ │M5 │ │Wait for│ + │ │Spindle ├──┤move & │ + └──┤Stop │ │disable │ + └──────────┘ └────────┘ + ┌──────────┐ ┌──────────┐ + Sensors─────┤Fault ├──┤Disable │ + └──────────┘ │power │ + └──────────┘ #### Laser Mode Logic: - ┌──────────┐ ┌─────────────┐ ┌───────────┐ - │M3,M4,M5 I│ │Set power │ │Stepper │ - ┌──┤Standard ├──┤Immediately &├──┤processes │ - │ │Default │ │wait for move│ │moves │ - │ │ │ │completion │ │ │ - │ └──────────┘ └─────────────┘ └───────────┘ - │ ┌──────────┐ ┌───────────┐ ┌───────────┐ ┌────────────┐ ┌────────────┐ ┌────────────┐ ┌───────────┐ - ┌──────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ - │G-Code│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ - │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ - └──────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ - │ └──────────┘ └───────────┘ └───────────┘ └────────────┘ └────────────┘ └────────────┘ └───────────┘ - │ ┌──────────┐ ┌───────────┐ ┌────────────────┐ ┌───────────┐ - │ │M4 I │ │Gx F-Value │ │Planner │ │Stepper │ - │ │Dynamic │ │set power │ │Calc & set block│ │uses block │ - └──┤Inline ├──┤or use ├──┤block power ├──┤values to │ - │ │ │default │ │using F-Value │ │apply power│ - └──────────┘ └───────────┘ └────────────────┘ └───────────┘ - ┌──────────┐ ┌──────────┐ - Sensors─────┤Fault ├──┤Disable │ - └──────────┘ │Power │ - └──────────┘ + ┌──────────┐ ┌─────────────┐ ┌───────────┐ + │M3,M4,M5 I│ │Set power │ │Stepper │ + ┌──┤Standard ├──┤Immediately &├──┤processes │ + │ │Default │ │wait for move│ │moves │ + │ │ │ │completion │ │ │ + │ └──────────┘ └─────────────┘ └───────────┘ + │ ┌──────────┐ ┌───────────┐ ┌───────────┐ ┌────────────┐ ┌────────────┐ ┌────────────┐ ┌───────────┐ + ┌──────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ + │G-Code│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ + │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ + └──────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ + │ └──────────┘ └───────────┘ └───────────┘ └────────────┘ └────────────┘ └────────────┘ └───────────┘ + │ ┌──────────┐ ┌───────────┐ ┌────────────────┐ ┌───────────┐ + │ │M4 I │ │Gx F-Value │ │Planner │ │Stepper │ + │ │Dynamic │ │set power │ │Calc & set block│ │uses block │ + └──┤Inline ├──┤or use ├──┤block power ├──┤values to │ + │ │ │default │ │using F-Value │ │apply power│ + └──────────┘ └───────────┘ └────────────────┘ └───────────┘ + ┌──────────┐ ┌──────────┐ + Sensors─────┤Fault ├──┤Disable │ + └──────────┘ │Power │ + └──────────┘ From 806a7289f543e6f9bca60047566ab0a1fc5eb1e2 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 8 Dec 2023 02:26:43 -0500 Subject: [PATCH 005/109] omit PROBE_OFFSET_ZMIN/MAX --- Marlin/src/inc/Conditionals_LCD.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index caef0d5fe0f2..26d8262abdb5 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1466,10 +1466,6 @@ #undef Z_PROBE_ERROR_TOLERANCE #undef MULTIPLE_PROBING #undef EXTRA_PROBING - #if DISABLED(DWIN_LCD_PROUI) - #undef PROBE_OFFSET_ZMIN - #undef PROBE_OFFSET_ZMAX - #endif #undef PAUSE_BEFORE_DEPLOY_STOW #undef PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED #undef PROBING_HEATERS_OFF From f2368eeb6cbf860c150286f3c96657bc83150269 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 8 Dec 2023 02:34:27 -0500 Subject: [PATCH 006/109] change to HAS_LEVELING - creality dwin.cpp --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 1422184e6b15..a212e9088427 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -35,7 +35,6 @@ #if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_UBL) #define HAS_ONESTEP_LEVELING 1 - #include "../../../feature/bedlevel/bedlevel.h" #endif #if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) @@ -65,6 +64,10 @@ #include "../../../feature/host_actions.h" #endif +#if HAS_LEVELING + #include "../../../feature/bedlevel/bedlevel.h" +#endif + #if HAS_BED_PROBE #include "../../../module/probe.h" #endif From 82c2457c32c95595c1210c82f853fd28f45d80f0 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 8 Dec 2023 02:55:42 -0500 Subject: [PATCH 007/109] replace HAS_ONESTEP_LEVELING => HAS_AUTOLEVEL "#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_UBL)" is literally HAS_AUTOLEVEL --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 36 +++++++++++------------- Marlin/src/lcd/e3v2/proui/dwin.h | 2 +- Marlin/src/lcd/e3v2/proui/dwin_defines.h | 4 --- 3 files changed, 17 insertions(+), 25 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index a212e9088427..eccffb3d781b 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -33,10 +33,6 @@ //#define USE_STRING_HEADINGS //#define USE_STRING_TITLES -#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_UBL) - #define HAS_ONESTEP_LEVELING 1 -#endif - #if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) #define JUST_BABYSTEP 1 #endif @@ -500,7 +496,7 @@ void drawBackFirst(const bool is_sel=true) { #define PREHEAT_CASE_TOTAL PREHEAT_CASE_SAVE #define ADVSET_CASE_HOMEOFF 1 -#define ADVSET_CASE_PROBEOFF (ADVSET_CASE_HOMEOFF + ENABLED(HAS_ONESTEP_LEVELING)) +#define ADVSET_CASE_PROBEOFF (ADVSET_CASE_HOMEOFF + ENABLED(HAS_AUTOLEVEL)) #define ADVSET_CASE_HEPID (ADVSET_CASE_PROBEOFF + ENABLED(HAS_HOTEND)) #define ADVSET_CASE_BEDPID (ADVSET_CASE_HEPID + ENABLED(HAS_HEATED_BED)) #define ADVSET_CASE_PWRLOSSR (ADVSET_CASE_BEDPID + ENABLED(POWER_LOSS_RECOVERY)) @@ -1135,7 +1131,7 @@ void popupWindowHome(const bool parking/*=false*/) { } } -#if HAS_ONESTEP_LEVELING +#if HAS_AUTOLEVEL void popupWindowLeveling() { clearMainWindow(); @@ -1262,7 +1258,7 @@ void gotoMainMenu() { iconPrint(); iconPrepare(); iconControl(); - TERN(HAS_ONESTEP_LEVELING, iconLeveling, iconStartInfo)(); + TERN(HAS_AUTOLEVEL, iconLeveling, iconStartInfo)(); } void hmiPlanMove(const feedRate_t fr_mm_s) { @@ -2082,7 +2078,7 @@ void hmiMainMenu() { case PAGE_PRINT: iconPrint(); break; case PAGE_PREPARE: iconPrint(); iconPrepare(); break; case PAGE_CONTROL: iconPrepare(); iconControl(); break; - case PAGE_INFO_LEVELING: iconControl(); TERN(HAS_ONESTEP_LEVELING, iconLeveling, iconStartInfo)(); break; + case PAGE_INFO_LEVELING: iconControl(); TERN(HAS_AUTOLEVEL, iconLeveling, iconStartInfo)(); break; } } } @@ -2091,8 +2087,8 @@ void hmiMainMenu() { switch (select_page.now) { case PAGE_PRINT: iconPrint(); iconPrepare(); break; case PAGE_PREPARE: iconPrepare(); iconControl(); break; - case PAGE_CONTROL: iconControl(); TERN(HAS_ONESTEP_LEVELING, iconLeveling, iconStartInfo)(); break; - case PAGE_INFO_LEVELING: TERN(HAS_ONESTEP_LEVELING, iconLeveling, iconStartInfo)(); break; + case PAGE_CONTROL: iconControl(); TERN(HAS_AUTOLEVEL, iconLeveling, iconStartInfo)(); break; + case PAGE_INFO_LEVELING: TERN(HAS_AUTOLEVEL, iconLeveling, iconStartInfo)(); break; } } } @@ -2118,7 +2114,7 @@ void hmiMainMenu() { break; case PAGE_INFO_LEVELING: - #if HAS_ONESTEP_LEVELING + #if HAS_AUTOLEVEL checkkey = ID_Leveling; hmiLeveling(); #else @@ -2419,7 +2415,7 @@ void itemAdvHomeOffsets(const uint8_t row) { drawMoreIcon(row); } -#if HAS_ONESTEP_LEVELING +#if HAS_AUTOLEVEL void itemAdvProbeOffsets(const uint8_t row) { if (false && hmiIsChinese()) { @@ -2510,7 +2506,7 @@ void drawAdvancedSettingsMenu() { if (AVISI(0)) drawBackFirst(select_advset.now == CASE_BACK); if (AVISI(ADVSET_CASE_HOMEOFF)) itemAdvHomeOffsets(ASCROL(ADVSET_CASE_HOMEOFF)); // Set Home Offsets > - #if HAS_ONESTEP_LEVELING + #if HAS_AUTOLEVEL if (AVISI(ADVSET_CASE_PROBEOFF)) itemAdvProbeOffsets(ASCROL(ADVSET_CASE_PROBEOFF)); // Probe Offsets > #endif if (AVISI(ADVSET_CASE_HEPID)) itemAdvHotendPID(ASCROL(ADVSET_CASE_HEPID)); // Nozzle PID @@ -2585,7 +2581,7 @@ void drawHomeOffMenu() { if (select_item.now != CASE_BACK) drawMenuCursor(select_item.now); } -#if HAS_ONESTEP_LEVELING +#if HAS_AUTOLEVEL void drawProbeOffMenu() { clearMainWindow(); @@ -2933,7 +2929,7 @@ void hmiControl() { dwinUpdateLCD(); } -#if HAS_ONESTEP_LEVELING +#if HAS_AUTOLEVEL // Leveling void hmiLeveling() { popupWindowLeveling(); @@ -3562,7 +3558,7 @@ void hmiAdvSet() { break; #endif - #if HAS_ONESTEP_LEVELING + #if HAS_AUTOLEVEL case ADVSET_CASE_PROBEOFF: checkkey = ID_ProbeOff; select_item.reset(); @@ -3659,7 +3655,7 @@ void hmiAdvSet() { #endif // HAS_HOME_OFFSET -#if HAS_ONESTEP_LEVELING +#if HAS_AUTOLEVEL // Probe Offset void hmiProbeOff() { @@ -3713,14 +3709,14 @@ void hmiAdvSet() { void hmiProbeOffX() { hmiProbeOffN(hmiValues.probeOffsScaled.x, probe.offset.x); } void hmiProbeOffY() { hmiProbeOffN(hmiValues.probeOffsScaled.y, probe.offset.y); } -#endif // HAS_ONESTEP_LEVELING +#endif // HAS_AUTOLEVEL // Info void hmiInfo() { EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { - #if HAS_ONESTEP_LEVELING + #if HAS_AUTOLEVEL checkkey = ID_Control; select_control.set(CONTROL_CASE_INFO); drawControlMenu(); @@ -4232,7 +4228,7 @@ void dwinHandleScreen() { case ID_HomeOffY: hmiHomeOffY(); break; case ID_HomeOffZ: hmiHomeOffZ(); break; #endif - #if HAS_ONESTEP_LEVELING + #if HAS_AUTOLEVEL case ID_ProbeOff: hmiProbeOff(); break; case ID_ProbeOffX: hmiProbeOffX(); break; case ID_ProbeOffY: hmiProbeOffY(); break; diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index cf4f9e264353..fef69921f6cb 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -234,7 +234,7 @@ void doCoolDown(); #if ENABLED(NOZZLE_PARK_FEATURE) void parkHead(); #endif -#if HAS_ONESTEP_LEVELING +#if HAS_AUTOLEVEL void trammingwizard(); #endif #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 1e7d5a97663b..3934f557c6af 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -42,10 +42,6 @@ #define DASH_REDRAW 1 #endif -#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_UBL) - #define HAS_ONESTEP_LEVELING 1 -#endif - #if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) #define JUST_BABYSTEP 1 #endif From d2b3bbb14a96bef1cde3f940f79fd5581d3696cb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 8 Dec 2023 02:43:47 -0600 Subject: [PATCH 008/109] Update Conditionals_post.h --- Marlin/src/inc/Conditionals_post.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 999eab2f15a4..cf11664f047d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2946,7 +2946,7 @@ /** * Bed Probe dependencies */ -#if ANY(BABYSTEPPING, PROBE_SELECTED) +#if ANY(BABYSTEPPING, PROBE_SELECTED) && ANY(DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) #define HAS_ZOFFSET_ITEM 1 #endif From 979edb6d2c8d952120a0ad2bcab4e7521f297f9c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 8 Dec 2023 02:54:30 -0600 Subject: [PATCH 009/109] serial tweaks --- Marlin/src/module/printcounter.cpp | 40 ++++++++++++++---------------- 1 file changed, 18 insertions(+), 22 deletions(-) diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index f3d9ec8a9d85..68a73742097e 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -180,23 +180,14 @@ void PrintCounter::saveStats() { TERN_(EXTENSIBLE_UI, ExtUI::onSettingsStored(true)); } -#if HAS_SERVICE_INTERVALS - inline void _service_when(char buffer[], const char * const msg, const uint32_t when) { - SERIAL_ECHOPGM(STR_STATS); - SERIAL_ECHOPGM_P(msg); - SERIAL_ECHOLNPGM(" in ", duration_t(when).toString(buffer)); - } -#endif - void PrintCounter::showStats() { char buffer[22]; - SERIAL_ECHOPGM(STR_STATS); - SERIAL_ECHOLNPGM( - "Prints: ", data.totalPrints, - ", Finished: ", data.finishedPrints, - ", Failed: ", data.totalPrints - data.finishedPrints - - ((isRunning() || isPaused()) ? 1 : 0) // Remove 1 from failures with an active counter + const uint16_t unfail = (isRunning() || isPaused()); // Remove 1 from failures with an active counter + SERIAL_ECHOLN(F(STR_STATS), + F("Prints: "), data.totalPrints, + F(", Finished: "), data.finishedPrints, + F(", Failed: "), data.totalPrints - data.finishedPrints - unfail ); SERIAL_ECHOPGM(STR_STATS); @@ -223,14 +214,19 @@ void PrintCounter::showStats() { SERIAL_EOL(); - #if SERVICE_INTERVAL_1 > 0 - _service_when(buffer, PSTR(SERVICE_NAME_1), data.nextService1); - #endif - #if SERVICE_INTERVAL_2 > 0 - _service_when(buffer, PSTR(SERVICE_NAME_2), data.nextService2); - #endif - #if SERVICE_INTERVAL_3 > 0 - _service_when(buffer, PSTR(SERVICE_NAME_3), data.nextService3); + #if HAS_SERVICE_INTERVALS + auto _service_when = [](char outstr[], PGM_P const msg, const uint32_t when) { + SERIAL_ECHOLN(F(STR_STATS), FPSTR(msg), F(" in "), duration_t(when).toString(outstr)); + }; + #if SERVICE_INTERVAL_1 > 0 + _service_when(buffer, PSTR(SERVICE_NAME_1), data.nextService1); + #endif + #if SERVICE_INTERVAL_2 > 0 + _service_when(buffer, PSTR(SERVICE_NAME_2), data.nextService2); + #endif + #if SERVICE_INTERVAL_3 > 0 + _service_when(buffer, PSTR(SERVICE_NAME_3), data.nextService3); + #endif #endif } From ee55dfe050edefd1b8b83409f2548cf7b7747e89 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 8 Dec 2023 03:59:22 -0500 Subject: [PATCH 010/109] Conditionals_post.h replace HAS_ZOFFSET_ITEM => PROBE_SELECTED --- Marlin/src/inc/Conditionals_post.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index cf11664f047d..5b5cf82cc542 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2950,7 +2950,7 @@ #define HAS_ZOFFSET_ITEM 1 #endif -#if HAS_ZOFFSET_ITEM +#if PROBE_SELECTED #ifndef PROBE_OFFSET_ZMIN #define PROBE_OFFSET_ZMIN -20 #endif From e696be3e0c2913b4c2279e158981f12d377a2f22 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Fri, 8 Dec 2023 14:41:39 -0500 Subject: [PATCH 011/109] Update Conditionals_post.h, include default-no probe/no mesh if one had no Probe and no Mesh, they can still adjust their Z-Offset --- Marlin/src/inc/Conditionals_post.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 5b5cf82cc542..bdde85067b2e 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2950,7 +2950,7 @@ #define HAS_ZOFFSET_ITEM 1 #endif -#if PROBE_SELECTED +#if ANY(PROBE_SELECTED, HAS_ZOFFSET_ITEM) #ifndef PROBE_OFFSET_ZMIN #define PROBE_OFFSET_ZMIN -20 #endif From 4ef2cbfe65483940e57d02cbc4061db4d6ae832a Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 8 Dec 2023 16:33:27 -0500 Subject: [PATCH 012/109] add default-no probe, no mesh to tests --- buildroot/tests/STM32F103RE_creality | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index ad80605e61fa..63d0edd6677b 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -9,6 +9,12 @@ set -e # # Build with configs included in the PR # +use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" +opt_disable DWIN_CREALITY_LCD +opt_enable DWIN_LCD_PROUI +opt_add NO_AUTO_ASSIGN_WARNING +exec_test $1 $2 "Ender-3 v2 - ProUI (Default)" "$3" + use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING BLTOUCH AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING exec_test $1 $2 "Ender-3 v2 - CrealityUI" "$3" From aa7e068a8ce5c2f8205fd040e767322ce2d48d92 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 12 Dec 2023 01:03:19 -0500 Subject: [PATCH 013/109] simplify MPC/PID Plot, dwin.cpp --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 35 +++++------------------------- 1 file changed, 6 insertions(+), 29 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 9e90ce075ef1..9e8732dba055 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1521,48 +1521,25 @@ void dwinLevelingDone() { case MPCTEMP_START: DWINUI::drawCenteredString(hmiData.colorPopupTxt, 100, GET_TEXT_F(MSG_MPC_AUTOTUNE)); DWINUI::drawString(hmiData.colorPopupTxt, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("MPC target: Celsius")); - break; - #endif - #if ANY(PIDTEMP, PIDTEMPBED) - TERN_(PIDTEMP, case PIDTEMP_START:) - TERN_(PIDTEMPBED, case PIDTEMPBED_START:) - DWINUI::drawCenteredString(hmiData.colorPopupTxt, 100, GET_TEXT_F(MSG_PID_AUTOTUNE)); - DWINUI::drawString(hmiData.colorPopupTxt, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("PID target: Celsius")); - break; - #endif - } - - switch (hmiValue.tempControl) { - default: break; - #if ANY(PIDTEMP, MPC_AUTOTUNE) - TERN_(PIDTEMP, case PIDTEMP_START:) - TERN_(MPC_AUTOTUNE, case MPCTEMP_START:) DWINUI::drawCenteredString(hmiData.colorPopupTxt, 120, F("for Nozzle is running.")); - break; - #endif - #if ENABLED(PIDTEMPBED) - case PIDTEMPBED_START: - DWINUI::drawCenteredString(hmiData.colorPopupTxt, 120, F("for BED is running.")); - break; - #endif - } - - switch (hmiValue.tempControl) { - default: break; - #if ENABLED(MPC_AUTOTUNE) - case MPCTEMP_START: _maxtemp = thermalManager.hotend_maxtemp[0]; _target = 200; break; #endif #if ENABLED(PIDTEMP) case PIDTEMP_START: + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 100, GET_TEXT_F(MSG_PID_AUTOTUNE)); + DWINUI::drawString(hmiData.colorPopupTxt, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("PID target: Celsius")); + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 120, F("for Nozzle is running.")); _maxtemp = thermalManager.hotend_maxtemp[0]; _target = hmiData.hotendPidT; break; #endif #if ENABLED(PIDTEMPBED) case PIDTEMPBED_START: + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 100, GET_TEXT_F(MSG_PID_AUTOTUNE)); + DWINUI::drawString(hmiData.colorPopupTxt, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("PID target: Celsius")); + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 120, F("for BED is running.")); _maxtemp = BED_MAXTEMP; _target = hmiData.bedPidT; break; From 8a6bcc25e25d28c1ae73df6af665eefe29e9dd85 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 12 Dec 2023 02:05:42 -0500 Subject: [PATCH 014/109] add HAS_TRAMMING_WIZARD swap to TERN_ in switch case --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 26 +++++++++--------------- Marlin/src/lcd/e3v2/proui/dwin_defines.h | 3 +++ 2 files changed, 13 insertions(+), 16 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 9e8732dba055..7a54723490ac 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1185,13 +1185,9 @@ void drawMainArea() { case ID_MainMenu: drawMainMenu(); break; case ID_PrintProcess: drawPrintProcess(); break; case ID_PrintDone: drawPrintDone(); break; - #if HAS_ESDIAG - case ID_ESDiagProcess: drawEndStopDiag(); break; - #endif + TERN_(HAS_ESDIAG, case ID_ESDiagProcess: drawEndStopDiag(); break;) case ID_Popup: popupDraw(); break; - #if HAS_LOCKSCREEN - case ID_Locked: lockScreen.draw(); break; - #endif + TERN_(HAS_LOCKSCREEN, case ID_Locked: lockScreen.draw(); break;) case ID_Menu: case ID_SetInt: case ID_SetPInt: @@ -1214,9 +1210,7 @@ void hmiWaitForUser() { select_page.reset(); gotoMainMenu(); break; - #if HAS_BED_PROBE - case ID_Leveling: - #endif + TERN_(HAS_BED_PROBE, case ID_Leveling:) default: hmiReturnScreen(); break; @@ -1399,9 +1393,7 @@ void dwinHandleScreen() { case ID_PrintProcess: hmiPrinting(); break; case ID_Popup: hmiPopup(); break; case ID_Leveling: break; - #if HAS_LOCKSCREEN - case ID_Locked: hmiLockScreen(); break; - #endif + TERN_(HAS_LOCKSCREEN, case ID_Locked: hmiLockScreen(); break;) case ID_PrintDone: TERN_(HAS_ESDIAG, case ID_ESDiagProcess:) case ID_WaitResponse: hmiWaitForUser(); break; @@ -2372,7 +2364,7 @@ void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refres #endif - #if HAS_BED_PROBE && HAS_MESH + #if ALL(HAS_BED_PROBE, HAS_MESH, HAS_TRAMMING_WIZARD) void trammingwizard() { if (hmiData.fullManualTramming) { @@ -2442,7 +2434,7 @@ void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refres toggleCheckboxLine(hmiData.fullManualTramming); } - #endif // HAS_BED_PROBE && HAS_MESH + #endif // HAS_BED_PROBE && HAS_MESH && HAS_TRAMMING_WIZARD #endif // LCD_BED_TRAMMING @@ -3008,8 +3000,10 @@ void drawPrepareMenu() { checkkey = ID_Menu; if (SET_MENU(trammingMenu, MSG_BED_TRAMMING, 8)) { BACK_ITEM(drawPrepareMenu); - #if HAS_BED_PROBE && HAS_MESH - MENU_ITEM(ICON_ProbeSet, MSG_TRAMMING_WIZARD, onDrawMenuItem, trammingwizard); + #if ALL(HAS_BED_PROBE, HAS_MESH) + #if HAS_TRAMMING_WIZARD + MENU_ITEM(ICON_ProbeSet, MSG_TRAMMING_WIZARD, onDrawMenuItem, trammingwizard); + #endif EDIT_ITEM(ICON_ProbeSet, MSG_BED_TRAMMING_MANUAL, onDrawChkbMenu, setManualTramming, &hmiData.fullManualTramming); #elif !HAS_BED_PROBE && HAS_ZOFFSET_ITEM MENU_ITEM_F(ICON_MoveZ0, "Home Z and disable", onDrawMenuItem, homeZAndDisable); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 3934f557c6af..0d451c44772e 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -98,6 +98,9 @@ #if ANY(PROUI_PID_TUNE, MPC_AUTOTUNE) && DISABLED(DISABLE_TUNING_GRAPH) #define PROUI_TUNING_GRAPH 1 #endif +#if ALL(LCD_BED_TRAMMING, HAS_BED_PROBE, HAS_MESH) + #define HAS_TRAMMING_WIZARD 1 // Manual mesh not have a probe +#endif #define HAS_GCODE_PREVIEW 1 // Preview G-code model thumbnail #define HAS_CUSTOM_COLORS 1 // Change display colors #define HAS_ESDIAG 1 // View End-stop/Runout switch continuity From 0a6d2b2cff8e17f43a125eba35326f3c3e354537 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 13 Dec 2023 02:49:24 -0500 Subject: [PATCH 015/109] update dwin.cpp spacing --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 91e85ee2842a..7d1c72259087 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -855,24 +855,24 @@ inline uint16_t nr_sd_menu_items() { } void makeNameWithoutExt(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) { - size_t pos = strlen(src); // Index of ending nul + size_t pos = strlen(src); // Index of ending nul // For files, remove the extension // which may be .gcode, .gco, or .g if (!card.flag.filenameIsDir) while (pos && src[pos] != '.') pos--; // Find last '.' (stop at 0) - if (!pos) pos = strlen(src); // pos = 0 ('.' not found) restore pos + if (!pos) pos = strlen(src); // pos = 0 ('.' not found) restore pos - size_t len = pos; // nul or '.' - if (len > maxlen) { // Keep the name short - pos = len = maxlen; // Move nul down - dst[--pos] = '.'; // Insert dots + size_t len = pos; // nul or '.' + if (len > maxlen) { // Keep the name short + pos = len = maxlen; // Move nul down + dst[--pos] = '.'; // Insert dots dst[--pos] = '.'; dst[--pos] = '.'; } - dst[len] = '\0'; // End it + dst[len] = '\0'; // End it // Copy down to 0 while (pos--) dst[pos] = src[pos]; From cff0e4fa7bdfbe523a26d136e200c11182559ffd Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 15 Dec 2023 01:21:15 -0500 Subject: [PATCH 016/109] update DWIN UI - spacing removed COLOR_AQUA - unused, same as COLOR_CYAN --- Marlin/src/lcd/e3v2/jyersui/dwin.h | 1 - Marlin/src/lcd/e3v2/proui/dwin.h | 4 +--- Marlin/src/lcd/e3v2/proui/dwinui.cpp | 19 +++++++++++-------- Marlin/src/lcd/e3v2/proui/dwinui.h | 6 +++--- 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h index 050a4cb39eae..3d51d3ce2e89 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -154,7 +154,6 @@ enum colorID : uint8_t { }; #define Custom_Colors 10 -#define COLOR_AQUA RGB(0x00,0x3F,0x1F) #define COLOR_LIGHT_WHITE 0xBDD7 #define COLOR_GREEN RGB(0x00,0x3F,0x00) #define COLOR_LIGHT_GREEN 0x3460 diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index fef69921f6cb..627f283f0c33 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -154,7 +154,6 @@ typedef struct { bool enablePreview = true; #endif } hmi_data_t; - extern hmi_data_t hmiData; static constexpr size_t eeprom_data_size = sizeof(hmi_data_t); @@ -179,6 +178,7 @@ typedef struct { uint8_t select = 0; // Auxiliary selector variable AxisEnum axis = X_AXIS; // Axis Select } hmi_value_t; +extern hmi_value_t hmiValue; typedef struct { uint8_t language; @@ -188,8 +188,6 @@ typedef struct { bool select_flag:1; // Popup button selected bool home_flag:1; // homing in course } hmi_flag_t; - -extern hmi_value_t hmiValue; extern hmi_flag_t hmiFlag; extern uint8_t checkkey; diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.cpp b/Marlin/src/lcd/e3v2/proui/dwinui.cpp index 23cd1736fdf4..293146fb9153 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwinui.cpp @@ -79,7 +79,7 @@ uint8_t DWINUI::fontWidth(fontid_t fid) { uint8_t DWINUI::fontHeight(fontid_t fid) { switch (fid) { #if DISABLED(TJC_DISPLAY) - case font6x12 : return 12; + case font6x12 : return 12; case font20x40: return 40; case font24x48: return 48; case font28x56: return 56; @@ -112,6 +112,9 @@ void DWINUI::setTextColor(uint16_t fgcolor) { void DWINUI::setBackgroundColor(uint16_t bgcolor) { backColor = bgcolor; } +void DWINUI::setButtonColor(uint16_t alcolor) { + buttonColor = alcolor; +} // Moves cursor to point // x: abscissa of the display @@ -199,7 +202,7 @@ void DWINUI::drawInt(uint8_t bShow, bool signedMode, fontid_t fid, uint16_t colo // value: float value void DWINUI::drawFloat(uint8_t bShow, bool signedMode, fontid_t fid, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { char nstr[10]; - dwinDrawString(bShow, fid, color, bColor, x, y, dtostrf(value, iNum + (signedMode ? 2:1) + fNum, fNum, nstr)); + dwinDrawString(bShow, fid, color, bColor, x, y, dtostrf(value, iNum + (signedMode ? 2 : 1) + fNum, fNum, nstr)); } // ------------------------- Icons -------------------------------// @@ -219,17 +222,17 @@ void DWINUI::ICON_Show(bool BG, uint8_t icon, uint16_t x, uint16_t y) { void DWINUI::drawButton(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, const char * const caption) { dwinDrawRectangle(1, bcolor, x1, y1, x2, y2); - drawCenteredString(0, fontID, color, bcolor, x1, x2, (y2 + y1 - fontHeight())/2, caption); + drawCenteredString(0, fontID, color, bcolor, x1, x2, (y2 + y1 - fontHeight()) / 2, caption); } void DWINUI::drawButton(uint8_t id, uint16_t x, uint16_t y) { switch (id) { - case BTN_Cancel : drawButton(GET_TEXT_F(MSG_BUTTON_CANCEL), x, y); break; - case BTN_Confirm : drawButton(GET_TEXT_F(MSG_BUTTON_CONFIRM), x, y); break; case BTN_Continue: drawButton(GET_TEXT_F(MSG_BUTTON_CONTINUE), x, y); break; - case BTN_Print : drawButton(GET_TEXT_F(MSG_BUTTON_PRINT), x, y); break; - case BTN_Save : drawButton(GET_TEXT_F(MSG_BUTTON_SAVE), x, y); break; - case BTN_Purge : drawButton(GET_TEXT_F(MSG_BUTTON_PURGE), x, y); break; + case BTN_Cancel : drawButton(GET_TEXT_F(MSG_BUTTON_CANCEL), x, y); break; + case BTN_Confirm : drawButton(GET_TEXT_F(MSG_BUTTON_CONFIRM), x, y); break; + case BTN_Print : drawButton(GET_TEXT_F(MSG_BUTTON_PRINT), x, y); break; + case BTN_Save : drawButton(GET_TEXT_F(MSG_BUTTON_SAVE), x, y); break; + case BTN_Purge : drawButton(GET_TEXT_F(MSG_BUTTON_PURGE), x, y); break; default: break; } } diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h index 636b4fbbad72..ab76f96e09a9 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.h +++ b/Marlin/src/lcd/e3v2/proui/dwinui.h @@ -165,9 +165,8 @@ // Extended and default UI Colors #define COLOR_BLACK 0 -#define COLOR_GREEN RGB(0,63,0) -#define COLOR_AQUA RGB(0,63,31) -#define COLOR_BLUE RGB(0,0,31) +#define COLOR_GREEN RGB(0, 63, 0) +#define COLOR_BLUE RGB(0, 0, 31) #define COLOR_LIGHT_WHITE 0xBDD7 #define COLOR_LIGHT_GREEN 0x3460 #define COLOR_CYAN 0x07FF @@ -272,6 +271,7 @@ namespace DWINUI { void setColors(uint16_t fgcolor, uint16_t bgcolor, uint16_t alcolor); void setTextColor(uint16_t fgcolor); void setBackgroundColor(uint16_t bgcolor); + void setButtonColor(uint16_t alcolor); // Moves cursor to point // x: abscissa of the display From cef2bda41622469ee2d7f633cc768de853273393 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 15 Dec 2023 11:34:56 -0500 Subject: [PATCH 017/109] update ProUI, remove unused, use Move/Probe methods --- Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp | 2 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 13 +++++++++---- Marlin/src/lcd/e3v2/proui/dwinui.cpp | 6 ------ Marlin/src/lcd/e3v2/proui/dwinui.h | 13 ------------- 4 files changed, 10 insertions(+), 24 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index 64d145c95dfd..af6ecc29fcd4 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -155,7 +155,7 @@ void BedLevelTools::manualMove(const uint8_t mesh_x, const uint8_t mesh_y, bool } } -// Move / Probe methods. As examples, not yet used. +// Move / Probe methods. void BedLevelTools::moveToXYZ() { goto_mesh_value = true; manualMove(mesh_x, mesh_y, false); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 7d1c72259087..015675e97035 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -3925,13 +3925,16 @@ void drawStepsMenu() { #endif #if ENABLED(PROUI_MESH_EDIT) + bool autoMovToMesh = false; + void setAutoMovToMesh() { toggleCheckboxLine(autoMovToMesh); } void liveEditMesh() { ((MenuItemPtr*)editZValueItem)->value = &bedlevel.z_values[hmiValue.select ? bedLevelTools.mesh_x : menuData.value][hmiValue.select ? menuData.value : bedLevelTools.mesh_y]; editZValueItem->redraw(); } - void applyEditMeshX() { bedLevelTools.mesh_x = menuData.value; } - void applyEditMeshY() { bedLevelTools.mesh_y = menuData.value; } + void applyEditMeshX() { bedLevelTools.mesh_x = menuData.value; if (autoMovToMesh) bedLevelTools.moveToXY(); } + void applyEditMeshY() { bedLevelTools.mesh_y = menuData.value; if (autoMovToMesh) bedLevelTools.moveToXY(); } void resetMesh() { bedLevelTools.meshReset(); LCD_MESSAGE(MSG_MESH_RESET); } void setEditMeshX() { hmiValue.select = 0; setIntOnClick(0, GRID_MAX_POINTS_X - 1, bedLevelTools.mesh_x, applyEditMeshX, liveEditMesh); } void setEditMeshY() { hmiValue.select = 1; setIntOnClick(0, GRID_MAX_POINTS_Y - 1, bedLevelTools.mesh_y, applyEditMeshY, liveEditMesh); } - void setEditZValue() { setPFloatOnClick(Z_OFFSET_MIN, Z_OFFSET_MAX, 3); } + void liveEditMeshZ() { *menuData.floatPtr = menuData.value / POW(10, 2); if (autoMovToMesh) bedLevelTools.moveToZ(); } + void setEditZValue() { setPFloatOnClick(Z_OFFSET_MIN, Z_OFFSET_MAX, 3, nullptr, liveEditMeshZ); if (autoMovToMesh) bedLevelTools.moveToXYZ(); } #endif #endif // HAS_MESH @@ -4012,12 +4015,14 @@ void drawStepsMenu() { if (!leveling_is_valid()) { LCD_MESSAGE(MSG_UBL_MESH_INVALID); return; } set_bed_leveling_enabled(false); checkkey = ID_Menu; - if (SET_MENU(editMeshMenu, MSG_EDIT_MESH, 4)) { + if (SET_MENU(editMeshMenu, MSG_EDIT_MESH, 6)) { bedLevelTools.mesh_x = bedLevelTools.mesh_y = 0; BACK_ITEM(drawMeshSetMenu); + EDIT_ITEM_F(ICON_UBLActive, "Move to position", onDrawChkbMenu, setAutoMovToMesh, &autoMovToMesh); EDIT_ITEM(ICON_MeshEditX, MSG_MESH_X, onDrawPInt8Menu, setEditMeshX, &bedLevelTools.mesh_x); EDIT_ITEM(ICON_MeshEditY, MSG_MESH_Y, onDrawPInt8Menu, setEditMeshY, &bedLevelTools.mesh_y); editZValueItem = EDIT_ITEM(ICON_MeshEditZ, MSG_MESH_EDIT_Z, onDrawPFloat2Menu, setEditZValue, &bedlevel.z_values[bedLevelTools.mesh_x][bedLevelTools.mesh_y]); + OPTCODE(HAS_BED_PROBE, MENU_ITEM_F(ICON_UBLActive, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY)) } updateMenu(editMeshMenu); } diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.cpp b/Marlin/src/lcd/e3v2/proui/dwinui.cpp index 293146fb9153..b17eccf59d53 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwinui.cpp @@ -35,18 +35,15 @@ #include "dwinui.h" xy_int_t DWINUI::cursor = { 0 }; -uint16_t DWINUI::penColor = COLOR_WHITE; uint16_t DWINUI::textColor = defColorText; uint16_t DWINUI::backColor = defColorBackground; uint16_t DWINUI::buttonColor = defColorButton; uint8_t DWINUI::fontID = font8x16; -FSTR_P const DWINUI::author = F(STRING_CONFIG_H_AUTHOR); void (*DWINUI::onTitleDraw)(Title* t) = nullptr; void DWINUI::init() { cursor.reset(); - penColor = COLOR_WHITE; textColor = defColorText; backColor = defColorBackground; buttonColor = defColorButton; @@ -112,9 +109,6 @@ void DWINUI::setTextColor(uint16_t fgcolor) { void DWINUI::setBackgroundColor(uint16_t bgcolor) { backColor = bgcolor; } -void DWINUI::setButtonColor(uint16_t alcolor) { - buttonColor = alcolor; -} // Moves cursor to point // x: abscissa of the display diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h index ab76f96e09a9..682313567d6e 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.h +++ b/Marlin/src/lcd/e3v2/proui/dwinui.h @@ -238,12 +238,10 @@ extern Title title; namespace DWINUI { extern xy_int_t cursor; - extern uint16_t penColor; extern uint16_t textColor; extern uint16_t backColor; extern uint16_t buttonColor; extern fontid_t fontID; - extern FSTR_P const author; extern void (*onTitleDraw)(Title* t); @@ -271,7 +269,6 @@ namespace DWINUI { void setColors(uint16_t fgcolor, uint16_t bgcolor, uint16_t alcolor); void setTextColor(uint16_t fgcolor); void setBackgroundColor(uint16_t bgcolor); - void setButtonColor(uint16_t alcolor); // Moves cursor to point // x: abscissa of the display @@ -287,16 +284,6 @@ namespace DWINUI { void moveBy(int16_t x, int16_t y); void moveBy(xy_int_t point); - // Draw a line from the cursor to xy position - // color: Line segment color - // x/y: End point - inline void lineTo(uint16_t color, uint16_t x, uint16_t y) { - dwinDrawLine(color, cursor.x, cursor.y, x, y); - } - inline void lineTo(uint16_t x, uint16_t y) { - dwinDrawLine(penColor, cursor.x, cursor.y, x, y); - } - // Extend a frame box // v: value to extend inline frame_rect_t extendFrame(frame_rect_t frame, uint8_t v) { From a77fec9cadc2adde10442067f066ee2439c276c0 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 21 Dec 2023 02:58:44 -0500 Subject: [PATCH 018/109] revert #undef, change to _OFFSET_ZMIN|MAX fix JyersUI - MAX|MIN_Z_OFFSET --- Marlin/src/inc/Conditionals_LCD.h | 2 ++ Marlin/src/inc/Conditionals_post.h | 4 ++-- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 13 ++++++------- Marlin/src/lcd/e3v2/proui/dwin.cpp | 5 ++++- 4 files changed, 14 insertions(+), 10 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 26d8262abdb5..955b8fd960f4 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1466,6 +1466,8 @@ #undef Z_PROBE_ERROR_TOLERANCE #undef MULTIPLE_PROBING #undef EXTRA_PROBING + #undef PROBE_OFFSET_ZMIN + #undef PROBE_OFFSET_ZMAX #undef PAUSE_BEFORE_DEPLOY_STOW #undef PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED #undef PROBING_HEATERS_OFF diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index bdde85067b2e..84a843a9547f 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2946,11 +2946,11 @@ /** * Bed Probe dependencies */ -#if ANY(BABYSTEPPING, PROBE_SELECTED) && ANY(DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) +#if ANY(BABYSTEPPING, PROBE_SELECTED) && HAS_DWIN_E3V2 #define HAS_ZOFFSET_ITEM 1 #endif -#if ANY(PROBE_SELECTED, HAS_ZOFFSET_ITEM) +#if PROBE_SELECTED #ifndef PROBE_OFFSET_ZMIN #define PROBE_OFFSET_ZMIN -20 #endif diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 06eae4d8e776..ea7250dbe36b 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -97,13 +97,12 @@ #define MAX_XY_OFFSET 100 -#if HAS_ZOFFSET_ITEM - #define MAX_Z_OFFSET 9.99 - #if HAS_BED_PROBE - #define MIN_Z_OFFSET -9.99 - #else - #define MIN_Z_OFFSET -1 - #endif +#if HAS_ZOFFSET_ITEM && HAS_BED_PROBE + #define MAX_Z_OFFSET 20 + #define MIN_Z_OFFSET -20 +#else + #define MAX_Z_OFFSET 3 + #define MIN_Z_OFFSET -3 #endif #if HAS_HOTEND diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 015675e97035..3e36d59fec26 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -165,6 +165,9 @@ #define BABY_Z_VAR z_offset #endif +#define _OFFSET_ZMIN TERN(HAS_BED_PROBE, PROBE_OFFSET_ZMIN, -20) +#define _OFFSET_ZMAX TERN(HAS_BED_PROBE, PROBE_OFFSET_ZMAX, 20) + // Structs hmi_value_t hmiValue; hmi_flag_t hmiFlag{0}; @@ -2030,7 +2033,7 @@ void autoHome() { queue.inject_P(G28_STR); } #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) babystep.accum = round(planner.settings.axis_steps_per_mm[Z_AXIS] * BABY_Z_VAR); #endif - setPFloatOnClick(PROBE_OFFSET_ZMIN, PROBE_OFFSET_ZMAX, 2, applyZOffset, liveZOffset); + setPFloatOnClick(_OFFSET_ZMIN, _OFFSET_ZMAX, 2, applyZOffset, liveZOffset); } void setMoveZto0() { From 590d66f67d2744f518e74976bfe89a2a10da7d0c Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 21 Dec 2023 03:11:37 -0500 Subject: [PATCH 019/109] tweak spacing --- Marlin/src/lcd/e3v2/common/dwin_color.h | 6 +++--- Marlin/src/lcd/e3v2/jyersui/dwin.h | 2 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 6 +++--- Marlin/src/lcd/e3v2/proui/dwin_defines.h | 10 +++++----- Marlin/src/lcd/e3v2/proui/dwinui.h | 4 ++-- Marlin/src/lcd/e3v2/proui/endstop_diag.cpp | 2 +- 6 files changed, 15 insertions(+), 15 deletions(-) diff --git a/Marlin/src/lcd/e3v2/common/dwin_color.h b/Marlin/src/lcd/e3v2/common/dwin_color.h index 8df4f95151ac..2496f72c340d 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_color.h +++ b/Marlin/src/lcd/e3v2/common/dwin_color.h @@ -22,14 +22,14 @@ #pragma once // Extended and default UI Colors -#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R,B: 0..31; G: 0..63 +#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R: 0..31, G: 0..63, B: 0..31 #define GetRColor(color) ((color >> 11) & 0x1F) #define GetGColor(color) ((color >> 5) & 0x3F) #define GetBColor(color) ((color >> 0) & 0x1F) #define COLOR_WHITE 0xFFFF -#define COLOR_YELLOW RGB(0x1F,0x3F,0x00) -#define COLOR_RED RGB(0x1F,0x00,0x00) +#define COLOR_YELLOW RGB(0x1F, 0x3F, 0x00) +#define COLOR_RED RGB(0x1F, 0x00, 0x00) #define COLOR_ERROR_RED 0xB000 // Error! #define COLOR_BG_RED 0xF00F // Red background color #define COLOR_BG_WINDOW 0x31E8 // Popup background color diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h index 3d51d3ce2e89..f42fc9ab98a9 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -155,7 +155,7 @@ enum colorID : uint8_t { #define Custom_Colors 10 #define COLOR_LIGHT_WHITE 0xBDD7 -#define COLOR_GREEN RGB(0x00,0x3F,0x00) +#define COLOR_GREEN RGB(0x00, 0x3F, 0x00) #define COLOR_LIGHT_GREEN 0x3460 #define COLOR_CYAN 0x07FF #define COLOR_LIGHT_CYAN 0x04F3 diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 3e36d59fec26..d0b480dfa5a1 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2679,9 +2679,9 @@ void onDrawGetColorItem(MenuItem* menuitem, int8_t line) { const uint8_t i = menuitem->icon; uint16_t color; switch (i) { - case 0: color = RGB(31, 0, 0); break; // Red - case 1: color = RGB(0, 63, 0); break; // Green - case 2: color = RGB(0, 0, 31); break; // Blue + case 0: color = RGB(31, 0, 0); break; // Red + case 1: color = RGB(0, 63, 0); break; // Green + case 2: color = RGB(0, 0, 31); break; // Blue default: color = 0; break; } dwinDrawRectangle(0, hmiData.colorHighlight, ICOX + 1, MBASE(line) - 1 + 1, ICOX + 18, MBASE(line) - 1 + 18); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 0d451c44772e..1db5292155e5 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -46,15 +46,15 @@ #define JUST_BABYSTEP 1 #endif -#define defColorBackground RGB( 1, 12, 8) +#define defColorBackground RGB(1, 12, 8) #define defColorCursor RGB(20, 49, 31) -#define defColorTitleBg RGB( 0, 23, 16) +#define defColorTitleBg RGB(0, 23, 16) #define defColorTitleTxt COLOR_WHITE #define defColorText COLOR_WHITE #define defColorSelected COLOR_SELECT -#define defColorSplitLine RGB( 0, 23, 16) +#define defColorSplitLine RGB(0, 23, 16) #define defColorHighlight COLOR_WHITE -#define defColorStatusBg RGB( 0, 23, 16) +#define defColorStatusBg RGB(0, 23, 16) #define defColorStatusTxt COLOR_YELLOW #define defColorPopupBg COLOR_BG_WINDOW #define defColorPopupTxt COLOR_POPUP_TEXT @@ -64,7 +64,7 @@ #define defColorBarfill COLOR_BARFILL #define defColorIndicator COLOR_WHITE #define defColorCoordinate COLOR_WHITE -#define defColorButton RGB( 0, 23, 16) +#define defColorButton RGB(0, 23, 16) #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) #define defColorLeds LEDColorWhite() #endif diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h index 682313567d6e..93111479c322 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.h +++ b/Marlin/src/lcd/e3v2/proui/dwinui.h @@ -165,8 +165,8 @@ // Extended and default UI Colors #define COLOR_BLACK 0 -#define COLOR_GREEN RGB(0, 63, 0) -#define COLOR_BLUE RGB(0, 0, 31) +#define COLOR_GREEN RGB(0, 63, 0) +#define COLOR_BLUE RGB(0, 0, 31) #define COLOR_LIGHT_WHITE 0xBDD7 #define COLOR_LIGHT_GREEN 0x3460 #define COLOR_CYAN 0x07FF diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp index 21c83dc8faa0..a0c00100b157 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp @@ -61,7 +61,7 @@ void draw_es_state(const bool is_hit) { const uint8_t LM = 130; DWINUI::cursor.x = LM; dwinDrawRectangle(1, hmiData.colorPopupBg, LM, DWINUI::cursor.y, LM + 100, DWINUI::cursor.y + 20); - is_hit ? DWINUI::drawString(RGB(31,31,16), F(STR_ENDSTOP_HIT)) : DWINUI::drawString(RGB(16,63,16), F(STR_ENDSTOP_OPEN)); + is_hit ? DWINUI::drawString(RGB(31, 31, 16), F(STR_ENDSTOP_HIT)) : DWINUI::drawString(RGB(16, 63, 16), F(STR_ENDSTOP_OPEN)); DWINUI::moveBy(0, 25); } From 90607e149c2bcada69092a2f5c5d2723b2d3cfa8 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 21 Dec 2023 10:28:55 -0500 Subject: [PATCH 020/109] small change change from OPTCODE to #if --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 338fd5a9c95f..6228075fb69a 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -4025,7 +4025,9 @@ void drawStepsMenu() { EDIT_ITEM(ICON_MeshEditX, MSG_MESH_X, onDrawPInt8Menu, setEditMeshX, &bedLevelTools.mesh_x); EDIT_ITEM(ICON_MeshEditY, MSG_MESH_Y, onDrawPInt8Menu, setEditMeshY, &bedLevelTools.mesh_y); editZValueItem = EDIT_ITEM(ICON_MeshEditZ, MSG_MESH_EDIT_Z, onDrawPFloat2Menu, setEditZValue, &bedlevel.z_values[bedLevelTools.mesh_x][bedLevelTools.mesh_y]); - OPTCODE(HAS_BED_PROBE, MENU_ITEM_F(ICON_UBLActive, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY)) + #if HAS_BED_PROBE + HAS_BED_PROBE, MENU_ITEM_F(ICON_UBLActive, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY); + #endif } updateMenu(editMeshMenu); } From 1c75a65b043e27f0f141c22fdcda6d796c626c67 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 25 Dec 2023 02:26:19 -0500 Subject: [PATCH 021/109] fix error, duplicate case --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index d221c8c41253..eac731986637 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1429,7 +1429,6 @@ void dwinHandleScreen() { case ID_Popup: hmiPopup(); break; case ID_Leveling: break; TERN_(HAS_LOCKSCREEN, case ID_Locked: hmiLockScreen(); break;) - case ID_PrintDone: TERN_(HAS_ESDIAG, case ID_ESDiagProcess:) TERN_(PROUI_ITEM_PLOT, case ID_PlotProcess:) case ID_PrintDone: From 843fc13727ee0d904473c9657c23bfad09a1785d Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 25 Dec 2023 02:27:55 -0500 Subject: [PATCH 022/109] rename to G-Code, Marlin webui --- buildroot/web-ui/data/www/index.html | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/buildroot/web-ui/data/www/index.html b/buildroot/web-ui/data/www/index.html index 1a8db1cafb04..1628840634f3 100644 --- a/buildroot/web-ui/data/www/index.html +++ b/buildroot/web-ui/data/www/index.html @@ -384,7 +384,7 @@
-
GCode Lines
+
G-Code Lines
-
@@ -466,11 +466,11 @@
- GCode checksum value: + G-Code checksum value:  
- +
From 7fabcefc1b922b46b572c93edc9459349531b6e7 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 25 Dec 2023 05:51:39 -0500 Subject: [PATCH 023/109] update digitpot spacing --- Marlin/src/feature/digipot/digipot_mcp4018.cpp | 2 +- Marlin/src/feature/digipot/digipot_mcp4451.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index f776c5a33901..48d7ff492c40 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -37,7 +37,7 @@ #ifndef DIGIPOT_A4988_Vrefmax #define DIGIPOT_A4988_Vrefmax 1.666 #endif -#define DIGIPOT_MCP4018_MAX_VALUE 127 +#define DIGIPOT_MCP4018_MAX_VALUE 127 #define DIGIPOT_A4988_Itripmax(Vref) ((Vref) / (8.0 * DIGIPOT_A4988_Rsx)) diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index 7416fe9f8d5c..e35b42a28bd5 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -35,8 +35,8 @@ // Settings for the I2C based DIGIPOT (MCP4451) on Azteeg X3 Pro #if MB(5DPRINT) - #define DIGIPOT_I2C_FACTOR 117.96f - #define DIGIPOT_I2C_MAX_CURRENT 1.736f + #define DIGIPOT_I2C_FACTOR 117.96f + #define DIGIPOT_I2C_MAX_CURRENT 1.736f #elif MB(AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI) #define DIGIPOT_I2C_FACTOR 113.5f #define DIGIPOT_I2C_MAX_CURRENT 2.0f From 5722f559ee0190175ab74950e8876e13d5172bd6 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 25 Dec 2023 06:50:05 -0500 Subject: [PATCH 024/109] update more spacing --- Marlin/src/lcd/e3v2/proui/dwin.h | 3 +++ Marlin/src/lcd/language/language_test.h | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index ec0cde682877..c8796053728b 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -155,6 +155,7 @@ typedef struct { bool enablePreview = true; #endif } hmi_data_t; + extern hmi_data_t hmiData; static constexpr size_t eeprom_data_size = sizeof(hmi_data_t); @@ -179,6 +180,7 @@ typedef struct { uint8_t select = 0; // Auxiliary selector variable AxisEnum axis = X_AXIS; // Axis Select } hmi_value_t; + extern hmi_value_t hmiValue; typedef struct { @@ -189,6 +191,7 @@ typedef struct { bool select_flag:1; // Popup button selected bool home_flag:1; // homing in course } hmi_flag_t; + extern hmi_flag_t hmiFlag; extern uint8_t checkkey; diff --git a/Marlin/src/lcd/language/language_test.h b/Marlin/src/lcd/language/language_test.h index 657e4e2e48a2..6e160a6b02f7 100644 --- a/Marlin/src/lcd/language/language_test.h +++ b/Marlin/src/lcd/language/language_test.h @@ -116,7 +116,7 @@ namespace Language_test { using namespace Language_en; // Inherit undefined strings from English - constexpr uint8_t CHARSIZE = 1; + constexpr uint8_t CHARSIZE = 1; #if ENABLED(DISPLAYTEST) LSTR WELCOME_MSG = _UxGT("Language TEST"); From 2184b9640297095bb7956db9623c0df60fde210d Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 27 Dec 2023 02:18:01 -0500 Subject: [PATCH 025/109] add ZeroMesh in editmesh menu ResetMesh if HAS_MESH --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index eac731986637..888dff4eb7e7 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -4021,18 +4021,28 @@ void drawStepsMenu() { #endif #if ENABLED(PROUI_MESH_EDIT) + void manualResetValue() { + gcode.process_subcommands_now( + TS(F("M421I"), bedLevelTools.mesh_x, 'J', bedLevelTools.mesh_y, 'Z', p_float_t(0, 3)) + ); + planner.synchronize(); + } + bool autoMovToMesh = false; void setAutoMovToMesh() { toggleCheckboxLine(autoMovToMesh); } + void liveEditMesh() { ((MenuItemPtr*)editZValueItem)->value = &bedlevel.z_values[hmiValue.select ? bedLevelTools.mesh_x : menuData.value][hmiValue.select ? menuData.value : bedLevelTools.mesh_y]; editZValueItem->redraw(); } void applyEditMeshX() { bedLevelTools.mesh_x = menuData.value; if (autoMovToMesh) bedLevelTools.moveToXY(); } void applyEditMeshY() { bedLevelTools.mesh_y = menuData.value; if (autoMovToMesh) bedLevelTools.moveToXY(); } - void resetMesh() { bedLevelTools.meshReset(); LCD_MESSAGE(MSG_MESH_RESET); } + void zeroMesh() { manualResetValue(); EditZValueItem->redraw(); LCD_MESSAGE(MSG_MESH_RESET); } void setEditMeshX() { hmiValue.select = 0; setIntOnClick(0, GRID_MAX_POINTS_X - 1, bedLevelTools.mesh_x, applyEditMeshX, liveEditMesh); } void setEditMeshY() { hmiValue.select = 1; setIntOnClick(0, GRID_MAX_POINTS_Y - 1, bedLevelTools.mesh_y, applyEditMeshY, liveEditMesh); } void liveEditMeshZ() { *menuData.floatPtr = menuData.value / POW(10, 2); if (autoMovToMesh) bedLevelTools.moveToZ(); } void setEditZValue() { setPFloatOnClick(Z_OFFSET_MIN, Z_OFFSET_MAX, 3, nullptr, liveEditMeshZ); if (autoMovToMesh) bedLevelTools.moveToXYZ(); } #endif + void resetMesh() { bedLevelTools.meshReset(); LCD_MESSAGE(MSG_MESH_RESET); } + #endif // HAS_MESH #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -4097,8 +4107,8 @@ void drawStepsMenu() { MENU_ITEM(ICON_UBLTiltGrid, MSG_UBL_TILT_MESH, onDrawMenuItem, ublMeshTilt); MENU_ITEM(ICON_UBLSmartFill, MSG_UBL_SMART_FILLIN, onDrawMenuItem, ublSmartFillMesh); #endif + MENU_ITEM(ICON_MeshReset, MSG_MESH_RESET, onDrawMenuItem, resetMesh); #if ENABLED(PROUI_MESH_EDIT) - MENU_ITEM(ICON_MeshReset, MSG_MESH_RESET, onDrawMenuItem, resetMesh); MENU_ITEM(ICON_MeshEdit, MSG_EDIT_MESH, onDrawSubMenu, drawEditMeshMenu); #endif MENU_ITEM(ICON_MeshViewer, MSG_MESH_VIEW, onDrawSubMenu, dwinMeshViewer); @@ -4114,13 +4124,14 @@ void drawStepsMenu() { if (SET_MENU(editMeshMenu, MSG_EDIT_MESH, 6)) { bedLevelTools.mesh_x = bedLevelTools.mesh_y = 0; BACK_ITEM(drawMeshSetMenu); - EDIT_ITEM_F(ICON_UBLActive, "Move to position", onDrawChkbMenu, setAutoMovToMesh, &autoMovToMesh); + EDIT_ITEM(ICON_SetHome, MSG_PROBE_WIZARD_MOVING, onDrawChkbMenu, setAutoMovToMesh, &autoMovToMesh); EDIT_ITEM(ICON_MeshEditX, MSG_MESH_X, onDrawPInt8Menu, setEditMeshX, &bedLevelTools.mesh_x); EDIT_ITEM(ICON_MeshEditY, MSG_MESH_Y, onDrawPInt8Menu, setEditMeshY, &bedLevelTools.mesh_y); editZValueItem = EDIT_ITEM(ICON_MeshEditZ, MSG_MESH_EDIT_Z, onDrawPFloat2Menu, setEditZValue, &bedlevel.z_values[bedLevelTools.mesh_x][bedLevelTools.mesh_y]); #if HAS_BED_PROBE - HAS_BED_PROBE, MENU_ITEM_F(ICON_UBLActive, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY); + HAS_BED_PROBE, MENU_ITEM_F(ICON_ProbeDeploy, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY); #endif + MENU_ITEM_F(ICON_SetZOffset, "Zero Current Point", onDrawMenuItem, zeroMesh); } updateMenu(editMeshMenu); } From 4b3ab1a9c1308d7b75cb2866cbeb707594262b33 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 1 Jan 2024 07:09:22 -0500 Subject: [PATCH 026/109] add space to "extern" --- Marlin/src/lcd/menu/menu.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index de9e4d5086a1..47ddc00bf4a8 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -146,6 +146,7 @@ typedef union { uint32_t uint32; celsius_t celsius; } chimera_t; + extern chimera_t editable; // Base class for Menu Edit Items From 0472c051051319bf6568285788d3eb91a44e833f Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 1 Jan 2024 07:18:41 -0500 Subject: [PATCH 027/109] remove extra ";" from invaders.h --- Marlin/src/lcd/menu/game/invaders.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/game/invaders.h b/Marlin/src/lcd/menu/game/invaders.h index c99e6c16ae76..a3ae6ffaedc2 100644 --- a/Marlin/src/lcd/menu/game/invaders.h +++ b/Marlin/src/lcd/menu/game/invaders.h @@ -53,8 +53,8 @@ typedef struct { uint8_t bugs[INVADER_ROWS], shooters[(INVADER_ROWS) * (INVADER_COLS)]; int8_t ufox, ufov; bool game_blink; - int8_t laser_col() { return ((laser.x - pos.x) / (INVADER_COL_W)); }; - int8_t laser_row() { return ((laser.y - pos.y + 2) / (INVADER_ROW_H)); }; + int8_t laser_col() { return ((laser.x - pos.x) / (INVADER_COL_W)); } + int8_t laser_row() { return ((laser.y - pos.y + 2) / (INVADER_ROW_H)); } } invaders_data_t; class InvadersGame : MarlinGame { public: static void enter_game(), game_screen(); }; From f5cadc561484794e4f5f34ca5759d30b808c5fd9 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 1 Jan 2024 22:38:28 -0500 Subject: [PATCH 028/109] update pins_CREALITY_CR4NTXXC10.h w/HAS_DWIN_E3V2 --- Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h b/Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h index d25cd6c17e42..5216f7ff8811 100644 --- a/Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h +++ b/Marlin/src/pins/stm32f4/pins_CREALITY_CR4NTXXC10.h @@ -226,7 +226,7 @@ #define BEEPER_PIN EXP1_01_PIN #endif -#elif ENABLED(DWIN_CREALITY_LCD) +#elif ENABLED(HAS_DWIN_E3V2) // DWIN ENCODER LCD #define BTN_ENC EXP1_05_PIN From 36d9b25810fc05b4fd06658d5053cdb73e0dffa7 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 1 Jan 2024 23:01:49 -0500 Subject: [PATCH 029/109] remove DWIN_CREALITY_LCD from MarlinCore.cpp, use ui.update() - relocate in dwin.cpp --- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 1dcee50d12c9..15c0bfd459bc 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -817,7 +817,7 @@ void idle(const bool no_stepper_sleep/*=false*/) { TERN_(HAS_BEEPER, buzzer.tick()); // Handle UI input / draw events - TERN(DWIN_CREALITY_LCD, dwinUpdate(), ui.update()); + ui.update(); // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index f79105b44f78..980af378bcf1 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1804,6 +1804,12 @@ void hmiSDCardInit() { card.cdroot(); } // Initialize or re-initialize the LCD void MarlinUI::init_lcd() { dwinStartup(); } +void MarlinUI::update() { + eachMomentUpdate(); // Status update + hmiSDCardUpdate(); // SD card update + dwinHandleScreen(); // Rotary encoder update +} + void MarlinUI::refresh() { /* Nothing to see here */ } #if HAS_LCD_BRIGHTNESS @@ -4068,12 +4074,6 @@ void dwinInitScreen() { hmiStartFrame(true); } -void dwinUpdate() { - eachMomentUpdate(); // Status update - hmiSDCardUpdate(); // SD card update - dwinHandleScreen(); // Rotary encoder update -} - void eachMomentUpdate() { static millis_t next_var_update_ms = 0, next_rts_update_ms = 0; From a7d1a8c3515cb06bfacce1eb58f82aac91268181 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Fri, 5 Jan 2024 19:22:38 -0500 Subject: [PATCH 030/109] revert Configuration_adv.h --- Marlin/Configuration_adv.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index ee89cf3cf8ea..10316ac9282b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3911,7 +3911,7 @@ // @section reporting // Extra options for the M114 "Current Position" report -//#define M114_DETAIL // Use 'M114' for details to check planner calculations +//#define M114_DETAIL // Use 'M114` for details to check planner calculations //#define M114_REALTIME // Real current position based on forward kinematics //#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed. @@ -3923,6 +3923,7 @@ * Spend 28 bytes of SRAM to optimize the G-code parser */ #define FASTER_GCODE_PARSER + #if ENABLED(FASTER_GCODE_PARSER) //#define GCODE_QUOTED_STRINGS // Support for quoted string parameters #endif From fa023126c3113be5dc15d62b283992aeb8fcdbdd Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 6 Jan 2024 00:54:37 -0500 Subject: [PATCH 031/109] fix CrealityUI error - ui.update/kill_screen update tests capitilize "v2" update so CrealityUI => `HAS_DISPLAY`, uses ui.update --- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/module/temperature.cpp | 2 +- buildroot/tests/STM32F103RE_creality | 8 ++++---- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 91496b1c5c50..4b8dbec768a5 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -884,7 +884,7 @@ void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullp // Echo the LCD message to serial for extra context if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLN(lcd_error); } - #if HAS_DISPLAY + #if HAS_DISPLAY && DISABLED(DWIN_CREALITY_LCD) ui.kill_screen(lcd_error ?: GET_TEXT_F(MSG_KILLED), lcd_component ?: FPSTR(NUL_STR)); #else UNUSED(lcd_error); UNUSED(lcd_component); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index e07d026cb961..ba88a42f1d19 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1069,7 +1069,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 diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index e65297b04a24..cfcb23a68f20 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -894,7 +894,7 @@ volatile bool Temperature::raw_temps_ready = false; hal.idletask(); // Run UI update - TERN(DWIN_CREALITY_LCD, dwinUpdate(), ui.update()); + ui.update(); } wait_for_heatup = false; diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index 63d0edd6677b..cf3aecb1906e 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -13,21 +13,21 @@ use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_disable DWIN_CREALITY_LCD opt_enable DWIN_LCD_PROUI opt_add NO_AUTO_ASSIGN_WARNING -exec_test $1 $2 "Ender-3 v2 - ProUI (Default)" "$3" +exec_test $1 $2 "Ender-3 V2 - ProUI (Default)" "$3" use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING BLTOUCH AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING -exec_test $1 $2 "Ender-3 v2 - CrealityUI" "$3" +exec_test $1 $2 "Ender-3 V2 - CrealityUI" "$3" use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_disable DWIN_CREALITY_LCD opt_enable DWIN_CREALITY_LCD_JYERSUI AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY -exec_test $1 $2 "Ender-3 v2 - JyersUI (ABL Bilinear/Manual)" "$3" +exec_test $1 $2 "Ender-3 V2 - JyersUI (ABL Bilinear/Manual)" "$3" use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_disable DWIN_CREALITY_LCD PIDTEMP opt_enable DWIN_MARLINUI_LANDSCAPE LCD_ENDSTOP_TEST AUTO_BED_LEVELING_UBL BLTOUCH Z_SAFE_HOMING MPCTEMP MPC_AUTOTUNE -exec_test $1 $2 "Ender-3 v2 - MarlinUI (UBL+BLTOUCH, MPCTEMP, LCD_ENDSTOP_TEST)" "$3" +exec_test $1 $2 "Ender-3 V2 - MarlinUI (UBL+BLTOUCH, MPCTEMP, LCD_ENDSTOP_TEST)" "$3" use_example_configs "Creality/Ender-3 S1/STM32F1" opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CANCEL_OBJECTS FWRETRACT EVENT_GCODE_SD_ABORT From 3a0cc0ae958d1df665cfa8324299ae5debf4a583 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 6 Jan 2024 01:09:23 -0500 Subject: [PATCH 032/109] fix proui error --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index f516e4f09651..ae9cd30469b4 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1426,14 +1426,14 @@ void dwinHandleScreen() { case ID_SetIntNoDraw: hmiSetNoDraw(); break; case ID_PrintProcess: hmiPrinting(); break; case ID_Popup: hmiPopup(); break; - case ID_Leveling: break; + TERN_(HAS_BED_PROBE, case ID_Leveling: break;) TERN_(HAS_LOCKSCREEN, case ID_Locked: hmiLockScreen(); break;) + TERN_(HAS_ESDIAG, case ID_ESDiagProcess:) TERN_(PROUI_ITEM_PLOT, case ID_PlotProcess:) case ID_PrintDone: case ID_WaitResponse: hmiWaitForUser(); break; - TERN_(HAS_BED_PROBE, case ID_Leveling:) case ID_Homing: case ID_PIDProcess: case ID_NothingToDo: From 3719b5db84dc632d63be1f26d5c79b30f07207e3 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 6 Jan 2024 01:21:53 -0500 Subject: [PATCH 033/109] fix other proui error --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index ae9cd30469b4..cbc18fcd354d 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -4027,7 +4027,7 @@ void drawStepsMenu() { void liveEditMesh() { ((MenuItemPtr*)editZValueItem)->value = &bedlevel.z_values[hmiValue.select ? bedLevelTools.mesh_x : menuData.value][hmiValue.select ? menuData.value : bedLevelTools.mesh_y]; editZValueItem->redraw(); } void applyEditMeshX() { bedLevelTools.mesh_x = menuData.value; if (autoMovToMesh) bedLevelTools.moveToXY(); } void applyEditMeshY() { bedLevelTools.mesh_y = menuData.value; if (autoMovToMesh) bedLevelTools.moveToXY(); } - void zeroMesh() { manualResetValue(); EditZValueItem->redraw(); LCD_MESSAGE(MSG_MESH_RESET); } + void zeroMesh() { manualResetValue(); editZValueItem->redraw(); LCD_MESSAGE(MSG_MESH_RESET); } void setEditMeshX() { hmiValue.select = 0; setIntOnClick(0, GRID_MAX_POINTS_X - 1, bedLevelTools.mesh_x, applyEditMeshX, liveEditMesh); } void setEditMeshY() { hmiValue.select = 1; setIntOnClick(0, GRID_MAX_POINTS_Y - 1, bedLevelTools.mesh_y, applyEditMeshY, liveEditMesh); } void liveEditMeshZ() { *menuData.floatPtr = menuData.value / POW(10, 2); if (autoMovToMesh) bedLevelTools.moveToZ(); } @@ -4122,7 +4122,7 @@ void drawStepsMenu() { EDIT_ITEM(ICON_MeshEditY, MSG_MESH_Y, onDrawPInt8Menu, setEditMeshY, &bedLevelTools.mesh_y); editZValueItem = EDIT_ITEM(ICON_MeshEditZ, MSG_MESH_EDIT_Z, onDrawPFloat2Menu, setEditZValue, &bedlevel.z_values[bedLevelTools.mesh_x][bedLevelTools.mesh_y]); #if HAS_BED_PROBE - HAS_BED_PROBE, MENU_ITEM_F(ICON_ProbeDeploy, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY); + MENU_ITEM_F(ICON_ProbeDeploy, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY); #endif MENU_ITEM_F(ICON_SetZOffset, "Zero Current Point", onDrawMenuItem, zeroMesh); } From 22e836591c067d021ab8fc5a59d0fea0cabb15b8 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 6 Jan 2024 23:28:59 -0500 Subject: [PATCH 034/109] transfer from Enable 2 mesh viewers as fixes/tweaks --- Marlin/src/feature/pause.h | 4 +- Marlin/src/gcode/calibrate/M48.cpp | 3 +- Marlin/src/gcode/host/M114.cpp | 6 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 19 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 3 +- Marlin/src/lcd/marlinui.cpp | 2 + Marlin/src/lcd/marlinui.h | 6 +- Marlin/src/pins/pins.h | 4 +- buildroot/share/vscode/avrdude.conf | 26212 ++++++++++++------------ 9 files changed, 13133 insertions(+), 13126 deletions(-) diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index 304c8a611d13..2b14fc94f725 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -105,7 +105,7 @@ void wait_for_confirmation( void resume_print( const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move - const_float_t extrude_length=ADVANCED_PAUSE_PURGE_LENGTH, // (mm) Purge length + const_float_t purge_length=ADVANCED_PAUSE_PURGE_LENGTH, // (mm) Purge length const int8_t max_beep_count=0, // Beep alert for attention const celsius_t targetTemp=0 // (°C) A target temperature for the hotend DXC_PARAMS // Dual-X-Carriage extruder index @@ -114,7 +114,7 @@ void resume_print( bool load_filament( const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move - const_float_t extrude_length=0, // (mm) Purge length + const_float_t purge_length=0, // (mm) Purge length const int8_t max_beep_count=0, // Beep alert for attention const bool show_lcd=false, // Set LCD status messages? const bool pause_for_user=false, // Pause for user before returning? diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 2d219a07c5fc..cb74c990aabc 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -261,8 +261,7 @@ void GcodeSuite::M48() { #if HAS_STATUS_MESSAGE // Display M48 results in the status bar - char sigma_str[8]; - ui.status_printf(0, F(S_FMT ": %s"), GET_TEXT(MSG_M48_DEVIATION), dtostrf(sigma, 2, 6, sigma_str)); + ui.set_status_and_level(MString<30>(GET_TEXT_F(MSG_M48_DEVIATION), F(": "), w_float_t(sigma, 2, 6))); #endif } diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 979764f75e30..2a46de9c861a 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -29,19 +29,17 @@ #if ENABLED(M114_DETAIL) void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=LOGICAL_AXES, const uint8_t precision=3) { - char str[12]; for (uint8_t a = 0; a < n; ++a) { SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_LBL[a])); if (pos[a] >= 0) SERIAL_CHAR(' '); - SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); + SERIAL_ECHO(p_float_t(pos[a], precision)); } SERIAL_EOL(); } inline void report_linear_axis_pos(const xyze_pos_t &pos) { report_all_axis_pos(pos, XYZ); } void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) { - char str[12]; - LOOP_NUM_AXES(a) SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_LBL[a]), dtostrf(pos[a], 1, precision, str)); + LOOP_NUM_AXES(a) SERIAL_ECHO(FPSTR(pgm_read_ptr(&SP_AXIS_LBL[a])), p_float_t(pos[a], precision)); SERIAL_EOL(); } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 980af378bcf1..2c381f2125a1 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1049,7 +1049,7 @@ void drawMotionMenu() { clearPopupArea(); drawPopupBkgd105(); if (toohigh) { - dwinIconShow(ICON, ICON_TempTooHigh, 102, 165); + dwinIconShow(ICON, ICON_TempTooHigh, 100, 165); if (hmiIsChinese()) { dwinFrameAreaCopy(1, 103, 371, 237, 386, 52, 285); // Temp Too High dwinFrameAreaCopy(1, 151, 389, 185, 402, 187, 285); @@ -1061,7 +1061,7 @@ void drawMotionMenu() { } } else { - dwinIconShow(ICON, ICON_TempTooLow, 102, 165); + dwinIconShow(ICON, ICON_TempTooLow, 100, 165); if (hmiIsChinese()) { dwinFrameAreaCopy(1, 103, 371, 270, 386, 52, 285); // Tenp Too Low dwinFrameAreaCopy(1, 189, 389, 271, 402, 95, 310); @@ -1084,7 +1084,7 @@ void drawPopupBkgd60() { void popupWindowETempTooLow() { clearMainWindow(); drawPopupBkgd60(); - dwinIconShow(ICON, ICON_TempTooLow, 102, 105); + dwinIconShow(ICON, ICON_TempTooLow, 100, 105); if (hmiIsChinese()) { dwinFrameAreaCopy(1, 103, 371, 136, 386, 69, 240); // Nozzle Too Cold dwinFrameAreaCopy(1, 170, 371, 270, 386, 69 + 33, 240); @@ -1119,7 +1119,7 @@ void popupWindowResume() { void popupWindowHome(const bool parking/*=false*/) { clearMainWindow(); drawPopupBkgd60(); - dwinIconShow(ICON, ICON_BLTouch, 101, 105); + dwinIconShow(ICON, ICON_BLTouch, 100, 105); if (hmiIsChinese()) { dwinFrameAreaCopy(1, 0, 371, 33, 386, 85, 240); // Wait for Move to Complete dwinFrameAreaCopy(1, 203, 286, 271, 302, 118, 240); @@ -1136,7 +1136,7 @@ void popupWindowHome(const bool parking/*=false*/) { void popupWindowLeveling() { clearMainWindow(); drawPopupBkgd60(); - dwinIconShow(ICON, ICON_AutoLeveling, 101, 105); + dwinIconShow(ICON, ICON_AutoLeveling, 100, 105); if (hmiIsChinese()) { dwinFrameAreaCopy(1, 0, 371, 100, 386, 84, 240); // Wait for Leveling dwinFrameAreaCopy(1, 0, 389, 150, 402, 61, 280); @@ -1810,6 +1810,15 @@ void MarlinUI::update() { dwinHandleScreen(); // Rotary encoder update } +// void MarlinUI::kill_screen(FSTR_P const error, FSTR_P const) { +// clearMainWindow(); +// drawPopupBkgd60(); +// dwinIconShow(ICON, ICON_TempTooHigh, 100, 105); +// dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, 20, 220, GET_TEXT_F(MSG_HALTED)); +// dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, 20, 220, error); +// dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, 20, 250, GET_TEXT_F(MSG_TURN_OFF)); +// } + void MarlinUI::refresh() { /* Nothing to see here */ } #if HAS_LCD_BRIGHTNESS diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index cbc18fcd354d..1ce6c253e8fb 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2010,7 +2010,6 @@ void dwinRedrawScreen() { void onClickConfirmToPrint() { dwinResetStatusLine(); if (hmiFlag.select_flag) { // Confirm - gotoMainMenu(); return card.openAndPrintFile(card.filename); } else @@ -4120,7 +4119,7 @@ void drawStepsMenu() { EDIT_ITEM(ICON_SetHome, MSG_PROBE_WIZARD_MOVING, onDrawChkbMenu, setAutoMovToMesh, &autoMovToMesh); EDIT_ITEM(ICON_MeshEditX, MSG_MESH_X, onDrawPInt8Menu, setEditMeshX, &bedLevelTools.mesh_x); EDIT_ITEM(ICON_MeshEditY, MSG_MESH_Y, onDrawPInt8Menu, setEditMeshY, &bedLevelTools.mesh_y); - editZValueItem = EDIT_ITEM(ICON_MeshEditZ, MSG_MESH_EDIT_Z, onDrawPFloat2Menu, setEditZValue, &bedlevel.z_values[bedLevelTools.mesh_x][bedLevelTools.mesh_y]); + editZValueItem = EDIT_ITEM(ICON_MeshEditZ, MSG_MESH_EDIT_Z, onDrawPFloat3Menu, setEditZValue, &bedlevel.z_values[bedLevelTools.mesh_x][bedLevelTools.mesh_y]); #if HAS_BED_PROBE MENU_ITEM_F(ICON_ProbeDeploy, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY); #endif diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 73094761822d..27d7b0bd032e 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1657,6 +1657,8 @@ void MarlinUI::host_notify(const char * const cstr) { pgm ? host_notify_P(ustr) : host_notify(ustr); } void MarlinUI::status_printf_P(int8_t level, PGM_P const fmt, ...) { + if (set_alert_level(level)) return; + MString<30> msg; va_list args; diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index a463701f566a..a862d809f15b 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -465,7 +465,7 @@ class MarlinUI { * @param fstr A constant F-string to set as the status. * @param level Alert level. Negative to ignore and reset the level. Non-zero never expires. */ - static void set_status_and_level(const char * const cstr, const int8_t level) { _set_status_and_level(cstr, level, false); } + static void set_status_and_level(const char * const cstr, const int8_t level=0) { _set_status_and_level(cstr, level, false); } /** * @brief Set Status with a P-string and alert level. @@ -473,7 +473,7 @@ class MarlinUI { * @param ustr A C- or P-string, according to pgm. * @param level Alert level. Negative to ignore and reset the level. Non-zero never expires. */ - static void set_status_and_level_P(PGM_P const pstr, const int8_t level) { _set_status_and_level(pstr, level, true); } + static void set_status_and_level_P(PGM_P const pstr, const int8_t level=0) { _set_status_and_level(pstr, level, true); } /** * @brief Set Status with a fixed string and alert level. @@ -481,7 +481,7 @@ class MarlinUI { * @param fstr A constant F-string to set as the status. * @param level Alert level. Negative to ignore and reset the level. Non-zero never expires. */ - static void set_status_and_level(FSTR_P const fstr, const int8_t level) { set_status_and_level_P(FTOP(fstr), level); } + static void set_status_and_level(FSTR_P const fstr, const int8_t level=0) { set_status_and_level_P(FTOP(fstr), level); } static void set_max_status(FSTR_P const fstr) { set_status_and_level(fstr, 127); } static void set_min_status(FSTR_P const fstr) { set_status_and_level(fstr, -1); } diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index d162881993ef..ce873a0f1990 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -647,13 +647,13 @@ #elif MB(CHITU3D_V9) #include "stm32f1/pins_CHITU3D_V9.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple #elif MB(CREALITY_V4) - #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple env:STM32F103RC_creality_maple #elif MB(CREALITY_V4210) #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V425) #include "stm32f1/pins_CREALITY_V425.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V422) - #include "stm32f1/pins_CREALITY_V422.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V422.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple env:STM32F103RC_creality_maple #elif MB(CREALITY_V423) #include "stm32f1/pins_CREALITY_V423.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer #elif MB(CREALITY_V427) diff --git a/buildroot/share/vscode/avrdude.conf b/buildroot/share/vscode/avrdude.conf index 991d255750f5..a1a3ef4ba4b8 100644 --- a/buildroot/share/vscode/avrdude.conf +++ b/buildroot/share/vscode/avrdude.conf @@ -240,8 +240,8 @@ #define AT86RF401 0xD0 #define AT89START 0xE0 -#define AT89S51 0xE0 -#define AT89S52 0xE1 +#define AT89S51 0xE0 +#define AT89S52 0xE1 # The following table lists the devices in the original AVR910 # appnote: @@ -293,15 +293,15 @@ # 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 +# ATmega8515 0x3A +# ATmega128 0x43 +# ATmega64 0x45 +# ATtiny26 0x5E +# ATmega8535 0x69 +# ATmega32 0x72 +# ATmega16 0x74 +# ATmega8 0x76 +# ATmega169 0x78 # # Overall avrdude defaults @@ -894,63 +894,63 @@ programmer # 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -958,132 +958,132 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -1091,170 +1091,170 @@ part #------------------------------------------------------------ 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 = + 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", + 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", + 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; + 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"; + "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"; - ; + 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 "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; + 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"; + 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"; - ; + 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; + 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"; + 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"; - ; + 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"; + ; ; @@ -1264,132 +1264,132 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -1397,114 +1397,114 @@ part #------------------------------------------------------------ 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -1512,112 +1512,112 @@ part #------------------------------------------------------------ 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", + 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; - ; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -1625,112 +1625,112 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -1738,126 +1738,126 @@ part #------------------------------------------------------------ part - id = "2333"; + 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"; - ; + 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"; + ; ; @@ -1866,122 +1866,122 @@ part #------------------------------------------------------------ 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"; - ; + 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"; + ; ; @@ -1990,123 +1990,123 @@ part #------------------------------------------------------------ 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -2114,82 +2114,82 @@ part #------------------------------------------------------------ part - id = "4434"; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -2197,113 +2197,113 @@ part #------------------------------------------------------------ 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 = + 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", + 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; - ; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -2311,120 +2311,120 @@ part #------------------------------------------------------------ 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", + 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", + 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", + 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", + 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; - ; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -2432,138 +2432,138 @@ part #------------------------------------------------------------ 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; + 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"; + " 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"; - ; + " 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"; + ; ; @@ -2572,177 +2572,177 @@ part #------------------------------------------------------------ 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"; - ; + 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"; + ; ; @@ -2753,177 +2753,177 @@ part #------------------------------------------------------------ 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -2931,189 +2931,189 @@ part #------------------------------------------------------------ part - id = "c128"; - desc = "AT90CAN128"; - has_jtag = yes; - stk500_devcode = 0xB3; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -3121,189 +3121,189 @@ part #------------------------------------------------------------ part - id = "c64"; - desc = "AT90CAN64"; - has_jtag = yes; - stk500_devcode = 0xB3; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -3311,189 +3311,189 @@ part #------------------------------------------------------------ part - id = "c32"; - desc = "AT90CAN32"; - has_jtag = yes; - stk500_devcode = 0xB3; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; @@ -3502,174 +3502,174 @@ part #------------------------------------------------------------ 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 = + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; @@ -3680,187 +3680,187 @@ part # 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; @@ -3871,187 +3871,187 @@ part # 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; @@ -4062,187 +4062,187 @@ part # 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -4252,187 +4252,187 @@ part # 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; @@ -4444,187 +4444,187 @@ part # 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; @@ -4634,193 +4634,193 @@ part #------------------------------------------------------------ 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", + 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", + 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; - ; + 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"; + 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"; - ; + 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; + 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"; + 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"; - ; + 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; + 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"; + 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"; - ; + 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; + 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"; + 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"; - ; + 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; + 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"; - ; + 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; + 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"; - ; + 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"; + ; ; @@ -4830,157 +4830,157 @@ part #------------------------------------------------------------ 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; + 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; + 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"; + " 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"; - ; + " 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"; + ; ; #------------------------------------------------------------ @@ -4988,179 +4988,179 @@ part #------------------------------------------------------------ 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; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -5168,182 +5168,182 @@ part #------------------------------------------------------------ part - id = "m329"; - desc = "ATMEGA329"; - has_jtag = yes; + 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; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -5352,182 +5352,182 @@ part # Identical to ATmega329 except of the signature part - id = "m329p"; - desc = "ATMEGA329P"; - has_jtag = yes; + 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; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -5537,182 +5537,182 @@ part # identical to ATmega329 part - id = "m3290"; - desc = "ATMEGA3290"; - has_jtag = yes; + 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; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -5722,182 +5722,182 @@ part # identical to ATmega3290 except of the signature part - id = "m3290p"; - desc = "ATMEGA3290P"; - has_jtag = yes; + 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; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -5905,182 +5905,182 @@ part #------------------------------------------------------------ part - id = "m649"; - desc = "ATMEGA649"; - has_jtag = yes; + 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; + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -6090,192 +6090,192 @@ part # identical to ATmega649 part - id = "m6490"; - desc = "ATMEGA6490"; - has_jtag = yes; + 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; + 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; + 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"; + " 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"; + " 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", + 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", + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -6283,174 +6283,174 @@ part #------------------------------------------------------------ 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; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -6458,138 +6458,138 @@ part #------------------------------------------------------------ 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; + 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; + 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"; + " 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"; - ; + " 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"; + ; ; @@ -6598,158 +6598,158 @@ part #------------------------------------------------------------ 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 = + 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; + 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"; + " 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"; - ; + " 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"; + ; ; @@ -6759,154 +6759,154 @@ part #------------------------------------------------------------ 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; + 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"; + " 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"; - ; + " 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"; + ; ; @@ -6917,156 +6917,156 @@ part #------------------------------------------------------------ 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; + 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"; + " 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"; - ; + " 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"; + ; ; @@ -7075,153 +7075,153 @@ part #------------------------------------------------------------ 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"; - ; + 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"; + ; ; @@ -7232,185 +7232,185 @@ part # 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; + 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", + 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", + 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"; - ; + 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"; + ; ; @@ -7421,185 +7421,185 @@ part # 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; + 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", + 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", + 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"; - ; + 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"; + ; ; @@ -7610,185 +7610,185 @@ part # 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; + 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", + 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", + 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"; - ; + 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"; + ; ; @@ -7798,185 +7798,185 @@ part #------------------------------------------------------------ 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; + 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 = + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; @@ -7985,185 +7985,185 @@ part #------------------------------------------------------------ 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; + 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 = + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -8171,187 +8171,187 @@ part #------------------------------------------------------------ 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 = + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -8359,185 +8359,185 @@ part #------------------------------------------------------------ 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; + 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 = + 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; + 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"; + " 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"; + " 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -8545,100 +8545,100 @@ part #------------------------------------------------------------ part - id = "m328p"; - desc = "ATMEGA328P"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 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", + 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", + 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 = + 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; + 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; + 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"; + " 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", + " 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"; + " 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; + " 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; + 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", @@ -8650,82 +8650,82 @@ part " 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"; + " 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"; + " 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"; + " 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; + mode = 0x41; + delay = 6; + blocksize = 128; + readsize = 256; - ; + ; - memory "lfuse" + 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"; + "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"; - ; + "x x x x x x x x i i i i i i i i"; + ; - memory "hfuse" + 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"; + "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"; - ; + "x x x x x x x x i i i i i i i i"; + ; - memory "efuse" + 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"; + "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"; - ; + "x x x x x x x x x x x x x i i i"; + ; - memory "lock" + 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"; + "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"; - ; + "x x x x x x x x 1 1 i i i i i i"; + ; - memory "calibration" + 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"; - ; + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; - memory "signature" + 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"; - ; + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -8733,186 +8733,186 @@ part #------------------------------------------------------------ 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; + 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", + 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", + 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"; + 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"; + 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"; + 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; - ; + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -8920,181 +8920,181 @@ part #------------------------------------------------------------ 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; + 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", + 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", + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -9104,181 +9104,181 @@ part # 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; + 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", + 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", + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -9287,180 +9287,180 @@ part # 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; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -9470,180 +9470,180 @@ part # 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; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -9651,179 +9651,179 @@ part #------------------------------------------------------------ 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; + 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; + 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", + 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", + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -9831,178 +9831,178 @@ part #------------------------------------------------------------ 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; + 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 = + 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", + 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", + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -10010,179 +10010,179 @@ part #------------------------------------------------------------ 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; + 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; + 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", + 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", + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -10191,187 +10191,187 @@ part # Almost same as ATmega1280, except for different memory sizes part - id = "m640"; - desc = "ATMEGA640"; - signature = 0x1e 0x96 0x08; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -10379,187 +10379,187 @@ part #------------------------------------------------------------ part - id = "m1280"; - desc = "ATMEGA1280"; - signature = 0x1e 0x97 0x03; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -10568,187 +10568,187 @@ part # Identical to ATmega1280 part - id = "m1281"; - desc = "ATMEGA1281"; - signature = 0x1e 0x97 0x04; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -10756,192 +10756,192 @@ part #------------------------------------------------------------ part - id = "m2560"; - desc = "ATMEGA2560"; - signature = 0x1e 0x98 0x01; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -10949,192 +10949,192 @@ part #------------------------------------------------------------ part - id = "m2561"; - desc = "ATMEGA2561"; - signature = 0x1e 0x98 0x02; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -11143,187 +11143,187 @@ part # Identical to ATmega2561 but half the ROM part - id = "m128rfa1"; - desc = "ATMEGA128RFA1"; - signature = 0x1e 0xa7 0x01; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -11331,181 +11331,181 @@ part #------------------------------------------------------------ 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; + 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; + 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", + 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", + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -11513,181 +11513,181 @@ part #------------------------------------------------------------ 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; + 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; + 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", + 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", + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -11695,182 +11695,182 @@ part #------------------------------------------------------------ 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; + 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; + 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", + 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", + 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; - ; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -11878,187 +11878,187 @@ part #------------------------------------------------------------ part - id = "m32u4"; - desc = "ATmega32U4"; - signature = 0x1e 0x95 0x87; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -12066,187 +12066,187 @@ part #------------------------------------------------------------ part - id = "usb646"; - desc = "AT90USB646"; - signature = 0x1e 0x96 0x82; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -12255,187 +12255,187 @@ part # identical to AT90USB646 part - id = "usb647"; - desc = "AT90USB647"; - signature = 0x1e 0x96 0x82; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -12443,187 +12443,187 @@ part #------------------------------------------------------------ part - id = "usb1286"; - desc = "AT90USB1286"; - signature = 0x1e 0x97 0x82; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -12632,187 +12632,187 @@ part # identical to AT90USB1286 part - id = "usb1287"; - desc = "AT90USB1287"; - signature = 0x1e 0x97 0x82; - has_jtag = yes; + 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", + 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", + 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"; - ; + 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"; + ; ; @@ -12821,179 +12821,179 @@ part #------------------------------------------------------------ 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -13005,179 +13005,179 @@ part # 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", + 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", + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -13185,188 +13185,188 @@ part #------------------------------------------------------------ part - id = "m325"; - desc = "ATMEGA325"; - signature = 0x1e 0x95 0x05; - has_jtag = yes; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -13374,188 +13374,188 @@ part #------------------------------------------------------------ part - id = "m645"; - desc = "ATMEGA645"; - signature = 0x1E 0x96 0x05; - has_jtag = yes; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -13563,188 +13563,188 @@ part #------------------------------------------------------------ part - id = "m3250"; - desc = "ATMEGA3250"; - signature = 0x1E 0x95 0x06; - has_jtag = yes; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -13752,188 +13752,188 @@ part #------------------------------------------------------------ part - id = "m6450"; - desc = "ATMEGA6450"; - signature = 0x1E 0x96 0x06; - has_jtag = yes; + 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"; - ; + 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"; + ; ; #------------------------------------------------------------ @@ -13941,96 +13941,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14038,96 +14038,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14135,96 +14135,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14232,96 +14232,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14329,96 +14329,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14426,96 +14426,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14523,96 +14523,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14620,96 +14620,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14717,96 +14717,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14814,96 +14814,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -14911,96 +14911,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -15008,96 +15008,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -15105,96 +15105,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -15202,96 +15202,96 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; @@ -15300,20 +15300,20 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; #------------------------------------------------------------ @@ -15321,38 +15321,38 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; @@ -15361,38 +15361,38 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; @@ -15401,38 +15401,38 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; @@ -15441,38 +15441,38 @@ part #------------------------------------------------------------ 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; - ; + 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; + ; ; From f2947b14f5cd584a1589768feceb65601ff71352 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 7 Jan 2024 03:17:28 -0500 Subject: [PATCH 035/109] remove comment (unused kill_screen) --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 2c381f2125a1..9b6f5a6fbf8d 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1810,15 +1810,6 @@ void MarlinUI::update() { dwinHandleScreen(); // Rotary encoder update } -// void MarlinUI::kill_screen(FSTR_P const error, FSTR_P const) { -// clearMainWindow(); -// drawPopupBkgd60(); -// dwinIconShow(ICON, ICON_TempTooHigh, 100, 105); -// dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, 20, 220, GET_TEXT_F(MSG_HALTED)); -// dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, 20, 220, error); -// dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, 20, 250, GET_TEXT_F(MSG_TURN_OFF)); -// } - void MarlinUI::refresh() { /* Nothing to see here */ } #if HAS_LCD_BRIGHTNESS From a59e0229e922883513ee5be8a45dabd660c394c9 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 8 Jan 2024 06:01:46 -0500 Subject: [PATCH 036/109] add M48 pause, return if error --- Marlin/src/gcode/calibrate/M48.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index cb74c990aabc..a7d804ed4ee6 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -58,7 +58,12 @@ void GcodeSuite::M48() { - if (homing_needed_error()) return; + #if ENABLED(DWIN_LCD_PROUI) + TERN_(ADVANCED_PAUSE_FEATURE, dwinPopupPause(GET_TEXT_F(MSG_M48_TEST));) + hmiSaveProcessID(ID_NothingToDo); + #endif + + if (homing_needed_error()) TERN(DWIN_LCD_PROUI, return hmiReturnScreen(), return); const int8_t verbose_level = parser.byteval('V', 1); if (!WITHIN(verbose_level, 0, 4)) { @@ -274,6 +279,8 @@ void GcodeSuite::M48() { TERN_(HAS_PTC, ptc.set_enabled(true)); report_current_position(); + + TERN_(DWIN_LCD_PROUI, hmiReturnScreen();) } #endif // Z_MIN_PROBE_REPEATABILITY_TEST From 39118d846c95cb01e492894ee18785ec2117b804 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 8 Jan 2024 06:48:22 -0500 Subject: [PATCH 037/109] removed because result = default --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 1ce6c253e8fb..22032baa773f 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1426,17 +1426,12 @@ void dwinHandleScreen() { case ID_SetIntNoDraw: hmiSetNoDraw(); break; case ID_PrintProcess: hmiPrinting(); break; case ID_Popup: hmiPopup(); break; - TERN_(HAS_BED_PROBE, case ID_Leveling: break;) TERN_(HAS_LOCKSCREEN, case ID_Locked: hmiLockScreen(); break;) TERN_(HAS_ESDIAG, case ID_ESDiagProcess:) TERN_(PROUI_ITEM_PLOT, case ID_PlotProcess:) case ID_PrintDone: case ID_WaitResponse: hmiWaitForUser(); break; - - case ID_Homing: - case ID_PIDProcess: - case ID_NothingToDo: default: break; } } From c79127b8814a34df018162e313afe931e2633ead Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 9 Jan 2024 04:24:15 -0500 Subject: [PATCH 038/109] no such ZHOME_BEFORE_LEVELING, removed --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 720c86769da4..5f1b24a1c677 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -306,7 +306,7 @@ void unified_bed_leveling::G29() { // Check for commands that require the printer to be homed if (may_move) { planner.synchronize(); - #if ALL(DWIN_LCD_PROUI, ZHOME_BEFORE_LEVELING) + #if ENABLED(DWIN_LCD_PROUI) save_ubl_active_state_and_disable(); gcode.process_subcommands_now(F("G28Z")); restore_ubl_active_state_and_leave(); From 7b618d666074e774ea0740b7307e6dbef3e612c5 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 9 Jan 2024 18:02:50 -0500 Subject: [PATCH 039/109] fix for redef, rename SDIO_ --- Marlin/src/HAL/STM32/inc/SanityCheck.h | 2 +- Marlin/src/HAL/STM32/sdio.h | 12 +++++------ Marlin/src/lcd/e3v2/common/dwin_api.cpp | 2 ++ Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h | 20 +++++++++---------- Marlin/src/pins/pinsDebug_list.h | 12 +++++------ 5 files changed, 25 insertions(+), 23 deletions(-) diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 80d0314dbbd4..faa8d6a7d8c2 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -60,7 +60,7 @@ */ #define _CHECK_SERIAL_PIN(N) (( \ BTN_EN1 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN0_PIN == N || \ - SDIO_D2_PIN == N || SDIO_D3_PIN == N || SDIO_CK_PIN == N || SDIO_CMD_PIN == N \ + BOARD_SDIO_D2 == N || BOARD_SDIO_D3 == N || BOARD_SDIO_CLK == N || BOARD_SDIO_CMD == N \ )) #define CHECK_SERIAL_PIN(T,N) defined(UART##N##_##T##_PIN) && _CHECK_SERIAL_PIN(UART##N##_##T##_PIN) #if SERIAL_IN_USE(1) diff --git a/Marlin/src/HAL/STM32/sdio.h b/Marlin/src/HAL/STM32/sdio.h index cf5539c3c76d..8e54c31439f1 100644 --- a/Marlin/src/HAL/STM32/sdio.h +++ b/Marlin/src/HAL/STM32/sdio.h @@ -21,9 +21,9 @@ */ #pragma once -#define SDIO_D0_PIN PC8 -#define SDIO_D1_PIN PC9 -#define SDIO_D2_PIN PC10 -#define SDIO_D3_PIN PC11 -#define SDIO_CK_PIN PC12 -#define SDIO_CMD_PIN PD2 +#define BOARD_SDIO_D0 PC8 +#define BOARD_SDIO_D1 PC9 +#define BOARD_SDIO_D2 PC10 +#define BOARD_SDIO_D3 PC11 +#define BOARD_SDIO_CLK PC12 +#define BOARD_SDIO_CMD PD2 diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index 4442b5847d58..3fcdb125772b 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -90,6 +90,7 @@ bool dwinHandshake() { } #endif +#if DISABLED(DWIN_LCD_PROUI) // Get font character width uint8_t fontWidth(uint8_t cfont) { switch (cfont) { @@ -123,6 +124,7 @@ uint8_t fontHeight(uint8_t cfont) { default: return 0; } } +#endif // Set screen display direction // dir: 0=0°, 1=90°, 2=180°, 3=270° diff --git a/Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h b/Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h index a477308277da..e6215be4fb7c 100644 --- a/Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h +++ b/Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h @@ -132,21 +132,21 @@ // SDIO // #define SDIO_READ_RETRIES 16 - #define SDIO_D0_PIN PC8 - #define SDIO_D1_PIN PC9 - #define SDIO_D2_PIN PC10 - #define SDIO_D3_PIN PC11 - #define SDIO_CK_PIN PC12 - #define SDIO_CMD_PIN PD2 + #define BOARD_SDIO_D0 PC8 + #define BOARD_SDIO_D1 PC9 + #define BOARD_SDIO_D2 PC10 + #define BOARD_SDIO_D3 PC11 + #define BOARD_SDIO_CLK PC12 + #define BOARD_SDIO_CMD PD2 #else #undef SDSS - #define SDSS PC11 // SDIO_D3_PIN + #define SDSS PC11 // BOARD_SDIO_D3 #define SS_PIN SDSS - #define SCK_PIN PC12 // SDIO_CK_PIN - #define MISO_PIN PC8 // SDIO_D0_PIN - #define MOSI_PIN PD2 // SDIO_CMD_PIN + #define SCK_PIN PC12 // BOARD_SDIO_CLK + #define MISO_PIN PC8 // BOARD_SDIO_D0 + #define MOSI_PIN PD2 // BOARD_SDIO_CMD #define SOFTWARE_SPI #endif diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index fa6cbf49b945..8760bc4b506c 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -2299,22 +2299,22 @@ // SDIO // #if PIN_EXISTS(SDIO_D0) - REPORT_NAME_DIGITAL(__LINE__, SDIO_D0_PIN) + REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D0) #endif #if PIN_EXISTS(SDIO_D1) - REPORT_NAME_DIGITAL(__LINE__, SDIO_D1_PIN) + REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D1) #endif #if PIN_EXISTS(SDIO_D2) - REPORT_NAME_DIGITAL(__LINE__, SDIO_D2_PIN) + REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D2) #endif #if PIN_EXISTS(SDIO_D3) - REPORT_NAME_DIGITAL(__LINE__, SDIO_D3_PIN) + REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D3) #endif #if PIN_EXISTS(SDIO_CK) - REPORT_NAME_DIGITAL(__LINE__, SDIO_CK_PIN) + REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_CLK) #endif #if PIN_EXISTS(SDIO_CMD) - REPORT_NAME_DIGITAL(__LINE__, SDIO_CMD_PIN) + REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_CMD) #endif // From 09a2aa3fed8b5e5b04e8614d49aacc587f9efaf2 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 9 Jan 2024 21:21:55 -0500 Subject: [PATCH 040/109] unused option for smooth encoder added left commented out, not recommended unless user rather have it enabled --- Marlin/src/lcd/e3v2/proui/dwin_defines.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 96ea7b2771be..d6087ee0c99d 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -109,3 +109,4 @@ #define HAS_ESDIAG 1 // View End-stop/Runout switch continuity #define HAS_LOCKSCREEN 1 // Simple lockscreen #define HAS_SD_EXTENDER 1 // Enable to support SD card extender cables +//#define SMOOTH_ENCODER_MENUITEMS // Menu items value faster/smooth change rate From db8daf92d55b0f502179053521613e8e3e2e38bc Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 9 Jan 2024 23:23:36 -0500 Subject: [PATCH 041/109] update dwin.cpp - add HAS_FLOW/FEEDRATE_EDIT rearrange layout --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 28 ++++++++++++++++++++-------- 1 file changed, 20 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 22032baa773f..b846526fc759 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2301,7 +2301,13 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, void setExtMinT() { setPIntOnClick(MIN_ETEMP, MAX_ETEMP, applyExtMinT); } #endif -void setSpeed() { setPIntOnClick(SPEED_EDIT_MIN, SPEED_EDIT_MAX); } +#if HAS_FEEDRATE_EDIT + void setSpeed() { setPIntOnClick(SPEED_EDIT_MIN, SPEED_EDIT_MAX); } +#endif + +#if HAS_FLOW_EDIT + void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(0); }); } +#endif #if HAS_HOTEND void applyHotendTemp() { thermalManager.setTargetHotend(menuData.value, 0); } @@ -2346,8 +2352,6 @@ void setSpeed() { setPIntOnClick(SPEED_EDIT_MIN, SPEED_EDIT_MAX); } #endif // ADVANCED_PAUSE_FEATURE -void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(0); }); } - // Bed Tramming #if ENABLED(LCD_BED_TRAMMING) @@ -3350,9 +3354,14 @@ void drawFilSetMenu() { void drawTuneMenu() { checkkey = ID_Menu; - if (SET_MENU_R(tuneMenu, selrect({73, 2, 28, 12}), MSG_TUNE, 20)) { + if (SET_MENU_R(tuneMenu, selrect({73, 2, 28, 12}), MSG_TUNE, 21)) { BACK_ITEM(gotoPrintProcess); - EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawSpeedItem, setSpeed, &feedrate_percentage); + #if HAS_FEEDRATE_EDIT + EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawSpeedItem, setSpeed, &feedrate_percentage); + #endif + #if HAS_FLOW_EDIT + EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]); + #endif #if HAS_HOTEND hotendTargetItem = EDIT_ITEM(ICON_HotendTemp, MSG_UBL_SET_TEMP_HOTEND, onDrawHotendTemp, setHotendTemp, &thermalManager.temp_hotend[0].target); #endif @@ -3367,7 +3376,6 @@ void drawTuneMenu() { #elif ALL(HAS_ZOFFSET_ITEM, MESH_BED_LEVELING, BABYSTEPPING) EDIT_ITEM(ICON_Zoffset, MSG_HOME_OFFSET_Z, onDrawPFloat2Menu, setZOffset, &BABY_Z_VAR); #endif - EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]); #if ENABLED(ADVANCED_PAUSE_FEATURE) MENU_ITEM(ICON_FilMan, MSG_FILAMENTCHANGE, onDrawMenuItem, changeFilament); #endif @@ -3516,8 +3524,12 @@ void drawMotionMenu() { EDIT_ITEM(ICON_UBLActive, MSG_STEP_SMOOTHING, onDrawChkbMenu, setAdaptiveStepSmoothing, &hmiData.adaptiveStepSmoothing); #endif MENU_ITEM(ICON_Step, MSG_STEPS_PER_MM, onDrawSteps, drawStepsMenu); - EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]); - EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawPIntMenu, setSpeed, &feedrate_percentage); + #if HAS_FEEDRATE_EDIT + EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawPIntMenu, setSpeed, &feedrate_percentage); + #endif + #if HAS_FLOW_EDIT + EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]); + #endif } updateMenu(motionMenu); } From cedf465935a94ba3222226c96bae321e091c0487 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 10 Jan 2024 01:16:39 -0500 Subject: [PATCH 042/109] remove space --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index b846526fc759..2f663d519f95 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1877,7 +1877,7 @@ void dwinInitScreen() { void MarlinUI::update() { hmiSDCardUpdate(); // SD card update - eachMomentUpdate(); // Status update + eachMomentUpdate(); // Status update dwinHandleScreen(); // Rotary encoder update } From 3b399ea84063f645d553214c67bfde9f57d4f1f3 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 11 Jan 2024 05:11:40 -0500 Subject: [PATCH 043/109] fix for error, fontWidth/Height not used by these UI --- Marlin/src/lcd/e3v2/common/dwin_api.cpp | 66 ++++++++++++------------- 1 file changed, 33 insertions(+), 33 deletions(-) diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index 3fcdb125772b..32736b40b984 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -90,40 +90,40 @@ bool dwinHandshake() { } #endif -#if DISABLED(DWIN_LCD_PROUI) -// Get font character width -uint8_t fontWidth(uint8_t cfont) { - switch (cfont) { - case font6x12 : return 6; - case font8x16 : return 8; - case font10x20: return 10; - case font12x24: return 12; - case font14x28: return 14; - case font16x32: return 16; - case font20x40: return 20; - case font24x48: return 24; - case font28x56: return 28; - case font32x64: return 32; - default: return 0; +#if NONE(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, IS_DWIN_MARLINUI) + // Get font character width + uint8_t fontWidth(uint8_t cfont) { + switch (cfont) { + case font6x12 : return 6; + case font8x16 : return 8; + case font10x20: return 10; + case font12x24: return 12; + case font14x28: return 14; + case font16x32: return 16; + case font20x40: return 20; + case font24x48: return 24; + case font28x56: return 28; + case font32x64: return 32; + default: return 0; + } } -} -// Get font character height -uint8_t fontHeight(uint8_t cfont) { - switch (cfont) { - case font6x12 : return 12; - case font8x16 : return 16; - case font10x20: return 20; - case font12x24: return 24; - case font14x28: return 28; - case font16x32: return 32; - case font20x40: return 40; - case font24x48: return 48; - case font28x56: return 56; - case font32x64: return 64; - default: return 0; + // Get font character height + uint8_t fontHeight(uint8_t cfont) { + switch (cfont) { + case font6x12 : return 12; + case font8x16 : return 16; + case font10x20: return 20; + case font12x24: return 24; + case font14x28: return 28; + case font16x32: return 32; + case font20x40: return 40; + case font24x48: return 48; + case font28x56: return 56; + case font32x64: return 64; + default: return 0; + } } -} #endif // Set screen display direction @@ -268,7 +268,7 @@ void dwinDrawString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, u void dwinDrawIntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint32_t value) { size_t i = 0; - #if DISABLED(DWIN_CREALITY_LCD_JYERSUI) + #if NONE(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, IS_DWIN_MARLINUI) dwinDrawRectangle(1, bColor, x, y, x + fontWidth(size) * iNum + 1, y + fontHeight(size)); #endif dwinByte(i, 0x14); @@ -318,7 +318,7 @@ void dwinDrawFloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, int32_t value) { //uint8_t *fvalue = (uint8_t*)&value; size_t i = 0; - #if DISABLED(DWIN_CREALITY_LCD_JYERSUI) + #if NONE(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, IS_DWIN_MARLINUI) dwinDrawRectangle(1, bColor, x, y, x + fontWidth(size) * (iNum + fNum + 1), y + fontHeight(size)); #endif dwinByte(i, 0x14); From b527e506c545bc4b62e1fc2d18315e02c65b12ce Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 11 Jan 2024 07:44:39 -0500 Subject: [PATCH 044/109] update print progress --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 30 +++++++++++++----------------- 1 file changed, 13 insertions(+), 17 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index b81f55c8b8d6..f8f5cf28edd6 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -552,26 +552,26 @@ void drawPrintLabels() { } } +static uint8_t _percent_done = 242; void drawPrintProgressBar() { - const uint8_t _percent_done = ui.get_progress_percent(); DWINUI::drawIconWB(ICON_Bar, 15, 93); - dwinDrawRectangle(1, hmiData.colorBarfill, 16 + _percent_done * 240 / 100, 93, 256, 113); + dwinDrawRectangle(1, hmiData.colorBarfill, 15 + (_percent_done * 242) / 100, 93, 257, 113); DWINUI::drawInt(hmiData.colorPercentTxt, hmiData.colorBackground, 3, 117, 133, _percent_done); DWINUI::drawString(hmiData.colorPercentTxt, 142, 133, F("%")); } +duration_t _printtime = print_job_timer.duration(); void drawPrintProgressElapsed() { - MString<12> buf; - duration_t elapsed = print_job_timer.duration(); // Print timer - buf.setf(F("%02i:%02i "), uint16_t(elapsed.value / 3600), (uint16_t(elapsed.value) % 3600) / 60); + MString<14> buf; + buf.setf(F("%02i:%02i "), uint16_t(_printtime.hour()), uint16_t(_printtime.minute())); DWINUI::drawString(hmiData.colorText, hmiData.colorBackground, 47, 192, buf); } #if ENABLED(SHOW_REMAINING_TIME) - uint32_t _remain_time = 0; + duration_t _remain_time = 0; void drawPrintProgressRemain() { - MString<12> buf; - buf.setf(F("%02i:%02i "), _remain_time / 3600, (_remain_time % 3600) / 60); + MString<14> buf; + buf.setf(F("%02i:%02i "), uint16_t(_remain_time.hour()), uint16_t(_remain_time.minute())); DWINUI::drawString(hmiData.colorText, hmiData.colorBackground, 181, 192, buf); } #endif @@ -1336,11 +1336,8 @@ void eachMomentUpdate() { if (checkkey == ID_PrintProcess) { // Print process // Progress percent - static uint8_t _percent_done = 255; - if (_percent_done != ui.get_progress_percent()) { - _percent_done = ui.get_progress_percent(); - drawPrintProgressBar(); - } + _percent_done = card.percentDone(); + drawPrintProgressBar(); // Remaining time #if ENABLED(SHOW_REMAINING_TIME) @@ -1351,10 +1348,9 @@ void eachMomentUpdate() { #endif // Elapsed print time - static uint16_t _printtime = 0; - const uint16_t min = (print_job_timer.duration() % 3600) / 60; - if (_printtime != min) { // 1 minute update - _printtime = min; + const uint16_t min = print_job_timer.duration(); + if (_printtime.minute() + 1 <= min) { // 1 minute update + _printtime.value = min; drawPrintProgressElapsed(); } } From bd80dd0282deaeee06e7911f3a90210b8137422e Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 13 Jan 2024 15:15:45 -0500 Subject: [PATCH 045/109] update print progress - simplify --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 26 +++++++++++++++----------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index f8f5cf28edd6..947c73400e4c 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -40,6 +40,7 @@ #include "../../../MarlinCore.h" #include "../../../core/serial.h" #include "../../../core/macros.h" +#include "../../../libs/numtostr.h" #include "../../../module/temperature.h" #include "../../../module/printcounter.h" #include "../../../module/motion.h" @@ -552,26 +553,27 @@ void drawPrintLabels() { } } -static uint8_t _percent_done = 242; +static uint8_t _percent_done = 100; void drawPrintProgressBar() { DWINUI::drawIconWB(ICON_Bar, 15, 93); dwinDrawRectangle(1, hmiData.colorBarfill, 15 + (_percent_done * 242) / 100, 93, 257, 113); - DWINUI::drawInt(hmiData.colorPercentTxt, hmiData.colorBackground, 3, 117, 133, _percent_done); - DWINUI::drawString(hmiData.colorPercentTxt, 142, 133, F("%")); + DWINUI::drawString(hmiData.colorPercentTxt, hmiData.colorBackground, 117, 133, pcttostrpctrj(_percent_done)); } duration_t _printtime = print_job_timer.duration(); void drawPrintProgressElapsed() { - MString<14> buf; - buf.setf(F("%02i:%02i "), uint16_t(_printtime.hour()), uint16_t(_printtime.minute())); - DWINUI::drawString(hmiData.colorText, hmiData.colorBackground, 47, 192, buf); + char buf[10]; + const bool has_days = (_printtime.value > 60*60*24L); + _printtime.toDigital(buf, has_days); + DWINUI::drawString(hmiData.colorText, hmiData.colorBackground, 56, 192, buf); } #if ENABLED(SHOW_REMAINING_TIME) duration_t _remain_time = 0; void drawPrintProgressRemain() { - MString<14> buf; - buf.setf(F("%02i:%02i "), uint16_t(_remain_time.hour()), uint16_t(_remain_time.minute())); + char buf[10]; + const bool has_days = (_remain_time.value > 60*60*24L); + _remain_time.toDigital(buf, has_days); DWINUI::drawString(hmiData.colorText, hmiData.colorBackground, 181, 192, buf); } #endif @@ -1336,8 +1338,10 @@ void eachMomentUpdate() { if (checkkey == ID_PrintProcess) { // Print process // Progress percent - _percent_done = card.percentDone(); - drawPrintProgressBar(); + if (_percent_done != card.percentDone()) { + _percent_done = card.percentDone(); + drawPrintProgressBar(); + } // Remaining time #if ENABLED(SHOW_REMAINING_TIME) @@ -1360,8 +1364,8 @@ void eachMomentUpdate() { } #endif - dwinUpdateLCD(); } + dwinUpdateLCD(); } #if ENABLED(POWER_LOSS_RECOVERY) From 3a4438b1da8539bbadb34a1a622fdea22e647427 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 14 Jan 2024 10:51:21 -0500 Subject: [PATCH 046/109] update ProgressElapsed --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 947c73400e4c..92802d55d218 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -565,7 +565,7 @@ void drawPrintProgressElapsed() { char buf[10]; const bool has_days = (_printtime.value > 60*60*24L); _printtime.toDigital(buf, has_days); - DWINUI::drawString(hmiData.colorText, hmiData.colorBackground, 56, 192, buf); + DWINUI::drawString(hmiData.colorText, hmiData.colorBackground, 45, 192, buf); } #if ENABLED(SHOW_REMAINING_TIME) From c76f337198c3e493b5382e48aed9098abf953788 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 16 Jan 2024 01:14:48 -0500 Subject: [PATCH 047/109] update dwin.cpp, bedleveltools --- Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp | 27 +++----- Marlin/src/lcd/e3v2/proui/bedlevel_tools.h | 4 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 68 +++++++++++--------- 3 files changed, 48 insertions(+), 51 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index 5cecac1e930e..c627b6573a13 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -77,14 +77,6 @@ bool drawing_mesh = false; #if ENABLED(AUTO_BED_LEVELING_UBL) - void BedLevelTools::manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y, bool undefined/*=false*/) { - MString cmd; - cmd.set(F("M421 I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)); - if (undefined) cmd += F(" N"); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - } - bool BedLevelTools::createPlaneFromMesh() { struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); @@ -124,17 +116,18 @@ bool drawing_mesh = false; return false; } -#else - - void BedLevelTools::manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y) { - gcode.process_subcommands_now( - TS(F("G29 I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)) - ); - planner.synchronize(); - } - #endif +void BedLevelTools::manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y, bool reset/*=false*/) { + float zval; + if (reset) { zval = 0; } + else { zval = current_position.z; } + gcode.process_subcommands_now( + TS(F(TERN(AUTO_BED_LEVELING_UBL, "M421 I", "G29 I")), mesh_x, 'J', mesh_y, 'Z', p_float_t(zval, 3)) + ); + planner.synchronize(); +} + void BedLevelTools::manualMove(const uint8_t mesh_x, const uint8_t mesh_y, bool zmove/*=false*/) { gcode.process_subcommands_now(F("G28O")); if (zmove) { diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h index 6e568e32b51e..15da2fa62b1d 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h @@ -58,11 +58,9 @@ class BedLevelTools { static uint8_t tilt_grid; #if ENABLED(AUTO_BED_LEVELING_UBL) - static void manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y, bool undefined=false); static bool createPlaneFromMesh(); - #else - static void manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y); #endif + static void manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y, bool reset=false); static void manualMove(const uint8_t mesh_x, const uint8_t mesh_y, bool zmove=false); static void moveToXYZ(); static void moveToXY(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 92802d55d218..cf98239bbd50 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -198,7 +198,7 @@ typedef struct { select_t select_page{0}, select_print{0}; #if ENABLED(LCD_BED_TRAMMING) - constexpr float bed_tramming_inset_lfbr[] = BED_TRAMMING_INSET_LFRB; + constexpr float lfrb[] = BED_TRAMMING_INSET_LFRB; #endif bool hash_changed = true; // Flag to know if message status was changed @@ -973,7 +973,7 @@ void onClickSDItem() { } else if ((selected >= 1 + hasUpDir) && (shift_len > MENU_CHAR_LIMIT)) { uint8_t shift_new = _MIN(shift_amt + 1, shift_len - MENU_CHAR_LIMIT); // Try to shift by... - drawSDItemShifted(shift_new); // Draw the item + drawSDItemShifted(shift_new); // Draw the item if (shift_new == shift_amt) // Scroll reached the end shift_new = -1; // Reset shift_amt = shift_new; // Set new scroll @@ -989,7 +989,7 @@ void onClickSDItem() { void onDrawFileName(MenuItem* menuitem, int8_t line) { const bool is_subdir = !card.flag.workDirIsRoot; if (is_subdir && menuitem->pos == 1) { - drawMenuLine(line, ICON_Folder, ".."); + drawMenuLine(line, ICON_ReadEEPROM, ".. Back"); } else { uint8_t icon; @@ -1004,7 +1004,7 @@ void drawPrintFileMenu() { checkkey = ID_Menu; if (card.isMounted()) { if (SET_MENU(fileMenu, MSG_MEDIA_MENU, nr_sd_menu_items() + 1)) { - BACK_ITEM(gotoMainMenu); + menuItemAdd(ICON_Back, F("Exit to Main Menu"), onDrawMenuItem, gotoMainMenu); for (uint8_t i = 0; i < nr_sd_menu_items(); ++i) menuItemAdd(onDrawFileName, onClickSDItem); } @@ -2037,6 +2037,7 @@ void gotoConfirmToPrint() { void writeEEPROM() { dwinDrawStatusLine(GET_TEXT_F(MSG_STORE_EEPROM)); + safe_delay(500); dwinUpdateLCD(); DONE_BUZZ(settings.save()); } @@ -2054,7 +2055,10 @@ void gotoConfirmToPrint() { } #if HAS_MESH - void saveMesh() { TERN(AUTO_BED_LEVELING_UBL, ublMeshSave(), writeEEPROM()); } + void saveMesh() { + TERN_(MESH_BED_LEVELING, manualMeshSave();) + TERN(AUTO_BED_LEVELING_UBL, ublMeshSave(), writeEEPROM()); + } #endif #endif // EEPROM_SETTINGS @@ -2360,28 +2364,29 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, switch (point) { case 0: LCD_MESSAGE(MSG_TRAM_FL); - x = bed_tramming_inset_lfbr[0]; - y = bed_tramming_inset_lfbr[1]; + x = lfrb[0]; + y = lfrb[1]; break; case 1: LCD_MESSAGE(MSG_TRAM_FR); - x = X_BED_SIZE - bed_tramming_inset_lfbr[2]; - y = bed_tramming_inset_lfbr[1]; + x = X_BED_SIZE - lfrb[2]; + y = lfrb[1]; break; case 2: LCD_MESSAGE(MSG_TRAM_BR); - x = X_BED_SIZE - bed_tramming_inset_lfbr[2]; - y = Y_BED_SIZE - bed_tramming_inset_lfbr[3]; + x = X_BED_SIZE - lfrb[2]; + y = Y_BED_SIZE - lfrb[3]; break; case 3: LCD_MESSAGE(MSG_TRAM_BL); - x = bed_tramming_inset_lfbr[0]; - y = Y_BED_SIZE - bed_tramming_inset_lfbr[3]; + x = lfrb[0]; + y = Y_BED_SIZE - lfrb[3]; break; #if ENABLED(BED_TRAMMING_INCLUDE_CENTER) case 4: LCD_MESSAGE(MSG_TRAM_C); - x = X_CENTER; y = Y_CENTER; + x = X_CENTER; + y = Y_CENTER; break; #endif } @@ -2443,15 +2448,20 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, #endif - #if ALL(HAS_BED_PROBE, HAS_MESH, HAS_TRAMMING_WIZARD) + #if HAS_TRAMMING_WIZARD void trammingwizard() { if (hmiData.fullManualTramming) { LCD_MESSAGE_F("Disable manual tramming"); return; } + else LCD_MESSAGE_F("Tramming Wizard Start"); + DWINUI::clearMainArea(); + meshViewer.drawMeshGrid(2, 2); // Indicate start. Draw the grid bed_mesh_t zval = {0}; + probe.stow(); zval[0][0] = tram(0); + if (checkkey == ID_Homing) meshViewer.drawMeshGrid(2, 2); // Redraw if Homing checkkey = ID_NothingToDo; meshViewer.drawMesh(zval, 2, 2); zval[1][0] = tram(1); @@ -2459,6 +2469,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, zval[1][1] = tram(2); meshViewer.drawMesh(zval, 2, 2); zval[0][1] = tram(3); + probe.stow(); meshViewer.drawMesh(zval, 2, 2); DWINUI::drawCenteredString(140, F("Calculating average")); @@ -2472,16 +2483,17 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, ui.reset_status(); #ifndef BED_TRAMMING_PROBE_TOLERANCE - #define BED_TRAMMING_PROBE_TOLERANCE 0.05 + #define BED_TRAMMING_PROBE_TOLERANCE 0.05f #endif if (ABS(meshViewer.max - meshViewer.min) < BED_TRAMMING_PROBE_TOLERANCE) { + EXIT_TRAMWIZ: DWINUI::drawCenteredString(140, F("Corners leveled")); DWINUI::drawCenteredString(160, F("Tolerance achieved!")); } else { uint8_t p = 0; - float max = 0; + float max = 0.0f; FSTR_P plabel; bool s = true; for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) { @@ -2491,6 +2503,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, max = d; p = x + 2 * y; } + else { goto EXIT_TRAMWIZ; } // fail-safe if Corners are = 0.00 } switch (p) { case 0b00 : plabel = GET_TEXT_F(MSG_TRAM_FL); break; @@ -2501,7 +2514,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, } DWINUI::drawCenteredString(120, F("Corners not leveled")); DWINUI::drawCenteredString(140, F("Knob adjustment required")); - DWINUI::drawCenteredString(COLOR_GREEN, 160, s ? F("Lower") : F("Raise")); + DWINUI::drawCenteredString((s ? COLOR_GREEN : COLOR_ERROR_RED), 160, (s ? F("Lower") : F("Raise"))); DWINUI::drawCenteredString(COLOR_GREEN, 180, plabel); } DWINUI::drawButton(BTN_Continue, 86, 305); @@ -2544,7 +2557,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, void manualMeshSave() { LCD_MESSAGE(MSG_UBL_STORAGE_MESH_MENU); - queue.inject(F("M211S1\nM500")); + queue.inject(F("M211S1")); } #endif // MESH_BED_LEVELING @@ -3581,7 +3594,7 @@ void drawFilamentManMenu() { mMeshMoveZItem = EDIT_ITEM(ICON_Zoffset, MSG_MOVE_Z, onDrawMMeshMoveZ, setMMeshMoveZ, ¤t_position.z); MENU_ITEM(ICON_Axis, MSG_UBL_CONTINUE_MESH, onDrawMenuItem, manualMeshContinue); MENU_ITEM(ICON_MeshViewer, MSG_MESH_VIEW, onDrawSubMenu, dwinMeshViewer); - MENU_ITEM(ICON_MeshSave, MSG_UBL_SAVE_MESH, onDrawMenuItem, manualMeshSave); + MENU_ITEM(ICON_MeshSave, MSG_UBL_SAVE_MESH, onDrawMenuItem, saveMesh); } updateMenu(manualMeshMenu); } @@ -4026,23 +4039,16 @@ void drawMaxAccelMenu() { #endif #if ENABLED(PROUI_MESH_EDIT) - void manualResetValue() { - gcode.process_subcommands_now( - TS(F("M421I"), bedLevelTools.mesh_x, 'J', bedLevelTools.mesh_y, 'Z', p_float_t(0, 3)) - ); - planner.synchronize(); - } - bool autoMovToMesh = false; void setAutoMovToMesh() { toggleCheckboxLine(autoMovToMesh); } void liveEditMesh() { ((MenuItemPtr*)editZValueItem)->value = &bedlevel.z_values[hmiValue.select ? bedLevelTools.mesh_x : menuData.value][hmiValue.select ? menuData.value : bedLevelTools.mesh_y]; editZValueItem->redraw(); } + void liveEditMeshZ() { *menuData.floatPtr = menuData.value / POW(10, 2); if (autoMovToMesh) bedLevelTools.moveToZ(); } void applyEditMeshX() { bedLevelTools.mesh_x = menuData.value; if (autoMovToMesh) bedLevelTools.moveToXY(); } void applyEditMeshY() { bedLevelTools.mesh_y = menuData.value; if (autoMovToMesh) bedLevelTools.moveToXY(); } - void zeroMesh() { manualResetValue(); editZValueItem->redraw(); LCD_MESSAGE(MSG_MESH_RESET); } + void zeroPoint() { bedLevelTools.manualValueUpdate(bedLevelTools.mesh_x, bedLevelTools.mesh_y, true); editZValueItem->redraw(); LCD_MESSAGE_F("Zero Current Point"); } void setEditMeshX() { hmiValue.select = 0; setIntOnClick(0, GRID_MAX_POINTS_X - 1, bedLevelTools.mesh_x, applyEditMeshX, liveEditMesh); } void setEditMeshY() { hmiValue.select = 1; setIntOnClick(0, GRID_MAX_POINTS_Y - 1, bedLevelTools.mesh_y, applyEditMeshY, liveEditMesh); } - void liveEditMeshZ() { *menuData.floatPtr = menuData.value / POW(10, 2); if (autoMovToMesh) bedLevelTools.moveToZ(); } void setEditZValue() { setPFloatOnClick(Z_OFFSET_MIN, Z_OFFSET_MAX, 3, nullptr, liveEditMeshZ); if (autoMovToMesh) bedLevelTools.moveToXYZ(); } #endif @@ -4106,7 +4112,7 @@ void drawMaxAccelMenu() { #endif #if ENABLED(AUTO_BED_LEVELING_UBL) EDIT_ITEM(ICON_UBLSlot, MSG_UBL_STORAGE_SLOT, onDrawUBLSlot, setUBLSlot, &bedlevel.storage_slot); - MENU_ITEM(ICON_UBLMeshSave, MSG_UBL_SAVE_MESH, onDrawMenuItem, ublMeshSave); + MENU_ITEM(ICON_UBLMeshSave, MSG_UBL_SAVE_MESH, onDrawMenuItem, saveMesh); MENU_ITEM(ICON_UBLMeshLoad, MSG_UBL_LOAD_MESH, onDrawMenuItem, ublMeshLoad); EDIT_ITEM(ICON_UBLTiltGrid, MSG_UBL_TILTING_GRID, onDrawPInt8Menu, setUBLTiltGrid, &bedLevelTools.tilt_grid); MENU_ITEM(ICON_UBLTiltGrid, MSG_UBL_TILT_MESH, onDrawMenuItem, ublMeshTilt); @@ -4136,7 +4142,7 @@ void drawMaxAccelMenu() { #if HAS_BED_PROBE MENU_ITEM_F(ICON_ProbeDeploy, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY); #endif - MENU_ITEM_F(ICON_SetZOffset, "Zero Current Point", onDrawMenuItem, zeroMesh); + MENU_ITEM_F(ICON_SetZOffset, "Zero Current Point", onDrawMenuItem, zeroPoint); } updateMenu(editMeshMenu); } From b2ddf104f1b37ab1de7a505af594f6046b18e1b2 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 18 Jan 2024 06:41:09 -0500 Subject: [PATCH 048/109] add to pinsDebug_list.h --- Marlin/src/HAL/STM32/inc/SanityCheck.h | 2 +- Marlin/src/HAL/STM32/sdio.h | 12 ++++++------ Marlin/src/pins/pinsDebug_list.h | 15 +++++++++++++++ 3 files changed, 22 insertions(+), 7 deletions(-) diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index faa8d6a7d8c2..80d0314dbbd4 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -60,7 +60,7 @@ */ #define _CHECK_SERIAL_PIN(N) (( \ BTN_EN1 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN0_PIN == N || \ - BOARD_SDIO_D2 == N || BOARD_SDIO_D3 == N || BOARD_SDIO_CLK == N || BOARD_SDIO_CMD == N \ + SDIO_D2_PIN == N || SDIO_D3_PIN == N || SDIO_CK_PIN == N || SDIO_CMD_PIN == N \ )) #define CHECK_SERIAL_PIN(T,N) defined(UART##N##_##T##_PIN) && _CHECK_SERIAL_PIN(UART##N##_##T##_PIN) #if SERIAL_IN_USE(1) diff --git a/Marlin/src/HAL/STM32/sdio.h b/Marlin/src/HAL/STM32/sdio.h index 8e54c31439f1..cf5539c3c76d 100644 --- a/Marlin/src/HAL/STM32/sdio.h +++ b/Marlin/src/HAL/STM32/sdio.h @@ -21,9 +21,9 @@ */ #pragma once -#define BOARD_SDIO_D0 PC8 -#define BOARD_SDIO_D1 PC9 -#define BOARD_SDIO_D2 PC10 -#define BOARD_SDIO_D3 PC11 -#define BOARD_SDIO_CLK PC12 -#define BOARD_SDIO_CMD PD2 +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 8760bc4b506c..f0fa7763816d 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -2299,23 +2299,38 @@ // SDIO // #if PIN_EXISTS(SDIO_D0) + REPORT_NAME_DIGITAL(__LINE__, SDIO_D0_PIN) +#elif defined(BOARD_SDIO_D0) REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D0) #endif #if PIN_EXISTS(SDIO_D1) + REPORT_NAME_DIGITAL(__LINE__, SDIO_D1_PIN) +#elif defined(BOARD_SDIO_D1) REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D1) #endif #if PIN_EXISTS(SDIO_D2) + REPORT_NAME_DIGITAL(__LINE__, SDIO_D2_PIN) +#elif defined(BOARD_SDIO_D2) REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D2) #endif #if PIN_EXISTS(SDIO_D3) + REPORT_NAME_DIGITAL(__LINE__, SDIO_D3_PIN) +#elif defined(BOARD_SDIO_D3) REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D3) #endif #if PIN_EXISTS(SDIO_CK) + REPORT_NAME_DIGITAL(__LINE__, SDIO_CK_PIN) +#elif defined(BOARD_SDIO_CLK) REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_CLK) #endif #if PIN_EXISTS(SDIO_CMD) + REPORT_NAME_DIGITAL(__LINE__, SDIO_CMD_PIN) +#elif defined(BOARD_SDIO_CMD) REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_CMD) #endif +#if defined(BOARD_SDIO_DET) + REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_DET) +#endif // // Miscellaneous From add7886f3f331831ebcd185a9754fbfad2d81580 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 19 Jan 2024 02:16:21 -0500 Subject: [PATCH 049/109] move dwinIconShow to dwin_lcd.h, replace dwinPopupConfirm w/ dwinPopupContinue, rename ICON_* functions --- Marlin/src/gcode/lcd/M0_M1.cpp | 4 +- Marlin/src/lcd/e3v2/common/dwin_api.h | 6 -- Marlin/src/lcd/e3v2/creality/dwin_lcd.h | 6 ++ Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h | 6 ++ Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h | 6 ++ Marlin/src/lcd/e3v2/proui/dwin.cpp | 132 ++++++++++++------------ Marlin/src/lcd/e3v2/proui/dwin.h | 3 + Marlin/src/lcd/e3v2/proui/dwin_popup.h | 8 -- Marlin/src/module/probe.cpp | 2 +- 9 files changed, 91 insertions(+), 82 deletions(-) diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index fcab61b59d92..2a2538c0b305 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -73,9 +73,9 @@ void GcodeSuite::M0_M1() { ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_USERWAIT)); #elif ENABLED(DWIN_LCD_PROUI) if (parser.string_arg) - dwinPopupConfirm(ICON_BLTouch, parser.string_arg, GET_TEXT_F(MSG_USERWAIT)); + dwinPopupContinue(ICON_BLTouch, parser.string_arg, GET_TEXT_F(MSG_USERWAIT)); else - dwinPopupConfirm(ICON_BLTouch, GET_TEXT_F(MSG_STOPPED), GET_TEXT_F(MSG_USERWAIT)); + dwinPopupContinue(ICON_BLTouch, GET_TEXT_F(MSG_STOPPED), GET_TEXT_F(MSG_USERWAIT)); #else if (parser.string_arg) { diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h index f2392af55cdb..759fdbbd56ba 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -223,12 +223,6 @@ void dwinDrawFloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t // id: Picture ID void dwinJPGShowAndCache(const uint8_t id); -// Draw an Icon -// libID: Icon library ID -// picID: Icon ID -// x/y: Upper-left point -void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); - // Draw an Icon // IBD: The icon background display: 0=Background filtering is not displayed, 1=Background display \\When setting the background filtering not to display, the background must be pure black // BIR: Background image restoration: 0=Background image is not restored, 1=Automatically use virtual display area image for background restoration diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h index b60fe2970d66..f1610a06db2f 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h @@ -45,3 +45,9 @@ // xEnd/yEnd: Lower-right of virtual area // x/y: Screen paste point void dwinFrameAreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); \ No newline at end of file diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h index a9335a4f23f1..27463cc913cc 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h @@ -32,3 +32,9 @@ // color: color // x/y: Upper-left coordinate of the first pixel void dwinDrawDegreeSymbol(uint16_t color, uint16_t x, uint16_t y); + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); \ No newline at end of file diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h index dc6c79bd2d0e..16d0abf4a2b5 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h @@ -30,6 +30,12 @@ #include "../common/dwin_api.h" +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); + // Picture ID #define DWIN_Boot_Horiz 0 #define DWIN_Boot_Vert 1 diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index cf98239bbd50..5766a6572350 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -159,12 +159,7 @@ #define DWIN_VAR_UPDATE_INTERVAL 500 #define DWIN_UPDATE_INTERVAL 1000 -#if HAS_MESH && HAS_BED_PROBE - #define BABY_Z_VAR probe.offset.z -#else - float z_offset = 0; - #define BABY_Z_VAR z_offset -#endif +#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, hmiData.manualZOffset) #define _OFFSET_ZMIN TERN(HAS_BED_PROBE, PROBE_OFFSET_ZMIN, -20) #define _OFFSET_ZMAX TERN(HAS_BED_PROBE, PROBE_OFFSET_ZMAX, 20) @@ -318,7 +313,7 @@ void hmiToggleLanguage() { typedef struct { uint16_t x, y[2], w, h; } text_info_t; -void ICON_Button(const bool selected, const int iconid, const frame_rect_t &ico, const text_info_t (&txt), FSTR_P caption) { +void iconButton(const bool selected, const int iconid, const frame_rect_t &ico, const text_info_t (&txt), FSTR_P caption) { DWINUI::drawIconWB(iconid + selected, ico.x, ico.y); if (selected) DWINUI::drawBox(0, hmiData.colorHighlight, ico); if (hmiIsChinese()) { @@ -334,73 +329,73 @@ void ICON_Button(const bool selected, const int iconid, const frame_rect_t &ico, // // Main Menu: "Print" // -void ICON_Print() { +void iconPrint() { constexpr frame_rect_t ico = { 17, 110, 110, 100 }; constexpr text_info_t txt = { 1, { 405, 447 }, 27, 15 }; - ICON_Button(select_page.now == PAGE_PRINT, ICON_Print_0, ico, txt, GET_TEXT_F(MSG_BUTTON_PRINT)); + iconButton(select_page.now == PAGE_PRINT, ICON_Print_0, ico, txt, GET_TEXT_F(MSG_BUTTON_PRINT)); } // // Main Menu: "Prepare" // -void ICON_Prepare() { +void iconPrepare() { constexpr frame_rect_t ico = { 145, 110, 110, 100 }; constexpr text_info_t txt = { 31, { 405, 447 }, 27, 15 }; - ICON_Button(select_page.now == PAGE_PREPARE, ICON_Prepare_0, ico, txt, GET_TEXT_F(MSG_PREPARE)); + iconButton(select_page.now == PAGE_PREPARE, ICON_Prepare_0, ico, txt, GET_TEXT_F(MSG_PREPARE)); } // // Main Menu: "Control" // -void ICON_Control() { +void iconControl() { constexpr frame_rect_t ico = { 17, 226, 110, 100 }; constexpr text_info_t txt = { 61, { 405, 447 }, 27, 15 }; - ICON_Button(select_page.now == PAGE_CONTROL, ICON_Control_0, ico, txt, GET_TEXT_F(MSG_CONTROL)); + iconButton(select_page.now == PAGE_CONTROL, ICON_Control_0, ico, txt, GET_TEXT_F(MSG_CONTROL)); } // // Main Menu: "Advanced Settings" // -void ICON_AdvSettings() { +void iconAdvSettings() { constexpr frame_rect_t ico = { 145, 226, 110, 100 }; constexpr text_info_t txt = { 91, { 405, 447 }, 27, 15 }; - ICON_Button(select_page.now == PAGE_ADVANCE, ICON_Info_0, ico, txt, GET_TEXT_F(MSG_BUTTON_ADVANCED)); + iconButton(select_page.now == PAGE_ADVANCE, ICON_Info_0, ico, txt, GET_TEXT_F(MSG_BUTTON_ADVANCED)); } // // Printing: "Tune" // -void ICON_Tune() { +void iconTune() { constexpr frame_rect_t ico = { 8, 232, 80, 100 }; constexpr text_info_t txt = { 121, { 405, 447 }, 27, 15 }; - ICON_Button(select_print.now == PRINT_SETUP, ICON_Setup_0, ico, txt, GET_TEXT_F(MSG_TUNE)); + iconButton(select_print.now == PRINT_SETUP, ICON_Setup_0, ico, txt, GET_TEXT_F(MSG_TUNE)); } // // Printing: "Pause" // -void ICON_Pause() { +void iconPause() { constexpr frame_rect_t ico = { 96, 232, 80, 100 }; constexpr text_info_t txt = { 181, { 405, 447 }, 27, 15 }; - ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Pause_0, ico, txt, GET_TEXT_F(MSG_BUTTON_PAUSE)); + iconButton(select_print.now == PRINT_PAUSE_RESUME, ICON_Pause_0, ico, txt, GET_TEXT_F(MSG_BUTTON_PAUSE)); } // // Printing: "Resume" // -void ICON_Resume() { +void iconResume() { constexpr frame_rect_t ico = { 96, 232, 80, 100 }; constexpr text_info_t txt = { 1, { 405, 447 }, 27, 15 }; - ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Continue_0, ico, txt, GET_TEXT_F(MSG_BUTTON_RESUME)); + iconButton(select_print.now == PRINT_PAUSE_RESUME, ICON_Continue_0, ico, txt, GET_TEXT_F(MSG_BUTTON_RESUME)); } // // Printing: "Stop" // -void ICON_Stop() { +void iconStop() { constexpr frame_rect_t ico = { 184, 232, 80, 100 }; constexpr text_info_t txt = { 151, { 405, 447 }, 27, 12 }; - ICON_Button(select_print.now == PRINT_STOP, ICON_Stop_0, ico, txt, GET_TEXT_F(MSG_BUTTON_STOP)); + iconButton(select_print.now == PRINT_STOP, ICON_Stop_0, ico, txt, GET_TEXT_F(MSG_BUTTON_STOP)); } // @@ -436,7 +431,7 @@ void popupPauseOrStop() { dwinUpdateLCD(); } else - dwinPopupConfirm(ICON_TempTooLow, GET_TEXT_F(MSG_HOTEND_TOO_COLD), GET_TEXT_F(MSG_PLEASE_PREHEAT)); + dwinPopupContinue(ICON_TempTooLow, GET_TEXT_F(MSG_HOTEND_TOO_COLD), GET_TEXT_F(MSG_PLEASE_PREHEAT)); } #endif @@ -513,14 +508,14 @@ void dwinDrawStatusMessage() { // Get a pointer to the next valid UTF8 character // and the string remaining length uint8_t rlen; - const char *stat = MarlinUI::status_and_len(rlen); + const char *stat = ui.status_and_len(rlen); dwinDrawRectangle(1, hmiData.colorStatusBg, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); DWINUI::moveTo(0, STATUS_Y + 2); DWINUI::drawString(hmiData.colorStatusTxt, stat, LCD_WIDTH); // If the string doesn't completely fill the line... if (rlen < LCD_WIDTH) { - DWINUI::drawChar(hmiData.colorStatusTxt, '.'); // Always at 1+ spaces left, draw a dot + DWINUI::drawChar(hmiData.colorStatusTxt, '.'); // Always at 1+ spaces left, draw a dot uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters if (--chars) { // Draw a second dot if there's space DWINUI::drawChar(hmiData.colorStatusTxt, '.'); @@ -528,7 +523,7 @@ void dwinDrawStatusMessage() { DWINUI::drawString(hmiData.colorStatusTxt, ui.status_message, chars); // Print a second copy of the message } } - MarlinUI::advance_status_scroll(); + ui.advance_status_scroll(); } #else @@ -578,8 +573,8 @@ void drawPrintProgressElapsed() { } #endif -void ICON_ResumeOrPause() { - if (checkkey == ID_PrintProcess) (print_job_timer.isPaused() || hmiFlag.pause_flag) ? ICON_Resume() : ICON_Pause(); +void iconResumeOrPause() { + if (checkkey == ID_PrintProcess) (print_job_timer.isPaused() || hmiFlag.pause_flag) ? iconResume() : iconPause(); } // Update filename on print @@ -609,14 +604,14 @@ void drawPrintProcess() { drawPrintProgressBar(); drawPrintProgressElapsed(); TERN_(SHOW_REMAINING_TIME, drawPrintProgressRemain()); - ICON_Tune(); - ICON_ResumeOrPause(); - ICON_Stop(); + iconTune(); + iconResumeOrPause(); + iconStop(); } void gotoPrintProcess() { if (checkkey == ID_PrintProcess) - ICON_ResumeOrPause(); + iconResumeOrPause(); else { checkkey = ID_PrintProcess; drawPrintProcess(); @@ -668,10 +663,10 @@ void drawMainMenu() { else title.showCaption(MACHINE_NAME); DWINUI::drawIcon(ICON_LOGO, 71, 52); // CREALITY logo - ICON_Print(); - ICON_Prepare(); - ICON_Control(); - ICON_AdvSettings(); + iconPrint(); + iconPrepare(); + iconControl(); + iconAdvSettings(); } void gotoMainMenu() { @@ -925,7 +920,7 @@ void onClickSDItem() { if (card.flag.filenameIsDir) return sdCardFolder(card.filename); if (card.fileIsBinary()) - return dwinPopupConfirm(ICON_Error, F("Please check filenames"), F("Only G-code can be printed")); + return dwinPopupContinue(ICON_Error, F("Please check filenames"), F("Only G-code can be printed")); else { dwinPrintHeader(card.longest_filename()); // Save filename return gotoConfirmToPrint(); @@ -1119,20 +1114,20 @@ void hmiMainMenu() { if (encoder_diffState == ENCODER_DIFF_CW) { if (select_page.inc(PAGE_COUNT)) { switch (select_page.now) { - case PAGE_PRINT: ICON_Print(); break; - case PAGE_PREPARE: ICON_Print(); ICON_Prepare(); break; - case PAGE_CONTROL: ICON_Prepare(); ICON_Control(); break; - case PAGE_ADVANCE: ICON_Control(); ICON_AdvSettings(); break; + case PAGE_PRINT: iconPrint(); break; + case PAGE_PREPARE: iconPrint(); iconPrepare(); break; + case PAGE_CONTROL: iconPrepare(); iconControl(); break; + case PAGE_ADVANCE: iconControl(); iconAdvSettings(); break; } } } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_page.dec()) { switch (select_page.now) { - case PAGE_PRINT: ICON_Print(); ICON_Prepare(); break; - case PAGE_PREPARE: ICON_Prepare(); ICON_Control(); break; - case PAGE_CONTROL: ICON_Control(); ICON_AdvSettings(); break; - case PAGE_ADVANCE: ICON_AdvSettings(); break; + case PAGE_PRINT: iconPrint(); iconPrepare(); break; + case PAGE_PREPARE: iconPrepare(); iconControl(); break; + case PAGE_CONTROL: iconControl(); iconAdvSettings(); break; + case PAGE_ADVANCE: iconAdvSettings(); break; } } } @@ -1171,18 +1166,18 @@ void hmiPrinting() { if (encoder_diffState == ENCODER_DIFF_CW) { if (select_print.inc(PRINT_COUNT)) { switch (select_print.now) { - case PRINT_SETUP: ICON_Tune(); break; - case PRINT_PAUSE_RESUME: ICON_Tune(); ICON_ResumeOrPause(); break; - case PRINT_STOP: ICON_ResumeOrPause(); ICON_Stop(); break; + case PRINT_SETUP: iconTune(); break; + case PRINT_PAUSE_RESUME: iconTune(); iconResumeOrPause(); break; + case PRINT_STOP: iconResumeOrPause(); iconStop(); break; } } } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_print.dec()) { switch (select_print.now) { - case PRINT_SETUP: ICON_Tune(); ICON_ResumeOrPause(); break; - case PRINT_PAUSE_RESUME: ICON_ResumeOrPause(); ICON_Stop(); break; - case PRINT_STOP: ICON_Stop(); break; + case PRINT_SETUP: iconTune(); iconResumeOrPause(); break; + case PRINT_PAUSE_RESUME: iconResumeOrPause(); iconStop(); break; + case PRINT_STOP: iconStop(); break; } } } @@ -1315,7 +1310,7 @@ void eachMomentUpdate() { if (!PENDING(ms, next_rts_update_ms)) { next_rts_update_ms = ms + DWIN_UPDATE_INTERVAL; - if ((isPrinting() != hmiFlag.printing_flag) && !hmiFlag.home_flag) { + if ((hmiFlag.printing_flag != isPrinting()) && !hmiFlag.home_flag && (checkkey != ID_Leveling)) { hmiFlag.printing_flag = isPrinting(); if (hmiFlag.printing_flag) dwinPrintStarted(); @@ -1325,7 +1320,7 @@ void eachMomentUpdate() { dwinPrintFinished(); } - if ((printingIsPaused() != hmiFlag.pause_flag) && !hmiFlag.home_flag) { + if ((hmiFlag.pause_flag != printingIsPaused()) && !hmiFlag.home_flag) { hmiFlag.pause_flag = printingIsPaused(); if (hmiFlag.pause_flag) dwinPrintPause(); @@ -1482,6 +1477,10 @@ void dwinHomingStart() { void dwinHomingDone() { hmiFlag.home_flag = false; + #if JUST_BABYSTEP + planner.synchronize(); + babystep.add_mm(Z_AXIS, hmiData.manualZOffset); + #endif if (last_checkkey == ID_PrintDone) gotoPrintDone(); else @@ -1653,7 +1652,7 @@ void dwinLevelingDone() { break; case PID_TEMP_TOO_HIGH: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_TEMP_TOO_HIGH)); + dwinPopupContinue(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_TEMP_TOO_HIGH)); break; #endif #if ENABLED(PIDTEMPBED) @@ -1668,15 +1667,15 @@ void dwinLevelingDone() { #endif case PID_BAD_HEATER_ID: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooLow, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_PID_BAD_HEATER_ID)); + dwinPopupContinue(ICON_TempTooLow, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_PID_BAD_HEATER_ID)); break; case PID_TUNING_TIMEOUT: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooHigh, GET_TEXT_F(MSG_ERROR), GET_TEXT_F(MSG_PID_TIMEOUT)); + dwinPopupContinue(ICON_TempTooHigh, GET_TEXT_F(MSG_ERROR), GET_TEXT_F(MSG_PID_TIMEOUT)); break; case AUTOTUNE_DONE: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooLow, GET_TEXT_F(MSG_PID_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); + dwinPopupContinue(ICON_TempTooLow, GET_TEXT_F(MSG_PID_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); break; default: checkkey = last_checkkey; @@ -1701,17 +1700,17 @@ void dwinLevelingDone() { break; case MPC_TEMP_ERROR: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), F(STR_MPC_TEMPERATURE_ERROR)); + dwinPopupContinue(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), F(STR_MPC_TEMPERATURE_ERROR)); ui.reset_alert_level(); break; case MPC_INTERRUPTED: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooHigh, GET_TEXT_F(MSG_ERROR), F(STR_MPC_AUTOTUNE_INTERRUPTED)); + dwinPopupContinue(ICON_TempTooHigh, GET_TEXT_F(MSG_ERROR), F(STR_MPC_AUTOTUNE_INTERRUPTED)); ui.reset_alert_level(); break; case AUTOTUNE_DONE: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooLow, GET_TEXT_F(MSG_MPC_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); + dwinPopupContinue(ICON_TempTooLow, GET_TEXT_F(MSG_MPC_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); ui.reset_alert_level(); break; default: @@ -1736,12 +1735,12 @@ void dwinPrintStarted() { // Pause a print job void dwinPrintPause() { - ICON_ResumeOrPause(); + iconResumeOrPause(); } // Resume print job void dwinPrintResume() { - ICON_ResumeOrPause(); + iconResumeOrPause(); LCD_MESSAGE(MSG_RESUME_PRINT); } @@ -1764,7 +1763,7 @@ void dwinPrintAborted() { #if ENABLED(NOZZLE_PARK_FEATURE) F("G27") #else - TS(F("G0Z"), float(_MIN(current_position.z + (Z_POST_CLEARANCE), Z_MAX_POS)), F("\nG0F2000Y"), Y_MAX_POS); + TS(F("G0Z"), float(_MIN(current_position.z + (Z_POST_CLEARANCE), Z_MAX_POS)), F("\nG0F2000Y"), Y_MAX_POS) #endif ); } @@ -1822,6 +1821,9 @@ void dwinSetDataDefaults() { #if ALL(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) hmiData.zAfterHoming = DEF_Z_AFTER_HOMING; #endif + #if !HAS_BED_PROBE + hmiData.manualZOffset = 0; + #endif #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) TERN_(LED_COLOR_PRESETS, leds.set_default()); applyLEDColor(); @@ -2152,7 +2154,7 @@ void axisMove(AxisEnum axis) { #if HAS_HOTEND if (axis == E_AXIS && thermalManager.tooColdToExtrude(0)) { gcode.process_subcommands_now(F("G92E0")); // Reset extruder position - return dwinPopupConfirm(ICON_TempTooLow, GET_TEXT_F(MSG_HOTEND_TOO_COLD), GET_TEXT_F(MSG_PLEASE_PREHEAT)); + return dwinPopupContinue(ICON_TempTooLow, GET_TEXT_F(MSG_HOTEND_TOO_COLD), GET_TEXT_F(MSG_PLEASE_PREHEAT)); } #endif planner.synchronize(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index 4d9395842ad3..873b0938e6b7 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -154,6 +154,9 @@ typedef struct { #if HAS_GCODE_PREVIEW bool enablePreview = true; #endif + #if !HAS_BED_PROBE + float manualZOffset = 0.0f; + #endif } hmi_data_t; extern hmi_data_t hmiData; diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.h b/Marlin/src/lcd/e3v2/proui/dwin_popup.h index d970cbfef475..83c5b5e3854c 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.h @@ -69,11 +69,3 @@ void dwinShowPopup(const uint8_t icon, T amsg1=nullptr, U amsg2=nullptr, uint8_t dwinDrawPopup(icon, amsg1, amsg2, button); dwinUpdateLCD(); } - -template -void dwinPopupConfirm(const uint8_t icon, T amsg1, U amsg2) { - hmiSaveProcessID(ID_WaitResponse); - dwinDrawPopup(icon, amsg1, amsg2, BTN_Confirm); // Button Confirm - dwinUpdateLCD(); -} - diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 0bd83bc3ac10..eb1c66580ff7 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -377,7 +377,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(ds_str)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(ds_str)); - TERN_(DWIN_LCD_PROUI, dwinPopupConfirm(ICON_BLTouch, ds_str, FPSTR(CONTINUE_STR))); + TERN_(DWIN_LCD_PROUI, dwinPopupContinue(ICON_BLTouch, ds_str, FPSTR(CONTINUE_STR))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.reset_status(); From d9405de3eb450fd84a5167d08cc927bb5e394f37 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 19 Jan 2024 02:56:16 -0500 Subject: [PATCH 050/109] change signed float to long --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index c945b40a32cc..bbf4e6203c8a 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -560,7 +560,7 @@ void dwinDrawLabel(const uint8_t row, FSTR_P title) { dwinDrawLabel(row, (char*)title); } -void dwinDrawSignedFloat(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, int32_t value) { +void dwinDrawSignedFloat(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { dwinDrawString(true, size, COLOR_WHITE, bColor, x - 8, y, value < 0 ? F("-") : F(" ")); dwinDrawFloatValue(true, true, 0, size, COLOR_WHITE, bColor, iNum, fNum, x, y, value < 0 ? -value : value); } From 2417818481fc49603355f125ac41d30b4cfa3c80 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 19 Jan 2024 04:06:24 -0500 Subject: [PATCH 051/109] fix for manualMeshSave --- Marlin/src/lcd/e3v2/proui/dwin.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index 873b0938e6b7..6613d68f6de0 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -342,6 +342,7 @@ void drawMotionMenu(); void drawFilamentManMenu(); #if ENABLED(MESH_BED_LEVELING) void drawManualMeshMenu(); + void manualMeshSave(); #endif void drawTemperatureMenu(); void drawMaxSpeedMenu(); From 0def0b13c2129fdb4a7575a2efa407272787b41f Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 19 Jan 2024 04:14:49 -0500 Subject: [PATCH 052/109] move previous up --- Marlin/src/lcd/e3v2/proui/dwin.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index 6613d68f6de0..587b6789efd1 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -213,6 +213,7 @@ uint32_t getHash(char * str); void readEEPROM(); void resetEEPROM(); #if HAS_MESH + void manualMeshSave(); void saveMesh(); #endif #endif @@ -342,7 +343,6 @@ void drawMotionMenu(); void drawFilamentManMenu(); #if ENABLED(MESH_BED_LEVELING) void drawManualMeshMenu(); - void manualMeshSave(); #endif void drawTemperatureMenu(); void drawMaxSpeedMenu(); From 739931d71f77bc728b5398806a384142765aa216 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 19 Jan 2024 23:43:44 -0500 Subject: [PATCH 053/109] fix convert error --- Marlin/src/gcode/lcd/M0_M1.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 2a2538c0b305..dd6fd78ed114 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -73,7 +73,7 @@ void GcodeSuite::M0_M1() { ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_USERWAIT)); #elif ENABLED(DWIN_LCD_PROUI) if (parser.string_arg) - dwinPopupContinue(ICON_BLTouch, parser.string_arg, GET_TEXT_F(MSG_USERWAIT)); + dwinPopupContinue(ICON_BLTouch, F(parser.string_arg), GET_TEXT_F(MSG_USERWAIT)); else dwinPopupContinue(ICON_BLTouch, GET_TEXT_F(MSG_STOPPED), GET_TEXT_F(MSG_USERWAIT)); #else From f299a643b09f06e43198e93b156662e60e59d5f3 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 20 Jan 2024 00:54:49 -0500 Subject: [PATCH 054/109] revert pins_trigorilla --- Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h b/Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h index e6215be4fb7c..a477308277da 100644 --- a/Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h +++ b/Marlin/src/pins/gd32f1/pins_TRIGORILLA_V006.h @@ -132,21 +132,21 @@ // SDIO // #define SDIO_READ_RETRIES 16 - #define BOARD_SDIO_D0 PC8 - #define BOARD_SDIO_D1 PC9 - #define BOARD_SDIO_D2 PC10 - #define BOARD_SDIO_D3 PC11 - #define BOARD_SDIO_CLK PC12 - #define BOARD_SDIO_CMD PD2 + #define SDIO_D0_PIN PC8 + #define SDIO_D1_PIN PC9 + #define SDIO_D2_PIN PC10 + #define SDIO_D3_PIN PC11 + #define SDIO_CK_PIN PC12 + #define SDIO_CMD_PIN PD2 #else #undef SDSS - #define SDSS PC11 // BOARD_SDIO_D3 + #define SDSS PC11 // SDIO_D3_PIN #define SS_PIN SDSS - #define SCK_PIN PC12 // BOARD_SDIO_CLK - #define MISO_PIN PC8 // BOARD_SDIO_D0 - #define MOSI_PIN PD2 // BOARD_SDIO_CMD + #define SCK_PIN PC12 // SDIO_CK_PIN + #define MISO_PIN PC8 // SDIO_D0_PIN + #define MOSI_PIN PD2 // SDIO_CMD_PIN #define SOFTWARE_SPI #endif From 5aebe9fd4798eeba9b6c893d3790a107571c0bf8 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 20 Jan 2024 01:12:17 -0500 Subject: [PATCH 055/109] update ESDiag - is filament sensor? --- Marlin/src/lcd/e3v2/proui/endstop_diag.cpp | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp index a0c00100b157..8c057c5ba2e2 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp @@ -57,11 +57,12 @@ void draw_es_label(FSTR_P const flabel=nullptr) { DWINUI::moveBy(0, 25); } -void draw_es_state(const bool is_hit) { +void draw_es_state(const bool is_hit, const bool is_fil) { const uint8_t LM = 130; DWINUI::cursor.x = LM; - dwinDrawRectangle(1, hmiData.colorPopupBg, LM, DWINUI::cursor.y, LM + 100, DWINUI::cursor.y + 20); - is_hit ? DWINUI::drawString(RGB(31, 31, 16), F(STR_ENDSTOP_HIT)) : DWINUI::drawString(RGB(16, 63, 16), F(STR_ENDSTOP_OPEN)); + dwinDrawRectangle(1, hmiData.colorPopupBg, LM, DWINUI::cursor.y, LM + 120, DWINUI::cursor.y + 20); + is_fil ? (is_hit ? DWINUI::drawString(RGB(16, 63, 16), F("PRESENT")) : DWINUI::drawString(RGB(31, 31, 16), F("Runout Detected"))) : + (is_hit ? DWINUI::drawString(RGB(31, 31, 16), F(STR_ENDSTOP_HIT)) : DWINUI::drawString(RGB(16, 63, 16), F(STR_ENDSTOP_OPEN))); DWINUI::moveBy(0, 25); } @@ -74,18 +75,19 @@ void ESDiag::draw() { #define ES_LABEL(S) draw_es_label(F(STR_##S)) TERN_(USE_X_MIN, ES_LABEL(X_MIN)); TERN_(USE_X_MAX, ES_LABEL(X_MAX)); TERN_(USE_Y_MIN, ES_LABEL(Y_MIN)); TERN_(USE_Y_MAX, ES_LABEL(Y_MAX)); - TERN_(USE_Z_MIN, ES_LABEL(Z_MIN)); TERN_(USE_Z_MAX, ES_LABEL(Z_MAX)); + IF_DISABLED(USE_Z_MIN_PROBE, TERN_(USE_Z_MIN, ES_LABEL(Z_MIN);) TERN_(USE_Z_MAX, ES_LABEL(Z_MAX);)) TERN_(HAS_FILAMENT_SENSOR, draw_es_label(F(STR_FILAMENT))); + TERN_(USE_Z_MIN_PROBE, ES_LABEL(Z_PROBE);) update(); } void ESDiag::update() { DWINUI::cursor.y = 80; - #define ES_REPORT(S) draw_es_state(READ(S##_PIN) == S##_ENDSTOP_HIT_STATE) - TERN_(USE_X_MIN, ES_REPORT(X_MIN)); TERN_(USE_X_MAX, ES_REPORT(X_MAX)); - TERN_(USE_Y_MIN, ES_REPORT(Y_MIN)); TERN_(USE_Y_MAX, ES_REPORT(Y_MAX)); - TERN_(USE_Z_MIN, ES_REPORT(Z_MIN)); TERN_(USE_Z_MAX, ES_REPORT(Z_MAX)); - TERN_(HAS_FILAMENT_SENSOR, draw_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE)); + #define ESREPORT(S) draw_es_state(READ(S##_PIN) == S##_ENDSTOP_HIT_STATE, false) + TERN_(USE_X_MIN, ESREPORT(X_MIN)); TERN_(USE_X_MAX, ESREPORT(X_MAX)); + TERN_(USE_Y_MIN, ESREPORT(Y_MIN)); TERN_(USE_Y_MAX, ESREPORT(Y_MAX)); + IF_DISABLED(USE_Z_MIN_PROBE, TERN_(USE_Z_MIN, ESREPORT(Z_MIN);) TERN_(USE_Z_MAX, ESREPORT(Z_MAX);)) + TERN_(HAS_FILAMENT_SENSOR, draw_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE, true)); dwinUpdateLCD(); } From e9b742d62021f8e6179e8aa8ec08d0c52f4a45dd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 Jan 2024 01:47:50 -0600 Subject: [PATCH 056/109] misc. adjustments --- Marlin/src/gcode/calibrate/M48.cpp | 10 ++-- Marlin/src/gcode/lcd/M0_M1.cpp | 2 +- Marlin/src/lcd/e3v2/common/dwin_api.cpp | 8 ++-- Marlin/src/lcd/e3v2/creality/dwin_lcd.h | 2 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 27 +++++------ Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h | 2 +- Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp | 2 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 48 +++++++++---------- Marlin/src/lcd/e3v2/proui/endstop_diag.cpp | 14 ++++-- Marlin/src/lcd/e3v2/proui/menus.cpp | 14 +++--- .../anycubic_i3mega/anycubic_i3mega_lcd.cpp | 4 +- Marlin/src/module/probe.cpp | 24 +++++----- 12 files changed, 78 insertions(+), 79 deletions(-) diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index a7d804ed4ee6..b1b5b64934a0 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -63,7 +63,7 @@ void GcodeSuite::M48() { hmiSaveProcessID(ID_NothingToDo); #endif - if (homing_needed_error()) TERN(DWIN_LCD_PROUI, return hmiReturnScreen(), return); + if (homing_needed_error()) return TERN_(DWIN_LCD_PROUI, hmiReturnScreen()); const int8_t verbose_level = parser.byteval('V', 1); if (!WITHIN(verbose_level, 0, 4)) { @@ -71,9 +71,6 @@ void GcodeSuite::M48() { return; } - if (verbose_level > 0) - SERIAL_ECHOLNPGM("M48 Z-Probe Repeatability Test"); - const int8_t n_samples = parser.byteval('P', 10); if (!WITHIN(n_samples, 4, 50)) { SERIAL_ECHOLNPGM("?Sample size not plausible (4-50)."); @@ -107,6 +104,9 @@ void GcodeSuite::M48() { const bool schizoid_flag = parser.boolval('S'); if (schizoid_flag && !seen_L) n_legs = 7; + if (verbose_level > 0) + SERIAL_ECHOLNPGM("M48 Z-Probe Repeatability Test"); + if (verbose_level > 2) SERIAL_ECHOLNPGM("Positioning the probe..."); @@ -280,7 +280,7 @@ void GcodeSuite::M48() { report_current_position(); - TERN_(DWIN_LCD_PROUI, hmiReturnScreen();) + TERN_(DWIN_LCD_PROUI, hmiReturnScreen()); } #endif // Z_MIN_PROBE_REPEATABILITY_TEST diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index dd6fd78ed114..2a2538c0b305 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -73,7 +73,7 @@ void GcodeSuite::M0_M1() { ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_USERWAIT)); #elif ENABLED(DWIN_LCD_PROUI) if (parser.string_arg) - dwinPopupContinue(ICON_BLTouch, F(parser.string_arg), GET_TEXT_F(MSG_USERWAIT)); + dwinPopupContinue(ICON_BLTouch, parser.string_arg, GET_TEXT_F(MSG_USERWAIT)); else dwinPopupContinue(ICON_BLTouch, GET_TEXT_F(MSG_STOPPED), GET_TEXT_F(MSG_USERWAIT)); #else diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index 32736b40b984..16492be96ac2 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -90,7 +90,7 @@ bool dwinHandshake() { } #endif -#if NONE(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, IS_DWIN_MARLINUI) +#if ENABLED(DWIN_CREALITY_LCD) // Get font character width uint8_t fontWidth(uint8_t cfont) { switch (cfont) { @@ -236,7 +236,7 @@ void dwinFrameAreaMove(uint8_t mode, uint8_t dir, uint16_t dis, // *string: The string // rlimit: To limit the drawn string length void dwinDrawString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit/*=0xFFFF*/) { - #if NONE(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, IS_DWIN_MARLINUI) + #if ENABLED(DWIN_CREALITY_LCD) dwinDrawRectangle(1, bColor, x, y, x + (fontWidth(size) * strlen_P(string)), y + fontHeight(size)); #endif constexpr uint8_t widthAdjust = 0; @@ -268,7 +268,7 @@ void dwinDrawString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, u void dwinDrawIntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint32_t value) { size_t i = 0; - #if NONE(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, IS_DWIN_MARLINUI) + #if ENABLED(DWIN_CREALITY_LCD) dwinDrawRectangle(1, bColor, x, y, x + fontWidth(size) * iNum + 1, y + fontHeight(size)); #endif dwinByte(i, 0x14); @@ -318,7 +318,7 @@ void dwinDrawFloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, int32_t value) { //uint8_t *fvalue = (uint8_t*)&value; size_t i = 0; - #if NONE(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, IS_DWIN_MARLINUI) + #if ENABLED(DWIN_CREALITY_LCD) dwinDrawRectangle(1, bColor, x, y, x + fontWidth(size) * (iNum + fNum + 1), y + fontHeight(size)); #endif dwinByte(i, 0x14); diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h index f1610a06db2f..2faf6a9d6522 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.h @@ -50,4 +50,4 @@ void dwinFrameAreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16 // libID: Icon library ID // picID: Icon ID // x/y: Upper-left point -void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); \ No newline at end of file +void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index a4a139c0bbee..f9ca1e6b9acd 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -257,16 +257,20 @@ class TextScroller { uint8_t mesh_x = 0; uint8_t mesh_y = 0; + inline void manualValueUpdate(const bool undefined=false) { + gcode.process_subcommands_now( + #if ENABLED(AUTO_BED_LEVELING_UBL) + TS(F("M421I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3), undefined ? "N" : "") + #else + TS(F("G29I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)) + #endif + ); + planner.synchronize(); + } + #if ENABLED(AUTO_BED_LEVELING_UBL) uint8_t tilt_grid = 1; - void manualValueUpdate(bool undefined=false) { - gcode.process_subcommands_now( - TS(F("M421I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3), undefined ? "N" : "") - ); - planner.synchronize(); - } - bool createPlaneFromMesh() { struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); @@ -305,15 +309,6 @@ class TextScroller { return false; } - #else - - void manualValueUpdate() { - gcode.process_subcommands_now( - TS(F("G29I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)) - ); - planner.synchronize(); - } - #endif void manual_mesh_move(const bool zmove=false) { diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h index 27463cc913cc..02a3abde6b7b 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h @@ -37,4 +37,4 @@ void dwinDrawDegreeSymbol(uint16_t color, uint16_t x, uint16_t y); // libID: Icon library ID // picID: Icon ID // x/y: Upper-left point -void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); \ No newline at end of file +void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index c627b6573a13..9832642f3983 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -123,7 +123,7 @@ void BedLevelTools::manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y if (reset) { zval = 0; } else { zval = current_position.z; } gcode.process_subcommands_now( - TS(F(TERN(AUTO_BED_LEVELING_UBL, "M421 I", "G29 I")), mesh_x, 'J', mesh_y, 'Z', p_float_t(zval, 3)) + TS(F(TERN(AUTO_BED_LEVELING_UBL, "M421 I", "G29 I")), mesh_x, 'J', mesh_y, 'Z', p_float_t(zval, 3)) ); planner.synchronize(); } diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 5766a6572350..9fdd9528dc32 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1206,9 +1206,13 @@ void drawMainArea() { case ID_MainMenu: drawMainMenu(); break; case ID_PrintProcess: drawPrintProcess(); break; case ID_PrintDone: drawPrintDone(); break; - TERN_(HAS_ESDIAG, case ID_ESDiagProcess: drawEndStopDiag(); break;) + #if HAS_ESDIAG + case ID_ESDiagProcess: drawEndStopDiag(); break; + #endif case ID_Popup: popupDraw(); break; - TERN_(HAS_LOCKSCREEN, case ID_Locked: lockScreen.draw(); break;) + #if HAS_LOCKSCREEN + case ID_Locked: lockScreen.draw(); break; + #endif case ID_Menu: case ID_SetInt: case ID_SetPInt: @@ -1227,14 +1231,8 @@ void hmiWaitForUser() { } if (!wait_for_user) { switch (checkkey) { - case ID_PrintDone: - select_page.reset(); - gotoMainMenu(); - break; - TERN_(HAS_BED_PROBE, case ID_Leveling:) - default: - hmiReturnScreen(); - break; + case ID_PrintDone: select_page.reset(); gotoMainMenu(); break; + default: hmiReturnScreen(); break; } } } @@ -1421,8 +1419,9 @@ void dwinHandleScreen() { case ID_SetIntNoDraw: hmiSetNoDraw(); break; case ID_PrintProcess: hmiPrinting(); break; case ID_Popup: hmiPopup(); break; - TERN_(HAS_LOCKSCREEN, case ID_Locked: hmiLockScreen(); break;) - + #if HAS_LOCKSCREEN + case ID_Locked: hmiLockScreen(); break; + #endif TERN_(HAS_ESDIAG, case ID_ESDiagProcess:) TERN_(PROUI_ITEM_PLOT, case ID_PlotProcess:) case ID_PrintDone: @@ -1585,16 +1584,13 @@ void dwinLevelingDone() { hmiSaveProcessID(ID_PlotProcess); switch (result) { - #if ENABLED(MPCTEMP) - case MPCTEMP_START: - #elif ENABLED(PIDTEMP) - case PIDTEMP_START: - #endif - title.showCaption(GET_TEXT_F(MSG_HOTEND_TEMP_GRAPH)); - DWINUI::drawCenteredString(3, hmiData.colorPopupTxt, 75, F("Nozzle Temperature")); - _maxtemp = thermalManager.hotend_max_target(0); - _target = thermalManager.degTargetHotend(0); - break; + TERN_(MPCTEMP, case MPCTEMP_START:) + TERN_(PIDTEMP, case PIDTEMP_START:) + title.showCaption(GET_TEXT_F(MSG_HOTEND_TEMP_GRAPH)); + DWINUI::drawCenteredString(3, hmiData.colorPopupTxt, 75, F("Nozzle Temperature")); + _maxtemp = thermalManager.hotend_max_target(0); + _target = thermalManager.degTargetHotend(0); + break; #if ENABLED(PIDTEMPBED) case PIDTEMPBED_START: title.showCaption(GET_TEXT_F(MSG_BED_TEMP_GRAPH)); @@ -1631,8 +1627,12 @@ void dwinLevelingDone() { if (seenC) hmiData.pidCycles = c; if (seenS) { switch (hid) { - OPTCODE(PIDTEMP, case 0 ... HOTENDS - 1: hmiData.hotendPidT = temp; break) - OPTCODE(PIDTEMPBED, case H_BED: hmiData.bedPidT = temp; break) + #if ENABLED(PIDTEMP) + case 0 ... HOTENDS - 1: hmiData.hotendPidT = temp; break; + #endif + #if ENABLED(PIDTEMPBED) + case H_BED: hmiData.bedPidT = temp; break; + #endif default: break; } } diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp index 8c057c5ba2e2..8d9bed50cbde 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp @@ -75,9 +75,12 @@ void ESDiag::draw() { #define ES_LABEL(S) draw_es_label(F(STR_##S)) TERN_(USE_X_MIN, ES_LABEL(X_MIN)); TERN_(USE_X_MAX, ES_LABEL(X_MAX)); TERN_(USE_Y_MIN, ES_LABEL(Y_MIN)); TERN_(USE_Y_MAX, ES_LABEL(Y_MAX)); - IF_DISABLED(USE_Z_MIN_PROBE, TERN_(USE_Z_MIN, ES_LABEL(Z_MIN);) TERN_(USE_Z_MAX, ES_LABEL(Z_MAX);)) - TERN_(HAS_FILAMENT_SENSOR, draw_es_label(F(STR_FILAMENT))); - TERN_(USE_Z_MIN_PROBE, ES_LABEL(Z_PROBE);) + #if !USE_Z_MIN_PROBE + TERN_(USE_Z_MIN, ES_LABEL(Z_MIN)); + #endif + TERN_(USE_Z_MAX, ES_LABEL(Z_MAX)); + TERN_(HAS_FILAMENT_SENSOR, ES_LABEL(FILAMENT)); + TERN_(USE_Z_MIN_PROBE, ES_LABEL(Z_PROBE)); update(); } @@ -86,7 +89,10 @@ void ESDiag::update() { #define ESREPORT(S) draw_es_state(READ(S##_PIN) == S##_ENDSTOP_HIT_STATE, false) TERN_(USE_X_MIN, ESREPORT(X_MIN)); TERN_(USE_X_MAX, ESREPORT(X_MAX)); TERN_(USE_Y_MIN, ESREPORT(Y_MIN)); TERN_(USE_Y_MAX, ESREPORT(Y_MAX)); - IF_DISABLED(USE_Z_MIN_PROBE, TERN_(USE_Z_MIN, ESREPORT(Z_MIN);) TERN_(USE_Z_MAX, ESREPORT(Z_MAX);)) + #if !USE_Z_MIN_PROBE + TERN_(USE_Z_MIN, ESREPORT(Z_MIN)); + #endif + TERN_(USE_Z_MAX, ESREPORT(Z_MAX)); TERN_(HAS_FILAMENT_SENSOR, draw_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE, true)); dwinUpdateLCD(); } diff --git a/Marlin/src/lcd/e3v2/proui/menus.cpp b/Marlin/src/lcd/e3v2/proui/menus.cpp index 9f48ff03b748..88fbf6000125 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.cpp +++ b/Marlin/src/lcd/e3v2/proui/menus.cpp @@ -263,7 +263,7 @@ void setPFloatOnClick(const float lo, const float hi, uint8_t dp, void (*apply)( // Generic menu control using the encoder void hmiMenu() { - EncoderState encoder_diffState = get_encoder_state(); + const EncoderState encoder_diffState = get_encoder_state(); if (currentMenu) { if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) @@ -280,10 +280,8 @@ void hmiMenu() { // 1 : live change // 2 : apply change int8_t hmiGet(bool draw) { - const int32_t lo = menuData.minValue; - const int32_t hi = menuData.maxValue; - const int32_t cval = menuData.value; - EncoderState encoder_diffState = TERN(SMOOTH_ENCODER_MENUITEMS, get_encoder_state(), encoderReceiveAnalyze()); + const int32_t lo = menuData.minValue, hi = menuData.maxValue, cval = menuData.value; + const EncoderState encoder_diffState = TERN(SMOOTH_ENCODER_MENUITEMS, get_encoder_state(), encoderReceiveAnalyze()); if (encoder_diffState != ENCODER_DIFF_NO) { if (applyEncoder(encoder_diffState, menuData.value)) { encoderRate.enabled = false; @@ -300,7 +298,7 @@ int8_t hmiGet(bool draw) { // Set and draw a value using the encoder void hmiSetDraw() { - int8_t val = hmiGet(true); + const int8_t val = hmiGet(true); switch (val) { case 0: return; case 1: if (menuData.liveUpdate) menuData.liveUpdate(); break; @@ -310,7 +308,7 @@ void hmiSetDraw() { // Set an value without drawing void hmiSetNoDraw() { - int8_t val = hmiGet(false); + const int8_t val = hmiGet(false); switch (val) { case 0: return; case 1: if (menuData.liveUpdate) menuData.liveUpdate(); break; @@ -320,7 +318,7 @@ void hmiSetNoDraw() { // Set an integer pointer variable using the encoder void hmiSetPInt() { - int8_t val = hmiGet(true); + const int8_t val = hmiGet(true); switch (val) { case 0: return; case 1: if (menuData.liveUpdate) menuData.liveUpdate(); break; diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index f8cba1567694..709b54a6d76a 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -897,7 +897,7 @@ void AnycubicTFT::doFilamentRunoutCheck() { #if ENABLED(FILAMENT_RUNOUT_SENSOR) // NOTE: getFilamentRunoutState() only returns the runout state if the job is printing // we want to actually check the status of the pin here, regardless of printstate - if (READ(FIL_RUNOUT1_PIN)) { + if (READ(FIL_RUNOUT1_PIN) == FIL_RUNOUT1_STATE) { if (mediaPrintingState == AMPRINTSTATE_PRINTING || mediaPrintingState == AMPRINTSTATE_PAUSED || mediaPrintingState == AMPRINTSTATE_PAUSE_REQUESTED) { // play tone to indicate filament is out injectCommands(F("\nM300 P200 S1567\nM300 P200 S1174\nM300 P200 S1567\nM300 P200 S1174\nM300 P2000 S1567")); @@ -940,7 +940,7 @@ void AnycubicTFT::pausePrint() { void AnycubicTFT::resumePrint() { #if HAS_MEDIA #if ENABLED(FILAMENT_RUNOUT_SENSOR) - if (READ(FIL_RUNOUT1_PIN)) { + if (READ(FIL_RUNOUT1_PIN) == FIL_RUNOUT1_STATE) { DEBUG_ECHOLNPGM("TFT Serial Debug: Resume Print with filament sensor still tripped... "); // trigger the user message box diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index eb1c66580ff7..c9f198ce5f31 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -356,28 +356,28 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { // Start preheating before waiting for user confirmation that the probe is ready. TERN_(PREHEAT_BEFORE_PROBING, if (deploy) probe.preheat_for_probing(0, PROBING_BED_TEMP, true)); - FSTR_P const ds_str = deploy ? GET_TEXT_F(MSG_MANUAL_DEPLOY) : GET_TEXT_F(MSG_MANUAL_STOW); + FSTR_P const ds_fstr = deploy ? GET_TEXT_F(MSG_MANUAL_DEPLOY) : GET_TEXT_F(MSG_MANUAL_STOW); ui.return_to_status(); // To display the new status message - ui.set_max_status(ds_str); + ui.set_max_status(ds_fstr); SERIAL_ECHOLN(deploy ? GET_EN_TEXT_F(MSG_MANUAL_DEPLOY) : GET_EN_TEXT_F(MSG_MANUAL_STOW)); OKAY_BUZZ(); #if ENABLED(PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED) + { // Wait for the probe to be attached or detached before asking for explicit user confirmation // Allow the user to interrupt - { - KEEPALIVE_STATE(PAUSED_FOR_USER); - TERN_(HAS_RESUME_CONTINUE, wait_for_user = true); - while (deploy == PROBE_TRIGGERED() && TERN1(HAS_RESUME_CONTINUE, wait_for_user)) idle_no_sleep(); - TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); - OKAY_BUZZ(); - } + KEEPALIVE_STATE(PAUSED_FOR_USER); + TERN_(HAS_RESUME_CONTINUE, wait_for_user = true); + while (deploy == PROBE_TRIGGERED() && TERN1(HAS_RESUME_CONTINUE, wait_for_user)) idle_no_sleep(); + TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); + OKAY_BUZZ(); + } #endif - TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(ds_str)); - TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(ds_str)); - TERN_(DWIN_LCD_PROUI, dwinPopupContinue(ICON_BLTouch, ds_str, FPSTR(CONTINUE_STR))); + TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(ds_fstr)); + TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(ds_fstr)); + TERN_(DWIN_LCD_PROUI, dwinPopupContinue(ICON_BLTouch, ds_fstr, FPSTR(CONTINUE_STR))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.reset_status(); From 7cab0c8982e6384727582fb9b43bcf4f321fda3c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 Jan 2024 01:54:17 -0600 Subject: [PATCH 057/109] extra ui.* --- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 8 ++++---- Marlin/src/lcd/e3v2/marlinui/ui_common.cpp | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 155ae581f06a..58eb8f3162c9 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -793,11 +793,11 @@ void MarlinUI::draw_status_message(const bool blink) { static lcd_uint_t pc = 0, pr = 2; inline void setPercentPos(const lcd_uint_t c, const lcd_uint_t r) { pc = c; pr = r; } void MarlinUI::drawPercent() { - const uint8_t progress = ui.get_progress_percent(); + const uint8_t progress = get_progress_percent(); if (progress) { lcd_moveto(pc, pr); lcd_put_u8str(F(TERN(IS_SD_PRINTING, "SD", "P:"))); - lcd_put_u8str(TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(ui.get_progress_permyriad()), ui8tostr3rj(progress))); + lcd_put_u8str(TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(get_progress_permyriad()), ui8tostr3rj(progress))); lcd_put_u8str(F("%")); } } @@ -806,7 +806,7 @@ void MarlinUI::draw_status_message(const bool blink) { #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { if (printJobOngoing()) { - const duration_t remaint = ui.get_remaining_time(); + const duration_t remaint = get_remaining_time(); timepos = TPOFFSET - remaint.toDigital(buffer); TERN_(NOT(LCD_INFO_SCREEN_STYLE), lcd_put_lchar(timepos - 1, 2, 0x20);) lcd_put_lchar(TERN(LCD_INFO_SCREEN_STYLE, 11, timepos), 2, 'R'); @@ -817,7 +817,7 @@ void MarlinUI::draw_status_message(const bool blink) { #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { - const duration_t interactt = ui.interaction_time; + const duration_t interactt = interaction_time; if (printingIsActive() && interactt.value) { timepos = TPOFFSET - interactt.toDigital(buffer); TERN_(NOT(LCD_INFO_SCREEN_STYLE), lcd_put_lchar(timepos - 1, 2, 0x20);) diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index f9318c75b9bb..6a4cb6afde5e 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -186,7 +186,7 @@ void MarlinUI::draw_status_message(const bool blink) { auto status_changed = []{ static MString<>::hash_t old_hash = 0x0000; - const MString<>::hash_t hash = ui.status_message.hash(); + const MString<>::hash_t hash = status_message.hash(); const bool hash_changed = hash != old_hash; old_hash = hash; return hash_changed || !did_first_redraw; From b5d6bd184cdb5e52a9fd243d08f4aed19d84297d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 Jan 2024 01:57:23 -0600 Subject: [PATCH 058/109] Fix dwinPopupContinue --- Marlin/src/lcd/e3v2/proui/dwin_popup.cpp | 6 ------ Marlin/src/lcd/e3v2/proui/dwin_popup.h | 8 +++++++- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp index 5756b770afbe..26412dd7f555 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp @@ -54,12 +54,6 @@ void drawSelectHighlight(const bool sel, const uint16_t ypos) { dwinDrawRectangle(0, c2, 144, ypos - 2, 247, ypos + 39); } -void dwinPopupContinue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2) { - hmiSaveProcessID(ID_WaitResponse); - dwinDrawPopup(icon, fmsg1, fmsg2, BTN_Continue); // Button Continue - dwinUpdateLCD(); -} - void dwinPopupConfirmCancel(const uint8_t icon, FSTR_P const fmsg2) { dwinDrawPopup(ICON_BLTouch, F("Please confirm"), fmsg2); DWINUI::drawButton(BTN_Confirm, 26, 280); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.h b/Marlin/src/lcd/e3v2/proui/dwin_popup.h index 83c5b5e3854c..659c64472f20 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.h @@ -38,7 +38,6 @@ extern popupDrawFunc_t popupDraw; void drawSelectHighlight(const bool sel, const uint16_t ypos); inline void drawSelectHighlight(const bool sel) { drawSelectHighlight(sel, 280); }; -void dwinPopupContinue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2); void dwinPopupConfirmCancel(const uint8_t icon, FSTR_P const fmsg2); void gotoPopup(const popupDrawFunc_t fnDraw, const popupClickFunc_t fnClick=nullptr, const popupChangeFunc_t fnChange=nullptr); void hmiPopup(); @@ -69,3 +68,10 @@ void dwinShowPopup(const uint8_t icon, T amsg1=nullptr, U amsg2=nullptr, uint8_t dwinDrawPopup(icon, amsg1, amsg2, button); dwinUpdateLCD(); } + +template +void dwinPopupContinue(const uint8_t icon, T amsg1, U amsg2) { + hmiSaveProcessID(ID_WaitResponse); + dwinDrawPopup(icon, amsg1, amsg2, BTN_Continue); // Button Continue + dwinUpdateLCD(); +} From 55ca94989f2228db7f03c115046174ec66cfe8e7 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 20 Jan 2024 06:10:25 -0500 Subject: [PATCH 059/109] dwinPopupContinue is undefined without #include dwin_popup.h --- Marlin/src/module/probe.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index c9f198ce5f31..f15f7b3d868b 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -97,7 +97,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" #elif ENABLED(DWIN_LCD_PROUI) - #include "../lcd/e3v2/proui/dwin.h" + #include "../lcd/e3v2/proui/dwin_popup.h" #endif #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) From 750b47c5a71472d16cf2d0cc623df3de76bbdb2f Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 20 Jan 2024 10:11:25 -0500 Subject: [PATCH 060/109] remove unneeded highlightY --- Marlin/src/lcd/e3v2/proui/dwin_popup.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp index 26412dd7f555..6ac467b16d60 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp @@ -41,10 +41,7 @@ popupDrawFunc_t popupDraw = nullptr; popupClickFunc_t popupClick = nullptr; popupChangeFunc_t popupChange = nullptr; -uint16_t highlightY = 280; - void drawSelectHighlight(const bool sel, const uint16_t ypos) { - highlightY = ypos; hmiFlag.select_flag = sel; const uint16_t c1 = sel ? hmiData.colorHighlight : hmiData.colorPopupBg, c2 = sel ? hmiData.colorPopupBg : hmiData.colorHighlight; @@ -80,7 +77,7 @@ void hmiPopup() { EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_CW || encoder_diffState == ENCODER_DIFF_CCW) { const bool change = encoder_diffState != ENCODER_DIFF_CW; - if (popupChange) popupChange(change); else drawSelectHighlight(change, highlightY); + if (popupChange) popupChange(change); else drawSelectHighlight(change); dwinUpdateLCD(); } } From 021ad7545e66395e3d680f7ae51af68adf31c293 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 Jan 2024 19:32:16 -0600 Subject: [PATCH 061/109] =?UTF-8?q?=F0=9F=8C=90=20Internationalize?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 91 ++++++++++++++------------- Marlin/src/lcd/language/language_en.h | 48 ++++++++++++++ 2 files changed, 94 insertions(+), 45 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 9fdd9528dc32..766b8750a1a0 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -999,7 +999,7 @@ void drawPrintFileMenu() { checkkey = ID_Menu; if (card.isMounted()) { if (SET_MENU(fileMenu, MSG_MEDIA_MENU, nr_sd_menu_items() + 1)) { - menuItemAdd(ICON_Back, F("Exit to Main Menu"), onDrawMenuItem, gotoMainMenu); + menuItemAdd(ICON_Back, GET_TEXT_F(MSG_EXIT_TO_MAIN_MENU), onDrawMenuItem, gotoMainMenu); for (uint8_t i = 0; i < nr_sd_menu_items(); ++i) menuItemAdd(onDrawFileName, onClickSDItem); } @@ -1092,9 +1092,10 @@ void drawInfoMenu() { DWINUI::drawCenteredString(268, F(CORP_WEBSITE)); } else { - DWINUI::drawCenteredString(102, F("Size")); - DWINUI::drawCenteredString(175, F("Firmware version")); - DWINUI::drawCenteredString(248, F("Build Datetime")); + DWINUI::drawCenteredString(102, GET_TEXT_F(MSG_INFO_SIZE)); + DWINUI::drawCenteredString(175, GET_TEXT_F(MSG_INFO_FWVERSION)); + DWINUI::drawCenteredString(248, GET_TEXT_F(MSG_INFO_BUILD)); + DWINUI::drawCenteredString(268, F(STRING_DISTRIBUTION_DATE)); } DWINUI::drawCenteredString(122, F(MACHINE_SIZE)); @@ -1373,8 +1374,8 @@ void eachMomentUpdate() { } else { DWINUI::drawCenteredString(hmiData.colorPopupTxt, 70, GET_TEXT_F(MSG_OUTAGE_RECOVERY)); - DWINUI::drawCenteredString(hmiData.colorPopupTxt, 147, F("It looks like the last")); - DWINUI::drawCenteredString(hmiData.colorPopupTxt, 167, F("file was interrupted.")); + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 147, GET_TEXT_F(MSG_OUTAGE_RECOVERY2)); + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 167, GET_TEXT_F(MSG_OUTAGE_RECOVERY3)); DWINUI::drawButton(BTN_Cancel, 26, 280); DWINUI::drawButton(BTN_Continue, 146, 280); } @@ -1544,7 +1545,7 @@ void dwinLevelingDone() { case MPCTEMP_START: DWINUI::drawCenteredString(hmiData.colorPopupTxt, 70, GET_TEXT_F(MSG_MPC_AUTOTUNE)); DWINUI::drawString(hmiData.colorPopupTxt, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("MPC target: Celsius")); - DWINUI::drawCenteredString(hmiData.colorPopupTxt, 92, F("for NOZZLE is running.")); + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 92, GET_TEXT_F(MSG_FOR_NOZZLE_RUNNING)); _maxtemp = thermalManager.hotend_maxtemp[0]; _target = 200; break; @@ -1553,7 +1554,7 @@ void dwinLevelingDone() { case PIDTEMP_START: DWINUI::drawCenteredString(hmiData.colorPopupTxt, 70, GET_TEXT_F(MSG_PID_AUTOTUNE)); DWINUI::drawString(hmiData.colorPopupTxt, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("PID target: Celsius")); - DWINUI::drawCenteredString(hmiData.colorPopupTxt, 92, F("for NOZZLE is running.")); + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 92, GET_TEXT_F(MSG_FOR_NOZZLE_RUNNING)); _maxtemp = thermalManager.hotend_maxtemp[0]; _target = hmiData.hotendPidT; break; @@ -1562,7 +1563,7 @@ void dwinLevelingDone() { case PIDTEMPBED_START: DWINUI::drawCenteredString(hmiData.colorPopupTxt, 70, GET_TEXT_F(MSG_PID_AUTOTUNE)); DWINUI::drawString(hmiData.colorPopupTxt, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("PID target: Celsius")); - DWINUI::drawCenteredString(hmiData.colorPopupTxt, 92, F("for BED is running.")); + DWINUI::drawCenteredString(hmiData.colorPopupTxt, 92, GET_TEXT_F(MSG_FOR_BED_RUNNING)); _maxtemp = BED_MAXTEMP; _target = hmiData.bedPidT; break; @@ -1587,14 +1588,14 @@ void dwinLevelingDone() { TERN_(MPCTEMP, case MPCTEMP_START:) TERN_(PIDTEMP, case PIDTEMP_START:) title.showCaption(GET_TEXT_F(MSG_HOTEND_TEMP_GRAPH)); - DWINUI::drawCenteredString(3, hmiData.colorPopupTxt, 75, F("Nozzle Temperature")); + DWINUI::drawCenteredString(3, hmiData.colorPopupTxt, 75, GET_TEXT_F(MSG_NOZZLE_TEMPERATURE)); _maxtemp = thermalManager.hotend_max_target(0); _target = thermalManager.degTargetHotend(0); break; #if ENABLED(PIDTEMPBED) case PIDTEMPBED_START: title.showCaption(GET_TEXT_F(MSG_BED_TEMP_GRAPH)); - DWINUI::drawCenteredString(3, hmiData.colorPopupTxt, 75, F("Bed Temperature")); + DWINUI::drawCenteredString(3, hmiData.colorPopupTxt, 75, GET_TEXT_F(MSG_BED_TEMPERATURE)); _maxtemp = BED_MAX_TARGET; _target = thermalManager.degTargetBed(); break; @@ -1647,7 +1648,7 @@ void dwinLevelingDone() { #if PROUI_TUNING_GRAPH dwinDrawPIDMPCPopup(); #else - dwinDrawPopup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), F("for Nozzle is running.")); + dwinDrawPopup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), GET_TEXT_F(MSG_FOR_NOZZLE_RUNNING)); #endif break; case PID_TEMP_TOO_HIGH: @@ -1661,7 +1662,7 @@ void dwinLevelingDone() { #if PROUI_TUNING_GRAPH dwinDrawPIDMPCPopup(); #else - dwinDrawPopup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), F("for BED is running.")); + dwinDrawPopup(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE), GET_TEXT_F(MSG_FOR_BED_RUNNING)); #endif break; #endif @@ -1695,7 +1696,7 @@ void dwinLevelingDone() { #if PROUI_TUNING_GRAPH dwinDrawPIDMPCPopup(); #else - dwinDrawPopup(ICON_TempTooHigh, GET_TEXT_F(MSG_MPC_AUTOTUNE), F("for Nozzle is running.")); + dwinDrawPopup(ICON_TempTooHigh, GET_TEXT_F(MSG_MPC_AUTOTUNE), GET_TEXT_F(MSG_FOR_NOZZLE_RUNNING)); #endif break; case MPC_TEMP_ERROR: @@ -2454,10 +2455,10 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, void trammingwizard() { if (hmiData.fullManualTramming) { - LCD_MESSAGE_F("Disable manual tramming"); + LCD_MESSAGE(MSG_DISABLE_MANUAL_TRAMMING); return; } - else LCD_MESSAGE_F("Tramming Wizard Start"); + LCD_MESSAGE(MSG_TRAMMING_WIZARD_START); DWINUI::clearMainArea(); meshViewer.drawMeshGrid(2, 2); // Indicate start. Draw the grid bed_mesh_t zval = {0}; @@ -2474,8 +2475,8 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, probe.stow(); meshViewer.drawMesh(zval, 2, 2); - DWINUI::drawCenteredString(140, F("Calculating average")); - DWINUI::drawCenteredString(160, F("and relative heights")); + DWINUI::drawCenteredString(140, GET_TEXT_F(MSG_CALCULATING_AVERAGE)); + DWINUI::drawCenteredString(160, GET_TEXT_F(MSG_AND RELATIVE_HEIGHTS)); safe_delay(1000); float avg = 0.0f; for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) avg += zval[x][y]; @@ -2490,8 +2491,8 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, if (ABS(meshViewer.max - meshViewer.min) < BED_TRAMMING_PROBE_TOLERANCE) { EXIT_TRAMWIZ: - DWINUI::drawCenteredString(140, F("Corners leveled")); - DWINUI::drawCenteredString(160, F("Tolerance achieved!")); + DWINUI::drawCenteredString(140, GET_TEXT_F(MSG_TRAMMING_DONE)); + DWINUI::drawCenteredString(160, GET_TEXT_F(MSG_TOLERANCE_ACHIEVED)); } else { uint8_t p = 0; @@ -2514,9 +2515,9 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, case 0b11 : plabel = GET_TEXT_F(MSG_TRAM_BR); break; default : plabel = F(""); break; } - DWINUI::drawCenteredString(120, F("Corners not leveled")); - DWINUI::drawCenteredString(140, F("Knob adjustment required")); - DWINUI::drawCenteredString((s ? COLOR_GREEN : COLOR_ERROR_RED), 160, (s ? F("Lower") : F("Raise"))); + DWINUI::drawCenteredString(120, GET_TEXT_F(MSG_CORNERS_NOT_LEVELED)); + DWINUI::drawCenteredString(140, GET_TEXT_F(MSG_KNOB_ADJUSTMENT_REQUIRED)); + DWINUI::drawCenteredString((s ? COLOR_GREEN : COLOR_ERROR_RED), 160, s ? GET_TEXT_F(MSG_LOWER) : GET_TEXT_F(MSG_RAISE)); DWINUI::drawCenteredString(COLOR_GREEN, 180, plabel); } DWINUI::drawButton(BTN_Continue, 86, 305); @@ -3239,7 +3240,7 @@ void drawMoveMenu() { #endif } updateMenu(moveMenu); - if (!all_axes_trusted()) LCD_MESSAGE_F("WARNING: Current position unknown. Home axes."); + if (!all_axes_trusted()) LCD_MESSAGE(MSG_POSITION_UNKNOWN); } #if HAS_HOME_OFFSET @@ -3787,24 +3788,24 @@ void drawMaxAccelMenu() { if (SET_MENU(selectColorMenu, MSG_COLORS_SELECT, 20)) { BACK_ITEM(drawAdvancedSettingsMenu); MENU_ITEM(ICON_StockConfiguration, MSG_RESTORE_DEFAULTS, onDrawMenuItem, restoreDefaultColors); - EDIT_ITEM_F(0, "Screen Background", onDrawSelColorItem, selColor, &hmiData.colorBackground); - EDIT_ITEM_F(0, "Cursor", onDrawSelColorItem, selColor, &hmiData.colorCursor); - EDIT_ITEM_F(0, "Title Background", onDrawSelColorItem, selColor, &hmiData.colorTitleBg); - EDIT_ITEM_F(0, "Title Text", onDrawSelColorItem, selColor, &hmiData.colorTitleTxt); - EDIT_ITEM_F(0, "Text", onDrawSelColorItem, selColor, &hmiData.colorText); - EDIT_ITEM_F(0, "Selected", onDrawSelColorItem, selColor, &hmiData.colorSelected); - EDIT_ITEM_F(0, "Split Line", onDrawSelColorItem, selColor, &hmiData.colorSplitLine); - EDIT_ITEM_F(0, "Highlight", onDrawSelColorItem, selColor, &hmiData.colorHighlight); - EDIT_ITEM_F(0, "Status Background", onDrawSelColorItem, selColor, &hmiData.colorStatusBg); - EDIT_ITEM_F(0, "Status Text", onDrawSelColorItem, selColor, &hmiData.colorStatusTxt); - EDIT_ITEM_F(0, "Popup Background", onDrawSelColorItem, selColor, &hmiData.colorPopupBg); - EDIT_ITEM_F(0, "Popup Text", onDrawSelColorItem, selColor, &hmiData.colorPopupTxt); - EDIT_ITEM_F(0, "Alert Background", onDrawSelColorItem, selColor, &hmiData.colorAlertBg); - EDIT_ITEM_F(0, "Alert Text", onDrawSelColorItem, selColor, &hmiData.colorAlertTxt); - EDIT_ITEM_F(0, "Percent Text", onDrawSelColorItem, selColor, &hmiData.colorPercentTxt); - EDIT_ITEM_F(0, "Bar Fill", onDrawSelColorItem, selColor, &hmiData.colorBarfill); - EDIT_ITEM_F(0, "Indicator value", onDrawSelColorItem, selColor, &hmiData.colorIndicator); - EDIT_ITEM_F(0, "Coordinate value", onDrawSelColorItem, selColor, &hmiData.colorCoordinate); + EDIT_ITEM(0, MSG_SCREEN_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorBackground); + EDIT_ITEM(0, MSG_CURSOR, onDrawSelColorItem, selColor, &hmiData.colorCursor); + EDIT_ITEM(0, MSG_TITLE_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorTitleBg); + EDIT_ITEM(0, MSG_TITLE_TEXT, onDrawSelColorItem, selColor, &hmiData.colorTitleTxt); + EDIT_ITEM(0, MSG_TEXT, onDrawSelColorItem, selColor, &hmiData.colorText); + EDIT_ITEM(0, MSG_SELECTED, onDrawSelColorItem, selColor, &hmiData.colorSelected); + EDIT_ITEM(0, MSG_SPLIT_LINE, onDrawSelColorItem, selColor, &hmiData.colorSplitLine); + EDIT_ITEM(0, MSG_HIGHLIGHT, onDrawSelColorItem, selColor, &hmiData.colorHighlight); + EDIT_ITEM(0, MSG_STATUS_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorStatusBg); + EDIT_ITEM(0, MSG_STATUS_TEXT, onDrawSelColorItem, selColor, &hmiData.colorStatusTxt); + EDIT_ITEM(0, MSG_POPUP_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorPopupBg); + EDIT_ITEM(0, MSG_POPUP_TEXT, onDrawSelColorItem, selColor, &hmiData.colorPopupTxt); + EDIT_ITEM(0, MSG_ALERT_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorAlertBg); + EDIT_ITEM(0, MSG_ALERT_TEXT, onDrawSelColorItem, selColor, &hmiData.colorAlertTxt); + EDIT_ITEM(0, MSG_PERCENT_TEXT, onDrawSelColorItem, selColor, &hmiData.colorPercentTxt); + EDIT_ITEM(0, MSG_BAR_FILL, onDrawSelColorItem, selColor, &hmiData.colorBarfill); + EDIT_ITEM(0, MSG_INDICATOR_VALUE, onDrawSelColorItem, selColor, &hmiData.colorIndicator); + EDIT_ITEM(0, MSG_COORDINATE_VALUE, onDrawSelColorItem, selColor, &hmiData.colorCoordinate); } updateMenu(selectColorMenu); } @@ -3974,7 +3975,7 @@ void drawMaxAccelMenu() { EDIT_ITEM(ICON_Zoffset, MSG_XATC_UPDATE_Z_OFFSET, onDrawPFloat2Menu, setZOffset, &BABY_Z_VAR); } updateMenu(zOffsetWizMenu); - if (!axis_is_trusted(Z_AXIS)) LCD_MESSAGE_F("WARNING: Z position unknown, move Z to home"); + if (!axis_is_trusted(Z_AXIS)) LCD_MESSAGE(MSG_POSITION_UNKNOWN_Z); } #endif @@ -4142,9 +4143,9 @@ void drawMaxAccelMenu() { EDIT_ITEM(ICON_MeshEditY, MSG_MESH_Y, onDrawPInt8Menu, setEditMeshY, &bedLevelTools.mesh_y); editZValueItem = EDIT_ITEM(ICON_MeshEditZ, MSG_MESH_EDIT_Z, onDrawPFloat3Menu, setEditZValue, &bedlevel.z_values[bedLevelTools.mesh_x][bedLevelTools.mesh_y]); #if HAS_BED_PROBE - MENU_ITEM_F(ICON_ProbeDeploy, "Probe for Z Value", onDrawMenuItem, bedLevelTools.probeXY); + MENU_ITEM(ICON_ProbeDeploy, MSG_PROBE_FOR_Z_VALUE, onDrawMenuItem, bedLevelTools.probeXY); #endif - MENU_ITEM_F(ICON_SetZOffset, "Zero Current Point", onDrawMenuItem, zeroPoint); + MENU_ITEM(ICON_SetZOffset, MSG_ZERO_CURRENT_POINT, onDrawMenuItem, zeroPoint); } updateMenu(editMeshMenu); } diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 553d9013a243..b72b7c23f855 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -115,6 +115,10 @@ namespace LanguageNarrow_en { LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); LSTR MSG_ERR_M428_TOO_FAR = _UxGT("MIN/MAX Too Far"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); + LSTR MSG_TRAMMING_DONE = _UxGT("Tramming done"); + LSTR MSG_LOWER = _UxGT("Lower"); + LSTR MSG_RAISE = _UxGT("Raise"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Select Origin"); LSTR MSG_LAST_VALUE_SP = _UxGT("Last value "); @@ -158,8 +162,12 @@ namespace LanguageNarrow_en { LSTR MSG_EXTRUDE = _UxGT("Extrude"); LSTR MSG_RETRACT = _UxGT("Retract"); LSTR MSG_MOVE_AXIS = _UxGT("Move Axis"); + LSTR MSG_BED_LEVELING = _UxGT("Bed Leveling"); LSTR MSG_LEVEL_BED = _UxGT("Level Bed"); + LSTR MSG_PROBE_FOR_Z_VALUE = _UxGT("Probe for Z Value"); + LSTR MSG_ZERO_CURRENT_POINT = _UxGT("Zero Current Point"); + LSTR MSG_BED_TRAMMING = _UxGT("Bed Tramming"); LSTR MSG_BED_TRAMMING_MANUAL = _UxGT("Manual Tramming"); LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Adjust bed until the probe triggers."); @@ -167,6 +175,7 @@ namespace LanguageNarrow_en { LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); LSTR MSG_NEXT_CORNER = _UxGT("Next Corner"); + LSTR MSG_MESH_EDITOR = _UxGT("Mesh Editor"); LSTR MSG_MESH_VIEWER = _UxGT("Mesh Viewer"); LSTR MSG_EDIT_MESH = _UxGT("Edit Mesh"); @@ -366,6 +375,8 @@ namespace LanguageNarrow_en { LSTR MSG_MPC_HEATING_PAST_200 = _UxGT("Heating to >200C"); LSTR MSG_MPC_COOLING_TO_AMBIENT = _UxGT("Cooling to ambient"); LSTR MSG_MPC_AUTOTUNE = _UxGT("MPC Autotune"); + LSTR MSG_FOR_NOZZLE_RUNNING = _UxGT("for NOZZLE is running."); + LSTR MSG_FOR_BED_RUNNING = _UxGT("for BED is running."); LSTR MSG_MPC_EDIT = _UxGT("Edit * MPC"); LSTR MSG_MPC_POWER = _UxGT("Heater Power"); LSTR MSG_MPC_POWER_E = _UxGT("Power *"); @@ -450,6 +461,8 @@ namespace LanguageNarrow_en { LSTR MSG_SCREEN_TIMEOUT = _UxGT("LCD Timeout (m)"); LSTR MSG_HOTEND_TEMP_GRAPH = _UxGT("Hotend Temp Graph"); LSTR MSG_BED_TEMP_GRAPH = _UxGT("Bed Temp Graph"); + LSTR MSG_NOZZLE_TEMPERATURE = _UxGT("Nozzle Temperature"); + LSTR MSG_BED_TEMPERATURE = _UxGT("Bed Temperature"); LSTR MSG_BRIGHTNESS_OFF = _UxGT("Backlight Off"); LSTR MSG_STORE_EEPROM = _UxGT("Store Settings"); LSTR MSG_LOAD_EEPROM = _UxGT("Load Settings"); @@ -671,6 +684,25 @@ namespace LanguageNarrow_en { LSTR MSG_COLORS_GREEN = _UxGT("Green"); LSTR MSG_COLORS_BLUE = _UxGT("Blue"); LSTR MSG_COLORS_WHITE = _UxGT("White"); + LSTR MSG_SCREEN_BACKGROUND = _UxGT("Screen Background"); + LSTR MSG_CURSOR = _UxGT("Cursor"); + LSTR MSG_TITLE_BACKGROUND = _UxGT("Title Background"); + LSTR MSG_TITLE_TEXT = _UxGT("Title Text"); + LSTR MSG_TEXT = _UxGT("Text"); + LSTR MSG_SELECTED = _UxGT("Selected"); + LSTR MSG_SPLIT_LINE = _UxGT("Split Line"); + LSTR MSG_HIGHLIGHT = _UxGT("Highlight"); + LSTR MSG_STATUS_BACKGROUND = _UxGT("Status Background"); + LSTR MSG_STATUS_TEXT = _UxGT("Status Text"); + LSTR MSG_POPUP_BACKGROUND = _UxGT("Popup Background"); + LSTR MSG_POPUP_TEXT = _UxGT("Popup Text"); + LSTR MSG_ALERT_BACKGROUND = _UxGT("Alert Background"); + LSTR MSG_ALERT_TEXT = _UxGT("Alert Text"); + LSTR MSG_PERCENT_TEXT = _UxGT("Percent Text"); + LSTR MSG_BAR_FILL = _UxGT("Bar Fill"); + LSTR MSG_INDICATOR_VALUE = _UxGT("Indicator value"); + LSTR MSG_COORDINATE_VALUE = _UxGT("Coordinate value"); + LSTR MSG_UI_LANGUAGE = _UxGT("UI Language"); LSTR MSG_SOUND_ENABLE = _UxGT("Enable sound"); LSTR MSG_LOCKSCREEN = _UxGT("Lock Screen"); @@ -711,6 +743,7 @@ namespace LanguageNarrow_en { LSTR MSG_FANCHECK = _UxGT("Fan Tacho Check"); LSTR MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); + LSTR MSG_EXIT_TO_MAIN_MENU = _UxGT("Exit to Main Menu"); LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); LSTR MSG_MMU2_MENU = _UxGT("MMU"); @@ -914,6 +947,21 @@ namespace LanguageWide_en { LSTR MSG_INFO_PRINT_TIME = _UxGT("Print Time"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Longest Job Time"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded Total"); + + LSTR MSG_OUTAGE_RECOVERY2 = _UxGT("It looks like the last"); + LSTR MSG_OUTAGE_RECOVERY3 = _UxGT("file was interrupted."); + + LSTR MSG_DISABLE_MANUAL_TRAMMING = _UxGT("Disable manual tramming"); + LSTR MSG_TRAMMING_WIZARD_START = _UxGT("Tramming Wizard Start"); + LSTR MSG_CALCULATING_AVERAGE = _UxGT("Calculating average"); + LSTR MSG_AND_RELATIVE_HEIGHTS = _UxGT("and relative heights"); + LSTR MSG_TOLERANCE_ACHIEVED = _UxGT("Tolerance achieved!"); + LSTR MSG_CORNERS_NOT_LEVELED = _UxGT("Corners not leveled"); + LSTR MSG_KNOB_ADJUSTMENT_REQUIRED = _UxGT("Knob adjustment required"); + + LSTR MSG_POSITION_UNKNOWN = _UxGT("WARNING: Current position unknown. Home axes."); + LSTR MSG_POSITION_UNKNOWN_Z = _UxGT("WARNING: Z position unknown, move Z to home"); + #endif } From 34fbc575d5779f92c03a5a7fb40d48d67980d834 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 Jan 2024 19:38:34 -0600 Subject: [PATCH 062/109] prettify --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 32 +++++++++++++++--------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 766b8750a1a0..73f911a743c8 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -3788,23 +3788,23 @@ void drawMaxAccelMenu() { if (SET_MENU(selectColorMenu, MSG_COLORS_SELECT, 20)) { BACK_ITEM(drawAdvancedSettingsMenu); MENU_ITEM(ICON_StockConfiguration, MSG_RESTORE_DEFAULTS, onDrawMenuItem, restoreDefaultColors); - EDIT_ITEM(0, MSG_SCREEN_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorBackground); - EDIT_ITEM(0, MSG_CURSOR, onDrawSelColorItem, selColor, &hmiData.colorCursor); + EDIT_ITEM(0, MSG_SCREEN_BACKGROUND,onDrawSelColorItem, selColor, &hmiData.colorBackground); + EDIT_ITEM(0, MSG_CURSOR, onDrawSelColorItem, selColor, &hmiData.colorCursor); EDIT_ITEM(0, MSG_TITLE_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorTitleBg); - EDIT_ITEM(0, MSG_TITLE_TEXT, onDrawSelColorItem, selColor, &hmiData.colorTitleTxt); - EDIT_ITEM(0, MSG_TEXT, onDrawSelColorItem, selColor, &hmiData.colorText); - EDIT_ITEM(0, MSG_SELECTED, onDrawSelColorItem, selColor, &hmiData.colorSelected); - EDIT_ITEM(0, MSG_SPLIT_LINE, onDrawSelColorItem, selColor, &hmiData.colorSplitLine); - EDIT_ITEM(0, MSG_HIGHLIGHT, onDrawSelColorItem, selColor, &hmiData.colorHighlight); - EDIT_ITEM(0, MSG_STATUS_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorStatusBg); - EDIT_ITEM(0, MSG_STATUS_TEXT, onDrawSelColorItem, selColor, &hmiData.colorStatusTxt); + EDIT_ITEM(0, MSG_TITLE_TEXT, onDrawSelColorItem, selColor, &hmiData.colorTitleTxt); + EDIT_ITEM(0, MSG_TEXT, onDrawSelColorItem, selColor, &hmiData.colorText); + EDIT_ITEM(0, MSG_SELECTED, onDrawSelColorItem, selColor, &hmiData.colorSelected); + EDIT_ITEM(0, MSG_SPLIT_LINE, onDrawSelColorItem, selColor, &hmiData.colorSplitLine); + EDIT_ITEM(0, MSG_HIGHLIGHT, onDrawSelColorItem, selColor, &hmiData.colorHighlight); + EDIT_ITEM(0, MSG_STATUS_BACKGROUND,onDrawSelColorItem, selColor, &hmiData.colorStatusBg); + EDIT_ITEM(0, MSG_STATUS_TEXT, onDrawSelColorItem, selColor, &hmiData.colorStatusTxt); EDIT_ITEM(0, MSG_POPUP_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorPopupBg); - EDIT_ITEM(0, MSG_POPUP_TEXT, onDrawSelColorItem, selColor, &hmiData.colorPopupTxt); + EDIT_ITEM(0, MSG_POPUP_TEXT, onDrawSelColorItem, selColor, &hmiData.colorPopupTxt); EDIT_ITEM(0, MSG_ALERT_BACKGROUND, onDrawSelColorItem, selColor, &hmiData.colorAlertBg); - EDIT_ITEM(0, MSG_ALERT_TEXT, onDrawSelColorItem, selColor, &hmiData.colorAlertTxt); - EDIT_ITEM(0, MSG_PERCENT_TEXT, onDrawSelColorItem, selColor, &hmiData.colorPercentTxt); - EDIT_ITEM(0, MSG_BAR_FILL, onDrawSelColorItem, selColor, &hmiData.colorBarfill); - EDIT_ITEM(0, MSG_INDICATOR_VALUE, onDrawSelColorItem, selColor, &hmiData.colorIndicator); + EDIT_ITEM(0, MSG_ALERT_TEXT, onDrawSelColorItem, selColor, &hmiData.colorAlertTxt); + EDIT_ITEM(0, MSG_PERCENT_TEXT, onDrawSelColorItem, selColor, &hmiData.colorPercentTxt); + EDIT_ITEM(0, MSG_BAR_FILL, onDrawSelColorItem, selColor, &hmiData.colorBarfill); + EDIT_ITEM(0, MSG_INDICATOR_VALUE, onDrawSelColorItem, selColor, &hmiData.colorIndicator); EDIT_ITEM(0, MSG_COORDINATE_VALUE, onDrawSelColorItem, selColor, &hmiData.colorCoordinate); } updateMenu(selectColorMenu); @@ -3815,9 +3815,9 @@ void drawMaxAccelMenu() { if (SET_MENU(getColorMenu, MSG_COLORS_GET, 5)) { BACK_ITEM(dwinApplyColor); MENU_ITEM(ICON_Cancel, MSG_BUTTON_CANCEL, onDrawMenuItem, drawSelectColorsMenu); - MENU_ITEM(0, MSG_COLORS_RED, onDrawGetColorItem, setRGBColor); + MENU_ITEM(0, MSG_COLORS_RED, onDrawGetColorItem, setRGBColor); MENU_ITEM(1, MSG_COLORS_GREEN, onDrawGetColorItem, setRGBColor); - MENU_ITEM(2, MSG_COLORS_BLUE, onDrawGetColorItem, setRGBColor); + MENU_ITEM(2, MSG_COLORS_BLUE, onDrawGetColorItem, setRGBColor); } updateMenu(getColorMenu); dwinDrawRectangle(1, *menuData.intPtr, 20, 315, DWIN_WIDTH - 20, 335); From e7c0ef805fbb089a5897cc66422a00c18c4fd8a4 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 21 Jan 2024 01:24:09 -0500 Subject: [PATCH 063/109] update spanish lang --- Marlin/src/lcd/language/language_es.h | 50 +++++++++++++++++++++++++++ 1 file changed, 50 insertions(+) diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 5bee09b2428b..c4aaa102b7a3 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -71,7 +71,15 @@ namespace LanguageNarrow_es { LSTR MSG_LEVEL_BED_DONE = _UxGT("¡Nivelación lista!"); LSTR MSG_Z_FADE_HEIGHT = _UxGT("Compen. Altura"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ajustar desfases"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Origen desfase X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Origen desfase Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Origen desfase Z"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicada"); + LSTR MSG_ERR_M428_TOO_FAR = _UxGT("MIN/MÁX demasiado lejos"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("Asistente de Tramming"); + LSTR MSG_TRAMMING_DONE = _UxGT("Tramming hecho"); + LSTR MSG_LOWER = _UxGT("Bajar"); + LSTR MSG_RAISE = _UxGT("Elevar"); LSTR MSG_PREHEAT_1 = _UxGT("Precal. ") PREHEAT_1_LABEL; LSTR MSG_PREHEAT_1_H = _UxGT("Precal. ") PREHEAT_1_LABEL " ~"; @@ -102,10 +110,15 @@ namespace LanguageNarrow_es { LSTR MSG_EXTRUDE = _UxGT("Extruir"); LSTR MSG_RETRACT = _UxGT("Retraer"); LSTR MSG_MOVE_AXIS = _UxGT("Mover ejes"); + LSTR MSG_BED_LEVELING = _UxGT("Nivelando Cama"); LSTR MSG_LEVEL_BED = _UxGT("Nivelar Cama"); + LSTR MSG_PROBE_FOR_Z_VALUE = _UxGT("Sonda para valor Z"); + LSTR MSG_ZERO_CURRENT_POINT = _UxGT("Punto de corriente cero"); + LSTR MSG_BED_TRAMMING = _UxGT("Recorrido Cama"); LSTR MSG_NEXT_CORNER = _UxGT("Siguente Esquina"); + LSTR MSG_MESH_EDITOR = _UxGT("Editor Mallado"); LSTR MSG_EDIT_MESH = _UxGT("Editar Mallado"); LSTR MSG_EDITING_STOPPED = _UxGT("Ed. Mallado parada"); @@ -259,6 +272,8 @@ namespace LanguageNarrow_es { LSTR MSG_LCD_OFF = _UxGT("Apg"); LSTR MSG_PID_AUTOTUNE = _UxGT("PID Auto-ajuste"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Auto-ajuste *"); + LSTR MSG_FOR_NOZZLE_RUNNING = _UxGT("para BOQUILLA está funcionando."); + LSTR MSG_FOR_BED_RUNNING = _UxGT("para CAMA está funcionando."); LSTR MSG_SELECT_E = _UxGT("Seleccionar *"); LSTR MSG_ACC = _UxGT("Aceleración"); LSTR MSG_JERK = _UxGT("Jerk"); @@ -304,6 +319,8 @@ namespace LanguageNarrow_es { LSTR MSG_ADVANCE_K = _UxGT("Avance K"); LSTR MSG_ADVANCE_K_E = _UxGT("Avance K *"); LSTR MSG_CONTRAST = _UxGT("Contraste LCD"); + LSTR MSG_NOZZLE_TEMPERATURE = _UxGT("Temperatura de la boquilla"); + LSTR MSG_BED_TEMPERATURE = _UxGT("Temperatura de la cama"); LSTR MSG_STORE_EEPROM = _UxGT("Guardar EEPROM"); LSTR MSG_LOAD_EEPROM = _UxGT("Cargar EEPROM"); LSTR MSG_RESTORE_DEFAULTS = _UxGT("Rest. fábrica"); @@ -446,6 +463,24 @@ namespace LanguageNarrow_es { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo cabina"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); + LSTR MSG_SCREEN_BACKGROUND = _UxGT("Fondo de pantalla"); + LSTR MSG_CURSOR = _UxGT("Puntero"); + LSTR MSG_TITLE_BACKGROUND = _UxGT("Fondo del título"); + LSTR MSG_TITLE_TEXT = _UxGT("Texto del título"); + LSTR MSG_TEXT = _UxGT("Texto"); + LSTR MSG_SELECTED = _UxGT("Seleccionado"); + LSTR MSG_SPLIT_LINE = _UxGT("Linea divisoria"); + LSTR MSG_HIGHLIGHT = _UxGT("Resaltar"); + LSTR MSG_STATUS_BACKGROUND = _UxGT("Fondo de estado"); + LSTR MSG_STATUS_TEXT = _UxGT("Texto de estado"); + LSTR MSG_POPUP_BACKGROUND = _UxGT("Fondo emergente"); + LSTR MSG_POPUP_TEXT = _UxGT("Texto emergente"); + LSTR MSG_ALERT_BACKGROUND = _UxGT("Fondo de alerta"); + LSTR MSG_ALERT_TEXT = _UxGT("Texto de alerta"); + LSTR MSG_PERCENT_TEXT = _UxGT("Texto porcentual"); + LSTR MSG_BAR_FILL = _UxGT("Relleno de barra"); + LSTR MSG_INDICATOR_VALUE = _UxGT("Valor del indicador"); + LSTR MSG_COORDINATE_VALUE = _UxGT("Valor de coordenada"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Impresiones"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); @@ -471,6 +506,7 @@ namespace LanguageNarrow_es { LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist. filamento mm"); LSTR MSG_KILL_HOMING_FAILED = _UxGT("Ir a origen Fallado"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondeo Fallado"); + LSTR MSG_EXIT_TO_MAIN_MENU = _UxGT("Salir al menú principal"); LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ELIJE FILAMENTO"); LSTR MSG_MMU2_MENU = _UxGT("MMU"); @@ -557,6 +593,20 @@ namespace LanguageWide_es { LSTR MSG_INFO_PRINT_TIME = _UxGT("Tiempo total de imp."); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Impresión más larga"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruido"); + + LSTR MSG_OUTAGE_RECOVERY2 = _UxGT("Parece que el último"); + LSTR MSG_OUTAGE_RECOVERY3 = _UxGT("archivo fue interrumpido."); + + LSTR MSG_DISABLE_MANUAL_TRAMMING = _UxGT("Deshabilitar tramming manual"); + LSTR MSG_TRAMMING_WIZARD_START = _UxGT("Iniciar asistente de tramming"); + LSTR MSG_CALCULATING_AVERAGE = _UxGT("Calculando promedio"); + LSTR MSG_AND_RELATIVE_HEIGHTS = _UxGT("y alturas relativas"); + LSTR MSG_TOLERANCE_ACHIEVED = _UxGT("¡Tolerancia lograda!"); + LSTR MSG_CORNERS_NOT_LEVELED = _UxGT("Esquinas no niveladas"); + LSTR MSG_KNOB_ADJUSTMENT_REQUIRED = _UxGT("Se require ajuste de perilla"); + + LSTR MSG_POSITION_UNKNOWN = _UxGT("ADVERTENCIA: Posición actual desconocida. Ejes de inicio."); + LSTR MSG_POSITION_UNKNOWN_Z = _UxGT("ADVERTENCIA: Posición Z desconocida, mueva Z a inicio"); #endif } From 4187388ad80642e0fad7442429909efde6c029c9 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 21 Jan 2024 03:55:44 -0500 Subject: [PATCH 064/109] missing _ typo error --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 73f911a743c8..aa747953f8a3 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2476,7 +2476,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, meshViewer.drawMesh(zval, 2, 2); DWINUI::drawCenteredString(140, GET_TEXT_F(MSG_CALCULATING_AVERAGE)); - DWINUI::drawCenteredString(160, GET_TEXT_F(MSG_AND RELATIVE_HEIGHTS)); + DWINUI::drawCenteredString(160, GET_TEXT_F(MSG_AND_RELATIVE_HEIGHTS)); safe_delay(1000); float avg = 0.0f; for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) avg += zval[x][y]; From 938b0fbaedf546e42f0872a88641a289997f67d5 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 21 Jan 2024 04:01:50 -0500 Subject: [PATCH 065/109] revert pinsDebug_list --- Marlin/src/pins/pinsDebug_list.h | 15 --------------- 1 file changed, 15 deletions(-) diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index f0fa7763816d..fa6cbf49b945 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -2300,36 +2300,21 @@ // #if PIN_EXISTS(SDIO_D0) REPORT_NAME_DIGITAL(__LINE__, SDIO_D0_PIN) -#elif defined(BOARD_SDIO_D0) - REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D0) #endif #if PIN_EXISTS(SDIO_D1) REPORT_NAME_DIGITAL(__LINE__, SDIO_D1_PIN) -#elif defined(BOARD_SDIO_D1) - REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D1) #endif #if PIN_EXISTS(SDIO_D2) REPORT_NAME_DIGITAL(__LINE__, SDIO_D2_PIN) -#elif defined(BOARD_SDIO_D2) - REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D2) #endif #if PIN_EXISTS(SDIO_D3) REPORT_NAME_DIGITAL(__LINE__, SDIO_D3_PIN) -#elif defined(BOARD_SDIO_D3) - REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_D3) #endif #if PIN_EXISTS(SDIO_CK) REPORT_NAME_DIGITAL(__LINE__, SDIO_CK_PIN) -#elif defined(BOARD_SDIO_CLK) - REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_CLK) #endif #if PIN_EXISTS(SDIO_CMD) REPORT_NAME_DIGITAL(__LINE__, SDIO_CMD_PIN) -#elif defined(BOARD_SDIO_CMD) - REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_CMD) -#endif -#if defined(BOARD_SDIO_DET) - REPORT_NAME_DIGITAL(__LINE__, BOARD_SDIO_DET) #endif // From 10b061a8542a647909612ba021d2bff9baadff0f Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 21 Jan 2024 04:05:52 -0500 Subject: [PATCH 066/109] remove bool from readEEPROM --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index aa747953f8a3..1803a6cfdd68 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2046,9 +2046,8 @@ void gotoConfirmToPrint() { } void readEEPROM() { - const bool success = settings.load(); dwinRedrawScreen(); - DONE_BUZZ(success); + DONE_BUZZ(settings.load()); } void resetEEPROM() { From 9eb38a0417399bb794e583c4c1fd21e88c7a385c Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 21 Jan 2024 04:25:17 -0500 Subject: [PATCH 067/109] 4 arg dwinIconShow unused, rename dacaiIconShow --- Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp index 7c71b8fc5974..e72752fdee41 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp @@ -52,14 +52,6 @@ void dwinDrawQR(uint8_t QR_Pixel, uint16_t x, uint16_t y, char *string) { dwinSend(i); } -// Draw an Icon with transparent background -// libID: Icon library ID -// picID: Icon ID -// x/y: Upper-left point -void dwinIconShow(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { - dwinIconShow(false, false, true, libID, picID, x, y); -} - // Copy area from current virtual display area to current screen // xStart/yStart: Upper-left of virtual area // xEnd/yEnd: Lower-right of virtual area @@ -135,7 +127,7 @@ void dwinWriteToMem(uint8_t mem, uint16_t addr, uint16_t length, uint8_t *data) } // Draw an Icon from SRAM without background transparency for DACAI Screens support -void DACAI_ICON_Show(uint16_t x, uint16_t y, uint16_t addr) { +void dacaiIconShow(uint16_t x, uint16_t y, uint16_t addr) { NOMORE(x, DWIN_WIDTH - 1); NOMORE(y, DWIN_HEIGHT - 1); size_t i = 0; @@ -148,7 +140,7 @@ void DACAI_ICON_Show(uint16_t x, uint16_t y, uint16_t addr) { void dwinIconShow(uint16_t x, uint16_t y, uint16_t addr) { #if ENABLED(DACAI_DISPLAY) - DACAI_ICON_Show(x, y, addr); + dacaiIconShow(x, y, addr); #else dwinIconShow(0, 0, 1, x, y, addr); #endif From f0249ac80953a525b7064026a5a61d2345008bd3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 Jan 2024 06:10:32 -0600 Subject: [PATCH 068/109] fix some code wrappers --- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 6 +++--- Marlin/src/lcd/e3v2/proui/dwin.cpp | 8 ++++---- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 58eb8f3162c9..1126b4a4b62c 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -808,7 +808,7 @@ void MarlinUI::draw_status_message(const bool blink) { if (printJobOngoing()) { const duration_t remaint = get_remaining_time(); timepos = TPOFFSET - remaint.toDigital(buffer); - TERN_(NOT(LCD_INFO_SCREEN_STYLE), lcd_put_lchar(timepos - 1, 2, 0x20);) + IF_DISABLED(LCD_INFO_SCREEN_STYLE, lcd_put_lchar(timepos - 1, 2, 0x20)); lcd_put_lchar(TERN(LCD_INFO_SCREEN_STYLE, 11, timepos), 2, 'R'); lcd_put_u8str(buffer); } @@ -820,7 +820,7 @@ void MarlinUI::draw_status_message(const bool blink) { const duration_t interactt = interaction_time; if (printingIsActive() && interactt.value) { timepos = TPOFFSET - interactt.toDigital(buffer); - TERN_(NOT(LCD_INFO_SCREEN_STYLE), lcd_put_lchar(timepos - 1, 2, 0x20);) + IF_DISABLED(LCD_INFO_SCREEN_STYLE, lcd_put_lchar(timepos - 1, 2, 0x20)); lcd_put_lchar(TERN(LCD_INFO_SCREEN_STYLE, 11, timepos), 2, 'C'); lcd_put_u8str(buffer); } @@ -832,7 +832,7 @@ void MarlinUI::draw_status_message(const bool blink) { if (printJobOngoing()) { const duration_t elapsedt = print_job_timer.duration(); timepos = TPOFFSET - elapsedt.toDigital(buffer); - TERN_(NOT(LCD_INFO_SCREEN_STYLE), lcd_put_lchar(timepos - 1, 2, 0x20);) + IF_DISABLED(LCD_INFO_SCREEN_STYLE, lcd_put_lchar(timepos - 1, 2, 0x20)); lcd_put_lchar(TERN(LCD_INFO_SCREEN_STYLE, 11, timepos), 2, 'E'); lcd_put_u8str(buffer); } diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 1803a6cfdd68..40c8e0266d7a 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1611,11 +1611,11 @@ void dwinLevelingDone() { } void drawHPlot() { - TERN_(PIDTEMP, dwinDrawPlot(PIDTEMP_START);) - TERN_(MPCTEMP, dwinDrawPlot(MPCTEMP_START);) + TERN_(PIDTEMP, dwinDrawPlot(PIDTEMP_START)); + TERN_(MPCTEMP, dwinDrawPlot(MPCTEMP_START)); } void drawBPlot() { - TERN_(PIDTEMPBED, dwinDrawPlot(PIDTEMPBED_START);) + TERN_(PIDTEMPBED, dwinDrawPlot(PIDTEMPBED_START)); } #endif // PROUI_ITEM_PLOT @@ -2058,7 +2058,7 @@ void gotoConfirmToPrint() { #if HAS_MESH void saveMesh() { - TERN_(MESH_BED_LEVELING, manualMeshSave();) + TERN_(MESH_BED_LEVELING, manualMeshSave()); TERN(AUTO_BED_LEVELING_UBL, ublMeshSave(), writeEEPROM()); } #endif From 73816f991c83d47cf7eafc90e55df25d5db035a5 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 21 Jan 2024 21:35:46 -0500 Subject: [PATCH 069/109] wrappers cont. --- Marlin/src/gcode/calibrate/M48.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index b1b5b64934a0..9d4a130168f9 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -59,7 +59,7 @@ void GcodeSuite::M48() { #if ENABLED(DWIN_LCD_PROUI) - TERN_(ADVANCED_PAUSE_FEATURE, dwinPopupPause(GET_TEXT_F(MSG_M48_TEST));) + TERN_(ADVANCED_PAUSE_FEATURE, dwinPopupPause(GET_TEXT_F(MSG_M48_TEST))); hmiSaveProcessID(ID_NothingToDo); #endif From d41f826e9e63bcec714c4a5f7d1806b642aedc88 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 Jan 2024 22:19:39 -0600 Subject: [PATCH 070/109] move test --- buildroot/tests/STM32F103RE_creality | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index cf3aecb1906e..e2e6e18f41ea 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -9,12 +9,6 @@ set -e # # Build with configs included in the PR # -use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" -opt_disable DWIN_CREALITY_LCD -opt_enable DWIN_LCD_PROUI -opt_add NO_AUTO_ASSIGN_WARNING -exec_test $1 $2 "Ender-3 V2 - ProUI (Default)" "$3" - use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING BLTOUCH AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING exec_test $1 $2 "Ender-3 V2 - CrealityUI" "$3" @@ -29,6 +23,12 @@ opt_disable DWIN_CREALITY_LCD PIDTEMP opt_enable DWIN_MARLINUI_LANDSCAPE LCD_ENDSTOP_TEST AUTO_BED_LEVELING_UBL BLTOUCH Z_SAFE_HOMING MPCTEMP MPC_AUTOTUNE exec_test $1 $2 "Ender-3 V2 - MarlinUI (UBL+BLTOUCH, MPCTEMP, LCD_ENDSTOP_TEST)" "$3" +use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" +opt_disable DWIN_CREALITY_LCD +opt_enable DWIN_LCD_PROUI +opt_add NO_AUTO_ASSIGN_WARNING +exec_test $1 $2 "Ender-3 V2 - ProUI (Default)" "$3" + use_example_configs "Creality/Ender-3 S1/STM32F1" opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CANCEL_OBJECTS FWRETRACT EVENT_GCODE_SD_ABORT opt_enable DWIN_LCD_PROUI INDIVIDUAL_AXIS_HOMING_SUBMENU SET_PROGRESS_MANUALLY SET_PROGRESS_PERCENT STATUS_MESSAGE_SCROLLING \ From 26f6dcadc82bc806e8e987bcd5908ac0d60fcc28 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 Jan 2024 23:14:32 -0600 Subject: [PATCH 071/109] =?UTF-8?q?=E2=80=A6more=E2=80=A6?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 8 ++--- Marlin/src/inc/Conditionals_LCD.h | 14 +++++++-- Marlin/src/lcd/e3v2/common/dwin_color.h | 26 ++++++++-------- Marlin/src/lcd/e3v2/creality/dwin.cpp | 40 ++++++++++++++----------- Marlin/src/lcd/e3v2/proui/dwin.cpp | 2 +- Marlin/src/lcd/marlinui.cpp | 3 +- Marlin/src/lcd/marlinui.h | 10 +++---- Marlin/src/lcd/tft/ui_color_ui.cpp | 3 +- Marlin/src/libs/numtostr.h | 4 +-- 9 files changed, 62 insertions(+), 48 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 4b8dbec768a5..b08ae54cdc87 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -884,11 +884,9 @@ void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullp // Echo the LCD message to serial for extra context if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLN(lcd_error); } - #if HAS_DISPLAY && DISABLED(DWIN_CREALITY_LCD) - ui.kill_screen(lcd_error ?: GET_TEXT_F(MSG_KILLED), lcd_component ?: FPSTR(NUL_STR)); - #else - UNUSED(lcd_error); UNUSED(lcd_component); - #endif + ui.kill_screen(lcd_error ?: GET_TEXT_F(MSG_KILLED), lcd_component ?: FPSTR(NUL_STR)); + + IF_DISABLED(HAS_DISPLAY, UNUSED(lcd_component)); TERN_(HAS_TFT_LVGL_UI, lv_draw_error_message(lcd_error)); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index e4e56d420b81..88a74bafed89 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1076,15 +1076,23 @@ #if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, HAS_DWIN_E3V2) /** - * HAS_DISPLAY indicates the display uses these MarlinUI methods... + * HAS_DISPLAY provides these MarlinUI settings... + * - SHOW_BOOTSCREEN and sub-options + * - SOUND_MENU_ITEM, SOUND_ON_DEFAULT + * - LCD_TIMEOUT_TO_STATUS, STATUS_MESSAGE_SCROLLING, STATUS_MESSAGE_TIMEOUT_SEC + * - LCD_DECIMAL_SMALL_XY + * - LCD_SHOW_E_TOTAL + * - SHOW_TEMPERATURE_BELOW_ZERO + * - LED_CONTROL_MENU and sub-options + * + * ...and indicates the LCD is handled in these marlinui.cpp shared methods... * - update * - abort_print * - pause_print * - resume_print * - poweroff (for PSU_CONTROL and HAS_MARLINUI_MENU) * - * ...and implements these MarlinUI methods: - * - zoffset_overlay (if BABYSTEP_GFX_OVERLAY or MESH_EDIT_GFX_OVERLAY are supported) + * ...and implements these MarlinUI methods: * - draw_kill_screen * - kill_screen * - draw_status_message diff --git a/Marlin/src/lcd/e3v2/common/dwin_color.h b/Marlin/src/lcd/e3v2/common/dwin_color.h index 0185c3969894..1196ac0be1d0 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_color.h +++ b/Marlin/src/lcd/e3v2/common/dwin_color.h @@ -28,18 +28,18 @@ #define GetBColor(color) ((color >> 0) & 0x1F) // RGB565 colors: https://rgbcolorpicker.com/565 -#define COLOR_WHITE 0xFFFF +#define COLOR_WHITE RGB(0x1F, 0x3F, 0x1F) #define COLOR_YELLOW RGB(0x1F, 0x3F, 0x00) #define COLOR_RED RGB(0x1F, 0x00, 0x00) -#define COLOR_ERROR_RED 0xB000 // Error! -#define COLOR_BG_RED 0xF00F // Red background color -#define COLOR_BG_WINDOW 0x31E8 // Popup background color -#define COLOR_BG_BLUE 0x1125 // Dark blue background color -#define COLOR_BG_BLACK 0x0841 // Black background color -#define COLOR_ICONBLUE 0x45FA // Lighter blue that matches icons/accents -#define COLOR_POPUP_TEXT 0xD6BA // Popup font background color -#define COLOR_LINE 0x3A6A // Split line color -#define COLOR_RECTANGLE 0xEE2F // Blue square cursor color -#define COLOR_PERCENT 0xFE29 // Percentage color -#define COLOR_BARFILL 0x10E4 // Fill color of progress bar -#define COLOR_SELECT 0x33BB // Selected color +#define COLOR_ERROR_RED RGB(0x16, 0x00, 0x00) // Error! +#define COLOR_BG_RED RGB(0x1E, 0x00, 0x0F) // Red background color +#define COLOR_BG_WINDOW RGB(0x06, 0x0F, 0x08) // Popup background color +#define COLOR_BG_BLUE RGB(0x02, 0x09, 0x05) // Dark blue background color +#define COLOR_BG_BLACK RGB(0x01, 0x02, 0x01) // Black background color +#define COLOR_ICONBLUE RGB(0x08, 0x2F, 0x1A) // Lighter blue that matches icons/accents +#define COLOR_POPUP_TEXT RGB(0x1A, 0x35, 0x1A) // Popup font background color +#define COLOR_LINE RGB(0x07, 0x13, 0x0A) // Split line color +#define COLOR_RECTANGLE RGB(0x1D, 0x31, 0x0F) // Blue square cursor color +#define COLOR_PERCENT RGB(0x1F, 0x31, 0x09) // Percentage color +#define COLOR_BARFILL RGB(0x02, 0x07, 0x04) // Fill color of progress bar +#define COLOR_SELECT RGB(0x06, 0x1D, 0x1B) // Selected color diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index e3ee67353da2..3f11f50dc1ee 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -33,6 +33,10 @@ //#define USE_STRING_HEADINGS //#define USE_STRING_TITLES +#if DISABLED(PROBE_MANUALLY) && ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) + #define HAS_ONESTEP_LEVELING 1 +#endif + #if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) #define JUST_BABYSTEP 1 #endif @@ -60,7 +64,7 @@ #include "../../../feature/host_actions.h" #endif -#if HAS_LEVELING +#if HAS_ONESTEP_LEVELING #include "../../../feature/bedlevel/bedlevel.h" #endif @@ -496,7 +500,7 @@ void drawBackFirst(const bool is_sel=true) { #define PREHEAT_CASE_TOTAL PREHEAT_CASE_SAVE #define ADVSET_CASE_HOMEOFF 1 -#define ADVSET_CASE_PROBEOFF (ADVSET_CASE_HOMEOFF + ENABLED(HAS_AUTOLEVEL)) +#define ADVSET_CASE_PROBEOFF (ADVSET_CASE_HOMEOFF + ENABLED(HAS_ONESTEP_LEVELING)) #define ADVSET_CASE_HEPID (ADVSET_CASE_PROBEOFF + ENABLED(HAS_HOTEND)) #define ADVSET_CASE_BEDPID (ADVSET_CASE_HEPID + ENABLED(HAS_HEATED_BED)) #define ADVSET_CASE_PWRLOSSR (ADVSET_CASE_BEDPID + ENABLED(POWER_LOSS_RECOVERY)) @@ -1131,7 +1135,7 @@ void popupWindowHome(const bool parking/*=false*/) { } } -#if HAS_AUTOLEVEL +#if HAS_ONESTEP_LEVELING void popupWindowLeveling() { clearMainWindow(); @@ -1258,7 +1262,7 @@ void gotoMainMenu() { iconPrint(); iconPrepare(); iconControl(); - TERN(HAS_AUTOLEVEL, iconLeveling, iconStartInfo)(); + TERN(HAS_ONESTEP_LEVELING, iconLeveling, iconStartInfo)(); } void hmiPlanMove(const feedRate_t fr_mm_s) { @@ -1816,6 +1820,8 @@ void MarlinUI::update() { void MarlinUI::refresh() { /* Nothing to see here */ } +void MarlinUI::kill_screen(FSTR_P const, FSTR_P const) { /* Nothing to see here */ } + #if HAS_LCD_BRIGHTNESS void MarlinUI::_set_brightness() { dwinLCDBrightness(backlight ? brightness : 0); } #endif @@ -2088,7 +2094,7 @@ void hmiMainMenu() { case PAGE_PRINT: iconPrint(); break; case PAGE_PREPARE: iconPrint(); iconPrepare(); break; case PAGE_CONTROL: iconPrepare(); iconControl(); break; - case PAGE_INFO_LEVELING: iconControl(); TERN(HAS_AUTOLEVEL, iconLeveling, iconStartInfo)(); break; + case PAGE_INFO_LEVELING: iconControl(); TERN(HAS_ONESTEP_LEVELING, iconLeveling, iconStartInfo)(); break; } } } @@ -2097,8 +2103,8 @@ void hmiMainMenu() { switch (select_page.now) { case PAGE_PRINT: iconPrint(); iconPrepare(); break; case PAGE_PREPARE: iconPrepare(); iconControl(); break; - case PAGE_CONTROL: iconControl(); TERN(HAS_AUTOLEVEL, iconLeveling, iconStartInfo)(); break; - case PAGE_INFO_LEVELING: TERN(HAS_AUTOLEVEL, iconLeveling, iconStartInfo)(); break; + case PAGE_CONTROL: iconControl(); TERN(HAS_ONESTEP_LEVELING, iconLeveling, iconStartInfo)(); break; + case PAGE_INFO_LEVELING: TERN(HAS_ONESTEP_LEVELING, iconLeveling, iconStartInfo)(); break; } } } @@ -2124,7 +2130,7 @@ void hmiMainMenu() { break; case PAGE_INFO_LEVELING: - #if HAS_AUTOLEVEL + #if HAS_ONESTEP_LEVELING checkkey = ID_Leveling; hmiLeveling(); #else @@ -2425,7 +2431,7 @@ void itemAdvHomeOffsets(const uint8_t row) { drawMoreIcon(row); } -#if HAS_AUTOLEVEL +#if HAS_ONESTEP_LEVELING void itemAdvProbeOffsets(const uint8_t row) { if (false && hmiIsChinese()) { @@ -2516,7 +2522,7 @@ void drawAdvancedSettingsMenu() { if (AVISI(0)) drawBackFirst(select_advset.now == CASE_BACK); if (AVISI(ADVSET_CASE_HOMEOFF)) itemAdvHomeOffsets(ASCROL(ADVSET_CASE_HOMEOFF)); // Set Home Offsets > - #if HAS_AUTOLEVEL + #if HAS_ONESTEP_LEVELING if (AVISI(ADVSET_CASE_PROBEOFF)) itemAdvProbeOffsets(ASCROL(ADVSET_CASE_PROBEOFF)); // Probe Offsets > #endif if (AVISI(ADVSET_CASE_HEPID)) itemAdvHotendPID(ASCROL(ADVSET_CASE_HEPID)); // Nozzle PID @@ -2591,7 +2597,7 @@ void drawHomeOffMenu() { if (select_item.now != CASE_BACK) drawMenuCursor(select_item.now); } -#if HAS_AUTOLEVEL +#if HAS_ONESTEP_LEVELING void drawProbeOffMenu() { clearMainWindow(); @@ -2939,7 +2945,7 @@ void hmiControl() { dwinUpdateLCD(); } -#if HAS_AUTOLEVEL +#if HAS_ONESTEP_LEVELING // Leveling void hmiLeveling() { popupWindowLeveling(); @@ -3568,7 +3574,7 @@ void hmiAdvSet() { break; #endif - #if HAS_AUTOLEVEL + #if HAS_ONESTEP_LEVELING case ADVSET_CASE_PROBEOFF: checkkey = ID_ProbeOff; select_item.reset(); @@ -3665,7 +3671,7 @@ void hmiAdvSet() { #endif // HAS_HOME_OFFSET -#if HAS_AUTOLEVEL +#if HAS_ONESTEP_LEVELING // Probe Offset void hmiProbeOff() { @@ -3719,14 +3725,14 @@ void hmiAdvSet() { void hmiProbeOffX() { hmiProbeOffN(hmiValues.probeOffsScaled.x, probe.offset.x); } void hmiProbeOffY() { hmiProbeOffN(hmiValues.probeOffsScaled.y, probe.offset.y); } -#endif // HAS_AUTOLEVEL +#endif // HAS_ONESTEP_LEVELING // Info void hmiInfo() { EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { - #if HAS_AUTOLEVEL + #if HAS_ONESTEP_LEVELING checkkey = ID_Control; select_control.set(CONTROL_CASE_INFO); drawControlMenu(); @@ -4232,7 +4238,7 @@ void dwinHandleScreen() { case ID_HomeOffY: hmiHomeOffY(); break; case ID_HomeOffZ: hmiHomeOffZ(); break; #endif - #if HAS_AUTOLEVEL + #if HAS_ONESTEP_LEVELING case ID_ProbeOff: hmiProbeOff(); break; case ID_ProbeOffX: hmiProbeOffX(); break; case ID_ProbeOffY: hmiProbeOffY(); break; diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index a6ac5f85ce78..76fe666112c7 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -984,7 +984,7 @@ void onClickSDItem() { void onDrawFileName(MenuItem* menuitem, int8_t line) { const bool is_subdir = !card.flag.workDirIsRoot; if (is_subdir && menuitem->pos == 1) { - drawMenuLine(line, ICON_ReadEEPROM, ".. Back"); + drawMenuLine(line, ICON_ReadEEPROM, ".. (up)"); } else { uint8_t icon; diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index e13bda60ddb4..6f3b6e621b97 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1874,6 +1874,7 @@ void MarlinUI::host_notify(const char * const cstr) { #endif // HAS_MEDIA #if HAS_MARLINUI_MENU + void MarlinUI::reset_settings() { settings.reset(); completion_feedback(); @@ -1895,7 +1896,7 @@ void MarlinUI::host_notify(const char * const cstr) { } #endif -#endif +#endif // HAS_MARLINUI_MENU #if ALL(EXTENSIBLE_UI, ADVANCED_PAUSE_FEATURE) diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index d578826e4970..d2a3cc80c201 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -616,11 +616,6 @@ class MarlinUI { static bool did_first_redraw; #endif - #if ANY(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) - static void zoffset_overlay(const int8_t dir); - static void zoffset_overlay(const_float_t zvalue); - #endif - static void draw_kill_screen(); static void kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component); #if DISABLED(LIGHTWEIGHT_UI) @@ -633,6 +628,11 @@ class MarlinUI { #endif + #if ANY(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + static void zoffset_overlay(const int8_t dir); + static void zoffset_overlay(const_float_t zvalue); + #endif + #if !HAS_WIRED_LCD static void quick_feedback(const bool=true) {} static void completion_feedback(const bool=true) {} diff --git a/Marlin/src/lcd/tft/ui_color_ui.cpp b/Marlin/src/lcd/tft/ui_color_ui.cpp index d6f3d2eff7fa..dffe0d65582c 100644 --- a/Marlin/src/lcd/tft/ui_color_ui.cpp +++ b/Marlin/src/lcd/tft/ui_color_ui.cpp @@ -81,7 +81,8 @@ void MarlinUI::tft_idle() { if ((BOOTSCREEN_TIMEOUT) > sofar) safe_delay((BOOTSCREEN_TIMEOUT) - sofar); clear_lcd(); } -#endif + +#endif // SHOW_BOOTSCREEN void MarlinUI::draw_kill_screen() { tft.queue.reset(); diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index fde07e836846..d718f6dca530 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -59,7 +59,7 @@ const char* i16tostr3rj(const int16_t x); // Convert signed int to lj string with 123 format const char* i16tostr3left(const int16_t xx); -// Convert signed int to rj string with _123, -123, _-12, or __-1 format +// Convert signed int to rj string with 1234, _123, -123, _-12, or __-1 format const char* i16tostr4signrj(const int16_t x); // Convert unsigned float to string with 1.2 format @@ -156,7 +156,7 @@ FORCE_INLINE const char* ftostr3rj(const_float_t x) { return i16tostr3rj(int16_t // Convert signed float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format const char* ftostr4sign(const_float_t fx); #else - // Convert signed float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format + // Convert signed float to rj string with 1234, _123, -123, _-12, or __-1 format FORCE_INLINE const char* ftostr4sign(const_float_t x) { return i16tostr4signrj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #endif From 1ee0684f89d3dff3eb43d86d57b62a57dfa84aab Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 Jan 2024 23:19:01 -0600 Subject: [PATCH 072/109] =?UTF-8?q?if=20HAS=5FDWIN=5FE3V2=20=3D>=20HAS=5FD?= =?UTF-8?q?ISPLAY=20then=E2=80=A6?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/bdl/bdl.cpp | 2 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 6 +++--- Marlin/src/feature/cancel_object.cpp | 2 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 6 +++--- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 4 ++-- Marlin/src/gcode/calibrate/G34_M422.cpp | 4 ++-- Marlin/src/gcode/calibrate/M48.cpp | 4 ++-- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/gcode/lcd/M117.cpp | 4 ++-- Marlin/src/inc/Conditionals_LCD.h | 8 -------- Marlin/src/lcd/marlinui.cpp | 10 +++++----- Marlin/src/lcd/marlinui.h | 15 +++++---------- Marlin/src/module/endstops.cpp | 6 +++--- Marlin/src/module/temperature.cpp | 4 ++-- Marlin/src/module/temperature.h | 2 +- ini/features.ini | 2 +- 17 files changed, 35 insertions(+), 48 deletions(-) diff --git a/Marlin/src/feature/bedlevel/bdl/bdl.cpp b/Marlin/src/feature/bedlevel/bdl/bdl.cpp index d469bb0c0673..aca28192ba98 100644 --- a/Marlin/src/feature/bedlevel/bdl/bdl.cpp +++ b/Marlin/src/feature/bedlevel/bdl/bdl.cpp @@ -137,7 +137,7 @@ void BDS_Leveling::process() { old_buf_z = current_position.z; endstops.bdp_state_update(z_sensor <= BD_SENSOR_HOME_Z_POSITION); - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY static float old_z_sensor = 0; if (old_z_sensor != z_sensor) { old_z_sensor = z_sensor; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 5123ca851a07..8360f2119396 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -767,7 +767,7 @@ void unified_bed_leveling::shift_mesh_height() { const grid_count_t point_num = (GRID_MAX_POINTS - count) + 1; SERIAL_ECHOLNPGM("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); + TERN_(HAS_DISPLAY, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); TERN_(DWIN_LCD_PROUI, dwinRedrawScreen()); @@ -1500,7 +1500,7 @@ void unified_bed_leveling::smart_fill_mesh() { for (uint8_t i = 0; i < 3; ++i) { SERIAL_ECHOLNPGM("Tilting mesh (", i + 1, "/3)"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_LCD_TILTING_MESH), i + 1)); + TERN_(HAS_DISPLAY, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_LCD_TILTING_MESH), i + 1)); measured_z = probe.probe_at_point(points[i], i < 2 ? PROBE_PT_RAISE : PROBE_PT_LAST_STOW, param.V_verbosity); if ((abort_flag = isnan(measured_z))) break; @@ -1556,7 +1556,7 @@ void unified_bed_leveling::smart_fill_mesh() { #endif SERIAL_ECHOLNPGM("Tilting mesh point ", point_num, "/", total_points, "\n"); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); + TERN_(HAS_DISPLAY, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points)); measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp index 0040f6ed9df8..c13d2054daf3 100644 --- a/Marlin/src/feature/cancel_object.cpp +++ b/Marlin/src/feature/cancel_object.cpp @@ -44,7 +44,7 @@ void CancelObject::set_active_object(const int8_t obj) { else skipping = false; - #if ALL(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) + #if ALL(HAS_DISPLAY, CANCEL_OBJECTS_REPORTING) if (active_object >= 0) ui.set_status(MString<30>(GET_TEXT_F(MSG_PRINTING_OBJECT), ' ', active_object)); else diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 1ca3826c816f..96b7ffa703e8 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -691,7 +691,7 @@ G29_TYPE GcodeSuite::G29() { if (TERN0(IS_KINEMATIC, !probe.can_reach(abl.probePos))) continue; if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing mesh point ", pt_index, "/", abl.abl_points, "."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points))); + TERN_(HAS_DISPLAY, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points))); #if ENABLED(BD_SENSOR_PROBE_NO_STOP) if (PR_INNER_VAR == inStart) { @@ -790,7 +790,7 @@ G29_TYPE GcodeSuite::G29() { for (uint8_t i = 0; i < 3; ++i) { if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing point ", i + 1, "/3."); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); + TERN_(HAS_DISPLAY, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); // Retain the last probe position abl.probePos = xy_pos_t(points[i]); @@ -813,7 +813,7 @@ G29_TYPE GcodeSuite::G29() { #endif // AUTO_BED_LEVELING_3POINT - TERN_(HAS_STATUS_MESSAGE, ui.reset_status()); + TERN_(HAS_DISPLAY, ui.reset_status()); // Stow the probe. No raise for FIX_MOUNTED_PROBE. if (probe.stow()) { diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index b3f03d03ba43..d765a16a15e2 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -196,7 +196,7 @@ void GcodeSuite::G29() { // After recording the last point, activate home and activate mbl_probe_index = -1; SERIAL_ECHOLNPGM("Mesh probing done."); - TERN_(HAS_STATUS_MESSAGE, LCD_MESSAGE(MSG_MESH_DONE)); + TERN_(HAS_DISPLAY, LCD_MESSAGE(MSG_MESH_DONE)); OKAY_BUZZ(); home_all_axes(); @@ -258,7 +258,7 @@ void GcodeSuite::G29() { if (state == MeshNext) { SERIAL_ECHOLNPGM("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS); - if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS))); + if (mbl_probe_index > 0) TERN_(HAS_DISPLAY, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS))); } report_current_position(); diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index bbc403904f66..c1ad1a3e6230 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -176,7 +176,7 @@ void GcodeSuite::G34() { bool adjustment_reverse = false; #endif - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY PGM_P const msg_iteration = GET_TEXT(MSG_ITERATION); const uint8_t iter_str_len = strlen_P(msg_iteration); #endif @@ -190,7 +190,7 @@ void GcodeSuite::G34() { const int iter = iteration + 1; SERIAL_ECHOLNPGM("\nG34 Iteration: ", iter); - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY char str[iter_str_len + 2 + 1]; sprintf_P(str, msg_iteration, iter); ui.set_status(str); diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 9d4a130168f9..76ce53482f72 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -152,7 +152,7 @@ void GcodeSuite::M48() { float sample_sum = 0.0; for (uint8_t n = 0; n < n_samples; ++n) { - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY // Display M48 progress in the status bar ui.status_printf(0, F(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples)); #endif @@ -264,7 +264,7 @@ void GcodeSuite::M48() { SERIAL_ECHOLNPGM("Finished!"); dev_report(verbose_level > 0, mean, sigma, min, max, true); - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY // Display M48 results in the status bar ui.set_status_and_level(MString<30>(GET_TEXT_F(MSG_M48_DEVIATION), F(": "), w_float_t(sigma, 2, 6))); #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 1ff643dc2174..6668e7fa120a 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -679,7 +679,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 115: M115(); break; // M115: Report capabilities #endif - case 117: TERN_(HAS_STATUS_MESSAGE, M117()); break; // M117: Set LCD message text, if possible + case 117: TERN_(HAS_DISPLAY, M117()); break; // M117: Set LCD message text, if possible case 118: M118(); break; // M118: Display a message in the host console case 119: M119(); break; // M119: Report endstop states diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 7a72097141b7..eb27b7bb7303 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -767,7 +767,7 @@ class GcodeSuite { static void M115(); #endif - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY static void M117(); #endif diff --git a/Marlin/src/gcode/lcd/M117.cpp b/Marlin/src/gcode/lcd/M117.cpp index 57a26851fd07..627f83d13be0 100644 --- a/Marlin/src/gcode/lcd/M117.cpp +++ b/Marlin/src/gcode/lcd/M117.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if HAS_STATUS_MESSAGE +#if HAS_DISPLAY #include "../gcode.h" #include "../../lcd/marlinui.h" @@ -39,4 +39,4 @@ void GcodeSuite::M117() { } -#endif // HAS_STATUS_MESSAGE +#endif // HAS_DISPLAY diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 88a74bafed89..b0fb6460beee 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1100,10 +1100,6 @@ #define HAS_DISPLAY 1 #endif -#if ANY(HAS_DISPLAY, DWIN_CREALITY_LCD) - #define HAS_UI_UPDATE 1 -#endif - #if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI #define HAS_LCDPRINT 1 #endif @@ -1112,10 +1108,6 @@ #define HAS_UTF8_UTILS 1 #endif -#if ANY(HAS_DISPLAY, HAS_DWIN_E3V2) - #define HAS_STATUS_MESSAGE 1 -#endif - #if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS) #define HAS_MARLINUI_MENU 1 #endif diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 6f3b6e621b97..0bedb36e7a70 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -57,7 +57,7 @@ MarlinUI ui; #define BASIC_PROGRESS_BAR 1 #endif -#if ANY(HAS_DISPLAY, HAS_STATUS_MESSAGE, BASIC_PROGRESS_BAR) +#if ANY(HAS_DISPLAY, BASIC_PROGRESS_BAR) #include "../module/printcounter.h" #endif @@ -67,7 +67,7 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; -#if HAS_STATUS_MESSAGE +#if HAS_DISPLAY #if ENABLED(STATUS_MESSAGE_SCROLLING) && ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) uint8_t MarlinUI::status_scroll_offset; // = 0 #endif @@ -1467,7 +1467,7 @@ void MarlinUI::host_notify(const char * const cstr) { #include -#if HAS_STATUS_MESSAGE +#if HAS_DISPLAY #if ENABLED(EXTENSIBLE_UI) #include "extui/ui_api.h" @@ -1652,7 +1652,7 @@ void MarlinUI::host_notify(const char * const cstr) { #endif -#else // !HAS_STATUS_MESSAGE +#else // !HAS_DISPLAY // // Send the status line as a host notification @@ -1679,7 +1679,7 @@ void MarlinUI::host_notify(const char * const cstr) { host_notify(msg); } -#endif // !HAS_STATUS_MESSAGE +#endif // !HAS_DISPLAY #if HAS_DISPLAY diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index d2a3cc80c201..893621b3137d 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -199,13 +199,6 @@ class MarlinUI { } static void init(); - - #if HAS_DISPLAY || HAS_DWIN_E3V2 - static void init_lcd(); - #else - static void init_lcd() {} - #endif - static void reinit_lcd() { TERN_(REINIT_NOISY_LCD, init_lcd()); } #if HAS_WIRED_LCD @@ -370,7 +363,7 @@ class MarlinUI { static void host_notify(FSTR_P const fstr) { host_notify_P(FTOP(fstr)); } static void host_notify(const char * const cstr); - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY #if ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) #if ENABLED(STATUS_MESSAGE_SCROLLING) @@ -505,8 +498,10 @@ class MarlinUI { template static void status_printf(int8_t level, FSTR_P const ffmt, Args... more) { status_printf_P(level, FTOP(ffmt), more...); } + static void init_lcd() IF_DISABLED(HAS_DISPLAY, {}); + // Periodic or as-needed display update - static void update() IF_DISABLED(HAS_UI_UPDATE, {}); + static void update() IF_DISABLED(HAS_DISPLAY, {}); #if HAS_DISPLAY @@ -896,7 +891,7 @@ class MarlinUI { static constexpr bool defer_return_to_status = false; #endif - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY static void finish_status(const bool persist); #endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 9c6a3c011cca..e3781e4a6a3a 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -303,7 +303,7 @@ void Endstops::event_handler() { if (hit_state == prev_hit_state) return; prev_hit_state = hit_state; if (hit_state) { - #if HAS_STATUS_MESSAGE + #if HAS_DISPLAY char NUM_AXIS_LIST_(chrX = ' ', chrY = ' ', chrZ = ' ', chrI = ' ', chrJ = ' ', chrK = ' ', chrU = ' ', chrV = ' ', chrW = ' ') chrP = ' '; #define _SET_STOP_CHAR(A,C) (chr## A = C) @@ -348,13 +348,13 @@ void Endstops::event_handler() { #endif SERIAL_EOL(); - TERN_(HAS_STATUS_MESSAGE, + #if HAS_DISPLAY ui.status_printf(0, F(S_FMT GANG_N_1(NUM_AXES, " %c") " %c"), GET_TEXT(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) { diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index ad1daae76245..f7f362d91272 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -810,7 +810,7 @@ volatile bool Temperature::raw_temps_ready = false; } } SHV((bias + d) >> 1); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PID_CYCLE), cycles, ncycles)); + TERN_(HAS_DISPLAY, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PID_CYCLE), cycles, ncycles)); cycles++; minT = target; } @@ -4434,7 +4434,7 @@ void Temperature::isr() { } #endif - #if HAS_HOTEND && HAS_STATUS_MESSAGE + #if HAS_HOTEND && HAS_DISPLAY void Temperature::set_heating_message(const uint8_t e, const bool isM104/*=false*/) { const bool heating = isHeatingHotend(e); ui.status_printf(0, diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 088a17ec1b99..bb5b3a55385e 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -1319,7 +1319,7 @@ class Temperature { #endif #endif - #if HAS_HOTEND && HAS_STATUS_MESSAGE + #if HAS_HOTEND && HAS_DISPLAY static void set_heating_message(const uint8_t e, const bool isM104=false); #else static void set_heating_message(const uint8_t, const bool=false) {} diff --git a/ini/features.ini b/ini/features.ini index 4baa2566f04d..0083bafc5b03 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -331,7 +331,7 @@ REPETIER_GCODE_M360 = build_src_filter=+ HAS_RESUME_CONTINUE = build_src_filter=+ SET_PROGRESS_MANUALLY = build_src_filter=+ -HAS_STATUS_MESSAGE = build_src_filter=+ +HAS_DISPLAY = build_src_filter=+ HAS_PREHEAT = build_src_filter=+ HAS_LCD_CONTRAST = build_src_filter=+ EDITABLE_DISPLAY_TIMEOUT = build_src_filter=+ From 73119c66a0b22897c64c5d2ad7e3250f125eca10 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 Jan 2024 23:35:58 -0600 Subject: [PATCH 073/109] =?UTF-8?q?=E2=80=A6and=E2=80=A6?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 4 ++-- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index d765a16a15e2..fc72893616f2 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -196,7 +196,7 @@ void GcodeSuite::G29() { // After recording the last point, activate home and activate mbl_probe_index = -1; SERIAL_ECHOLNPGM("Mesh probing done."); - TERN_(HAS_DISPLAY, LCD_MESSAGE(MSG_MESH_DONE)); + LCD_MESSAGE(MSG_MESH_DONE); OKAY_BUZZ(); home_all_axes(); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 6668e7fa120a..8d9a5f49d8b9 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -679,7 +679,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 115: M115(); break; // M115: Report capabilities #endif - case 117: TERN_(HAS_DISPLAY, M117()); break; // M117: Set LCD message text, if possible + case 117: TERN_(HAS_DISPLAY, M117()); break; // M117: Set LCD message text, if possible case 118: M118(); break; // M118: Display a message in the host console case 119: M119(); break; // M119: Report endstop states diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 76fe666112c7..15d0888c1f03 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1208,11 +1208,11 @@ void drawMainArea() { case ID_PrintProcess: drawPrintProcess(); break; case ID_PrintDone: drawPrintDone(); break; #if HAS_ESDIAG - case ID_ESDiagProcess: drawEndStopDiag(); break; + case ID_ESDiagProcess: drawEndStopDiag(); break; #endif case ID_Popup: popupDraw(); break; #if HAS_LOCKSCREEN - case ID_Locked: lockScreen.draw(); break; + case ID_Locked: lockScreen.draw(); break; #endif case ID_Menu: case ID_SetInt: diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index e3781e4a6a3a..59e4badf1c66 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -353,7 +353,7 @@ void Endstops::event_handler() { F(S_FMT GANG_N_1(NUM_AXES, " %c") " %c"), GET_TEXT(MSG_LCD_ENDSTOPS), NUM_AXIS_LIST_(chrX, chrY, chrZ, chrI, chrJ, chrK, chrU, chrV, chrW) chrP - ) + ); #endif #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f7f362d91272..ec3895444d18 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1269,7 +1269,7 @@ volatile bool Temperature::raw_temps_ready = false; // Allow the system to stabilize under MPC, then get a better measure of ambient loss with and without fan SERIAL_ECHOLNPGM(STR_MPC_MEASURING_AMBIENT, hotend.modeled_block_temp); - TERN(DWIN_LCD_PROUI, LCD_ALERTMESSAGE(MSG_MPC_MEASURING_AMBIENT), LCD_MESSAGE(MSG_MPC_MEASURING_AMBIENT)); + TERN(DWIN_LCD_PROUI, LCD_ALERTMESSAGE, LCD_MESSAGE)(MSG_MPC_MEASURING_AMBIENT); // Use the estimated overshoot of the temperature as the target to achieve. hotend.target = hotend.modeled_block_temp; From 227115a92e7c5bebb5a2ab41f99dece1f4cab531 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 22 Jan 2024 10:38:43 -0500 Subject: [PATCH 074/109] move up settings.load --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 15d0888c1f03..686226a128e4 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2046,8 +2046,8 @@ void gotoConfirmToPrint() { } void readEEPROM() { - dwinRedrawScreen(); DONE_BUZZ(settings.load()); + dwinRedrawScreen(); } void resetEEPROM() { From 16edc203c084fdaf67bbdee235493f2c7b258523 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 22 Jan 2024 11:08:35 -0500 Subject: [PATCH 075/109] update runout string --- Marlin/src/lcd/e3v2/proui/endstop_diag.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp index 8d9bed50cbde..f2572f37112d 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp @@ -61,7 +61,7 @@ void draw_es_state(const bool is_hit, const bool is_fil) { const uint8_t LM = 130; DWINUI::cursor.x = LM; dwinDrawRectangle(1, hmiData.colorPopupBg, LM, DWINUI::cursor.y, LM + 120, DWINUI::cursor.y + 20); - is_fil ? (is_hit ? DWINUI::drawString(RGB(16, 63, 16), F("PRESENT")) : DWINUI::drawString(RGB(31, 31, 16), F("Runout Detected"))) : + is_fil ? (is_hit ? DWINUI::drawString(RGB(16, 63, 16), GET_TEXT_F(MSG_FILAMENT)) : DWINUI::drawString(RGB(31, 31, 16), GET_TEXT_F(MSG_RUNOUT_SENSOR))) : (is_hit ? DWINUI::drawString(RGB(31, 31, 16), F(STR_ENDSTOP_HIT)) : DWINUI::drawString(RGB(16, 63, 16), F(STR_ENDSTOP_OPEN))); DWINUI::moveBy(0, 25); } From 52fc2c670f10f14fb6fd57da7dca36f81dfde4e3 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 25 Jan 2024 12:29:05 -0500 Subject: [PATCH 076/109] revert change to popup --- Marlin/src/lcd/e3v2/proui/dwin_popup.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp index 6ac467b16d60..26412dd7f555 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp @@ -41,7 +41,10 @@ popupDrawFunc_t popupDraw = nullptr; popupClickFunc_t popupClick = nullptr; popupChangeFunc_t popupChange = nullptr; +uint16_t highlightY = 280; + void drawSelectHighlight(const bool sel, const uint16_t ypos) { + highlightY = ypos; hmiFlag.select_flag = sel; const uint16_t c1 = sel ? hmiData.colorHighlight : hmiData.colorPopupBg, c2 = sel ? hmiData.colorPopupBg : hmiData.colorHighlight; @@ -77,7 +80,7 @@ void hmiPopup() { EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_CW || encoder_diffState == ENCODER_DIFF_CCW) { const bool change = encoder_diffState != ENCODER_DIFF_CW; - if (popupChange) popupChange(change); else drawSelectHighlight(change); + if (popupChange) popupChange(change); else drawSelectHighlight(change, highlightY); dwinUpdateLCD(); } } From ce572da7dc4fd35c1509209f9b881c9899484cee Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 26 Jan 2024 17:14:30 -0500 Subject: [PATCH 077/109] update gcode_preview - fix for restarting after multiple clicks --- Marlin/src/lcd/e3v2/proui/gcode_preview.cpp | 78 ++++++++++----------- Marlin/src/lcd/e3v2/proui/gcode_preview.h | 16 +++++ 2 files changed, 52 insertions(+), 42 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp index 045615f3c2ae..5c93c67f6bfe 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -39,51 +39,41 @@ #include "../../marlinui.h" #include "../../../sd/cardreader.h" -#include "../../../MarlinCore.h" // for wait_for_user -#include "dwin.h" #include "dwin_popup.h" #include "base64.h" -#define THUMBWIDTH 230 -#define THUMBHEIGHT 180 +#if ENABLED(TJC_DISPLAY) + #define THUMBWIDTH 180 + #define THUMBHEIGHT 180 +#else + #define THUMBWIDTH 200 + #define THUMBHEIGHT 200 +#endif Preview preview; +fileprop_t fileprop; -typedef struct { - char name[13] = ""; // 8.3 + null - uint32_t thumbstart = 0; - int thumbsize = 0; - int thumbheight = 0, thumbwidth = 0; - float time = 0; - float filament = 0; - float layer = 0; - float width = 0, height = 0, length = 0; - - void setname(const char * const fn) { - const uint8_t len = _MIN(sizeof(name) - 1, strlen(fn)); - memcpy(name, fn, len); - name[len] = '\0'; - } - - void clear() { - name[0] = '\0'; - thumbstart = 0; - thumbsize = 0; - thumbheight = thumbwidth = 0; - time = 0; - filament = 0; - layer = 0; - height = width = length = 0; - } - -} fileprop_t; +void fileprop_t::setname(const char * const fn) { + const uint8_t len = _MIN(sizeof(name) - 1, strlen(fn)); + memcpy(name, fn, len); + name[len] = '\0'; +} -fileprop_t fileprop; +void fileprop_t::clear() { + name[0] = '\0'; + thumbstart = 0; + thumbsize = 0; + thumbheight = thumbwidth = 0; + time = 0; + filament = 0; + layer = 0; + height = width = length = 0; +} void getValue(const char * const buf, PGM_P const key, float &value) { if (value != 0.0f) return; - char *posptr = strstr_P(buf, key); + const char *posptr = strstr_P(buf, key); if (posptr == nullptr) return; char num[10] = ""; @@ -101,7 +91,7 @@ void getValue(const char * const buf, PGM_P const key, float &value) { bool Preview::hasPreview() { const char * const tbstart = PSTR("; thumbnail begin " STRINGIFY(THUMBWIDTH) "x" STRINGIFY(THUMBHEIGHT)); - char *posptr = nullptr; + const char *posptr = nullptr; uint32_t indx = 0; float tmp = 0; @@ -184,11 +174,7 @@ bool Preview::hasPreview() { } void Preview::drawFromSD() { - if (!hasPreview()) { - hmiFlag.select_flag = 1; - wait_for_user = false; - return; - } + hasPreview(); MString<45> buf; dwinDrawRectangle(1, hmiData.colorBackground, 0, 0, DWIN_WIDTH, STATUS_Y - 1); @@ -208,10 +194,18 @@ void Preview::drawFromSD() { buf.set(F("Volume: "), p_float_t(fileprop.width, 1), 'x', p_float_t(fileprop.length, 1), 'x', p_float_t(fileprop.height, 1), F(" mm")); DWINUI::drawString(20, 70, &buf); } + + if (!fileprop.thumbsize) { + const uint8_t xpos = ((DWIN_WIDTH) / 2) - 55, // 55 = iconW/2 + ypos = ((DWIN_HEIGHT) / 2) - 125; + DWINUI::drawIcon(ICON_Info_0, xpos, ypos); + buf.set(PSTR("No " STRINGIFY(THUMBWIDTH) "x" STRINGIFY(THUMBHEIGHT) " Thumbnail")); + DWINUI::drawCenteredString(false, (DWINUI::fontid * 3), DWINUI::textColor, DWINUI::backColor, 0, DWIN_WIDTH, (DWIN_HEIGHT / 2), &buf); + } DWINUI::drawButton(BTN_Print, 26, 290); DWINUI::drawButton(BTN_Cancel, 146, 290); - show(); - drawSelectHighlight(true, 290); + if (fileprop.thumbsize) show(); + drawSelectHighlight(false, 290); dwinUpdateLCD(); } diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.h b/Marlin/src/lcd/e3v2/proui/gcode_preview.h index 91466424475d..4d8325678ecb 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.h +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.h @@ -39,3 +39,19 @@ class Preview { }; extern Preview preview; + +typedef struct { + char name[13] = ""; // 8.3 + null + uint32_t thumbstart; + int thumbsize, thumbheight, thumbwidth; + float time, + filament, + layer, + width, height, length; + + void setname(const char * const fn); + void clear(); + +} fileprop_t; + +extern fileprop_t fileprop; From 03ae02dd270a4b629871f74d9998c228a038df17 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 26 Jan 2024 20:38:50 -0500 Subject: [PATCH 078/109] fix typo --- Marlin/src/lcd/e3v2/proui/gcode_preview.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp index 5c93c67f6bfe..c14e35f513f4 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -200,7 +200,7 @@ void Preview::drawFromSD() { ypos = ((DWIN_HEIGHT) / 2) - 125; DWINUI::drawIcon(ICON_Info_0, xpos, ypos); buf.set(PSTR("No " STRINGIFY(THUMBWIDTH) "x" STRINGIFY(THUMBHEIGHT) " Thumbnail")); - DWINUI::drawCenteredString(false, (DWINUI::fontid * 3), DWINUI::textColor, DWINUI::backColor, 0, DWIN_WIDTH, (DWIN_HEIGHT / 2), &buf); + DWINUI::drawCenteredString(false, (DWINUI::fontID * 3), DWINUI::textColor, DWINUI::backColor, 0, DWIN_WIDTH, (DWIN_HEIGHT / 2), &buf); } DWINUI::drawButton(BTN_Print, 26, 290); DWINUI::drawButton(BTN_Cancel, 146, 290); From 975ba093626a344b7e64d39c1d374df0fa2680cc Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Fri, 26 Jan 2024 21:06:54 -0500 Subject: [PATCH 079/109] initialize msg array --- Marlin/src/lcd/e3v2/proui/meshviewer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp index 1c5f08bb4dfa..0a460e2551ac 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp @@ -87,7 +87,7 @@ void MeshViewer::drawMeshPoint(const uint8_t x, const uint8_t y, const float z) else DWINUI::drawSignedFloat(meshfont, 1, 2, px(x) - 3 * fs, fy, z); } else { - char msg[9]; msg[0] = '\0'; + char msg[9] = {0}; switch (v) { case -999 ... -100: case 100 ... 999: DWINUI::drawSignedFloat(meshfont, 1, 1, px(x) - 3 * fs, fy, z); break; From ab61dba206c7f31a622db273fbcd912dd913f5bb Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 27 Jan 2024 03:18:40 -0500 Subject: [PATCH 080/109] shortened some espanol moved MSG_BLTOUCH_MODE_CHANGE to Wide Note: some translations are 21 characters... not much I can do about it, so hope that might be ok --- Marlin/src/lcd/language/language_es.h | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index c4aaa102b7a3..d9fc1eb2a2c9 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -46,7 +46,7 @@ namespace LanguageNarrow_es { LSTR MSG_MEDIA_READ_ERROR = _UxGT("Error lectura SD/FD"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); - LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbordamiento de subllamada"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Rebosar subllamada"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); LSTR MSG_MAIN_MENU = _UxGT("Menú principal"); @@ -63,8 +63,8 @@ namespace LanguageNarrow_es { LSTR MSG_AUTO_HOME_Z = _UxGT("Origen Z"); LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto alineado Z"); LSTR MSG_ITERATION = _UxGT("G34 Iteración: %i"); - LSTR MSG_DECREASING_ACCURACY = _UxGT("¡Precisión disminuyendo!"); - LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Precisión conseguida"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("¡Precisión menos!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Precisión lograda"); LSTR MSG_LEVEL_BED_HOMING = _UxGT("Origen XYZ"); LSTR MSG_LEVEL_BED_WAITING = _UxGT("Pulsar para comenzar"); LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Siguiente punto"); @@ -75,8 +75,8 @@ namespace LanguageNarrow_es { LSTR MSG_HOME_OFFSET_Y = _UxGT("Origen desfase Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Origen desfase Z"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfase aplicada"); - LSTR MSG_ERR_M428_TOO_FAR = _UxGT("MIN/MÁX demasiado lejos"); - LSTR MSG_TRAMMING_WIZARD = _UxGT("Asistente de Tramming"); + LSTR MSG_ERR_M428_TOO_FAR = _UxGT("MIN/MÁX muy lejos"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("Asistente Tramming"); LSTR MSG_TRAMMING_DONE = _UxGT("Tramming hecho"); LSTR MSG_LOWER = _UxGT("Bajar"); LSTR MSG_RAISE = _UxGT("Elevar"); @@ -114,7 +114,7 @@ namespace LanguageNarrow_es { LSTR MSG_BED_LEVELING = _UxGT("Nivelando Cama"); LSTR MSG_LEVEL_BED = _UxGT("Nivelar Cama"); LSTR MSG_PROBE_FOR_Z_VALUE = _UxGT("Sonda para valor Z"); - LSTR MSG_ZERO_CURRENT_POINT = _UxGT("Punto de corriente cero"); + LSTR MSG_ZERO_CURRENT_POINT = _UxGT("Cero este punto"); LSTR MSG_BED_TRAMMING = _UxGT("Recorrido Cama"); LSTR MSG_NEXT_CORNER = _UxGT("Siguente Esquina"); @@ -272,8 +272,8 @@ namespace LanguageNarrow_es { LSTR MSG_LCD_OFF = _UxGT("Apg"); LSTR MSG_PID_AUTOTUNE = _UxGT("PID Auto-ajuste"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Auto-ajuste *"); - LSTR MSG_FOR_NOZZLE_RUNNING = _UxGT("para BOQUILLA está funcionando."); - LSTR MSG_FOR_BED_RUNNING = _UxGT("para CAMA está funcionando."); + LSTR MSG_FOR_NOZZLE_RUNNING = _UxGT("BOQUILLA funcionando"); + LSTR MSG_FOR_BED_RUNNING = _UxGT("CAMA funcionando"); LSTR MSG_SELECT_E = _UxGT("Seleccionar *"); LSTR MSG_ACC = _UxGT("Aceleración"); LSTR MSG_JERK = _UxGT("Jerk"); @@ -319,8 +319,8 @@ namespace LanguageNarrow_es { LSTR MSG_ADVANCE_K = _UxGT("Avance K"); LSTR MSG_ADVANCE_K_E = _UxGT("Avance K *"); LSTR MSG_CONTRAST = _UxGT("Contraste LCD"); - LSTR MSG_NOZZLE_TEMPERATURE = _UxGT("Temperatura de la boquilla"); - LSTR MSG_BED_TEMPERATURE = _UxGT("Temperatura de la cama"); + LSTR MSG_NOZZLE_TEMPERATURE = _UxGT("Temperatura boquilla"); + LSTR MSG_BED_TEMPERATURE = _UxGT("Temperatura cama"); LSTR MSG_STORE_EEPROM = _UxGT("Guardar EEPROM"); LSTR MSG_LOAD_EEPROM = _UxGT("Cargar EEPROM"); LSTR MSG_RESTORE_DEFAULTS = _UxGT("Rest. fábrica"); @@ -401,7 +401,6 @@ namespace LanguageNarrow_es { LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Poner BLTouch a 5V"); LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Poner BLTouch a OD"); LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Informe de drenaje"); - LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("PELIGRO: ¡Una mala configuración puede producir daños! ¿Proceder igualmente?"); LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); LSTR MSG_TOUCHMI_INIT = _UxGT("Iniciar TouchMI"); LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test de desfase Z"); @@ -625,6 +624,7 @@ namespace LanguageTall_es { LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Espere para", "purgar el filamento")); LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Pulse para finalizar", "la purga de filamen.")); LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Esperando impresora", "para reanudar...")); + LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT(MSG_3_LINE("PELIGRO: Mala config", "puede causar daños!", "¿Proceder?")); #endif } From 5fcab1fd52601610a279de512e03777964b9c770 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 31 Jan 2024 17:08:04 -0500 Subject: [PATCH 081/109] fix tramwiz, so now... When x = 0 and y = 0, p will be calculated as p = 0 + 2 * 0 = 0. When x = 0 and y = 1, p will be calculated as p = 1 + 2 * 0 = 1. When x = 1 and y = 0, p will be calculated as p = 0 + 2 * 1 = 2. When x = 1 and y = 1, p will be calculated as p = 1 + 2 * 1 = 3. --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 23 +++++++++++------------ Marlin/src/lcd/e3v2/proui/dwin.h | 5 ++--- 2 files changed, 13 insertions(+), 15 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 686226a128e4..cdc3f10b5d95 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2396,7 +2396,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, #if HAS_BED_PROBE - float tram(const uint8_t point) { + float tram(const uint8_t point, bool stow_probe/*=true*/) { static bool inLev = false; if (inLev) return NAN; @@ -2425,10 +2425,10 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, LIMIT(xpos, MESH_MIN_X, MESH_MAX_X); LIMIT(ypos, MESH_MIN_Y, MESH_MAX_Y); - probe.stow(); - gcode.process_subcommands_now(F("M420S0\nG28O")); + set_bed_leveling_enabled(false); + if (stow_probe) { probe.stow(); } inLev = true; - zval = probe.probe_at_point(xpos, ypos, PROBE_PT_STOW); + zval = probe.probe_at_point(xpos, ypos, (stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE)); if (isnan(zval)) LCD_MESSAGE(MSG_ZPROBE_OUT); else @@ -2462,15 +2462,14 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, meshViewer.drawMeshGrid(2, 2); // Indicate start. Draw the grid bed_mesh_t zval = {0}; probe.stow(); - zval[0][0] = tram(0); - if (checkkey == ID_Homing) meshViewer.drawMeshGrid(2, 2); // Redraw if Homing checkkey = ID_NothingToDo; + zval[0][0] = tram(0, false); meshViewer.drawMesh(zval, 2, 2); - zval[1][0] = tram(1); + zval[1][0] = tram(1, false); meshViewer.drawMesh(zval, 2, 2); - zval[1][1] = tram(2); + zval[1][1] = tram(2, false); meshViewer.drawMesh(zval, 2, 2); - zval[0][1] = tram(3); + zval[0][1] = tram(3, false); probe.stow(); meshViewer.drawMesh(zval, 2, 2); @@ -2503,15 +2502,15 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, if (max < d) { s = (zval[x][y] >= 0); max = d; - p = x + 2 * y; + p = y + 2 * x; } else { goto EXIT_TRAMWIZ; } // fail-safe if Corners are = 0.00 } switch (p) { case 0b00 : plabel = GET_TEXT_F(MSG_TRAM_FL); break; case 0b01 : plabel = GET_TEXT_F(MSG_TRAM_FR); break; - case 0b10 : plabel = GET_TEXT_F(MSG_TRAM_BL); break; - case 0b11 : plabel = GET_TEXT_F(MSG_TRAM_BR); break; + case 0b10 : plabel = GET_TEXT_F(MSG_TRAM_BR); break; + case 0b11 : plabel = GET_TEXT_F(MSG_TRAM_BL); break; default : plabel = F(""); break; } DWINUI::drawCenteredString(120, GET_TEXT_F(MSG_CORNERS_NOT_LEVELED)); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index 587b6789efd1..94c1efcc8034 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -240,9 +240,6 @@ void doCoolDown(); #if ENABLED(NOZZLE_PARK_FEATURE) void parkHead(); #endif -#if HAS_AUTOLEVEL - void trammingwizard(); -#endif #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) void applyLEDColor(); #endif @@ -330,6 +327,8 @@ void drawTrammingMenu(); #endif #if HAS_BED_PROBE void drawProbeSetMenu(); + void trammingwizard(); + float tram(uint8_t point, bool stow_probe=true); #endif void drawFilSetMenu(); #if ALL(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) From 35c54cf91cb3d8cd2514e9a11c127b7a18c06ace Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 3 Feb 2024 03:38:05 -0500 Subject: [PATCH 082/109] fix (-) float --- Marlin/src/module/probe.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index f15f7b3d868b..737796919a0b 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -777,7 +777,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/, const_float_t z_min_p // Stop the probe before it goes too low to prevent damage. // For known Z probe below the expected trigger point, otherwise -10mm lower. - const float z_probe_low_point = zoffs + z_min_point -float((!axis_is_trusted(Z_AXIS)) * 10); + const float z_probe_low_point = zoffs + z_min_point - float((!axis_is_trusted(Z_AXIS)) * 10); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Probe Low Point: ", z_probe_low_point); // Double-probing does a fast probe followed by a slow probe From 41eb6909c7f992af87f805b78ae509fee9343a57 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 3 Feb 2024 10:29:13 -0500 Subject: [PATCH 083/109] toggleCheckboxLine -- ^= true --- Marlin/src/lcd/e3v2/proui/menus.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/menus.cpp b/Marlin/src/lcd/e3v2/proui/menus.cpp index 88fbf6000125..97eed1d0104c 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.cpp +++ b/Marlin/src/lcd/e3v2/proui/menus.cpp @@ -95,7 +95,7 @@ void showCheckboxLine(const bool checked) { } void toggleCheckboxLine(bool &checked) { - checked = !checked; + checked ^= true; showCheckboxLine(checked); } From 4c8a9fa96347a0263c87c2279ca016f80361d1fc Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 3 Feb 2024 11:48:29 -0500 Subject: [PATCH 084/109] null msg, meshviewer.cpp --- Marlin/src/lcd/e3v2/proui/meshviewer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp index 0a460e2551ac..9a0ea86c878d 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp @@ -87,7 +87,7 @@ void MeshViewer::drawMeshPoint(const uint8_t x, const uint8_t y, const float z) else DWINUI::drawSignedFloat(meshfont, 1, 2, px(x) - 3 * fs, fy, z); } else { - char msg[9] = {0}; + char msg[9] = ""; switch (v) { case -999 ... -100: case 100 ... 999: DWINUI::drawSignedFloat(meshfont, 1, 1, px(x) - 3 * fs, fy, z); break; From d1e6d1ce84aa677701deab859fd176cada96d85a Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 3 Feb 2024 22:59:38 -0500 Subject: [PATCH 085/109] OPTARG to update_software_endstops --- Marlin/src/module/motion.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index c7558db43fc4..17d973a123b8 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -237,9 +237,7 @@ inline float home_bump_mm(const AxisEnum axis) { extern soft_endstops_t soft_endstop; void apply_motion_limits(xyz_pos_t &target); void update_software_endstops(const AxisEnum axis - #if HAS_HOTEND_OFFSET - , const uint8_t old_tool_index=0, const uint8_t new_tool_index=0 - #endif + OPTARG(HAS_HOTEND_OFFSET, const uint8_t old_tool_index=0, const uint8_t new_tool_index=0) ); #define SET_SOFT_ENDSTOP_LOOSE(loose) (soft_endstop._loose = loose) From f145848c7ed1a2124a644bffc7eeb6cf91b6daa4 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 5 Feb 2024 10:32:08 -0500 Subject: [PATCH 086/109] tweak trammingwizard --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 46 ++++++++++++++---------------- 1 file changed, 22 insertions(+), 24 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index cdc3f10b5d95..ce4602054518 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2459,19 +2459,19 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, } LCD_MESSAGE(MSG_TRAMMING_WIZARD_START); DWINUI::clearMainArea(); - meshViewer.drawMeshGrid(2, 2); // Indicate start. Draw the grid - bed_mesh_t zval = {0}; + static bed_mesh_t zval = {}; probe.stow(); checkkey = ID_NothingToDo; zval[0][0] = tram(0, false); - meshViewer.drawMesh(zval, 2, 2); + meshViewer.drawMeshGrid(2, 2); // Indicate start. Draw the grid + meshViewer.drawMeshPoint(0, 0, zval[0][0]); zval[1][0] = tram(1, false); - meshViewer.drawMesh(zval, 2, 2); + meshViewer.drawMeshPoint(1, 0, zval[1][0]); zval[1][1] = tram(2, false); - meshViewer.drawMesh(zval, 2, 2); + meshViewer.drawMeshPoint(1, 1, zval[1][1]); zval[0][1] = tram(3, false); + meshViewer.drawMeshPoint(0, 1, zval[0][1]); probe.stow(); - meshViewer.drawMesh(zval, 2, 2); DWINUI::drawCenteredString(140, GET_TEXT_F(MSG_CALCULATING_AVERAGE)); DWINUI::drawCenteredString(160, GET_TEXT_F(MSG_AND_RELATIVE_HEIGHTS)); @@ -2487,30 +2487,28 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, #define BED_TRAMMING_PROBE_TOLERANCE 0.05f #endif - if (ABS(meshViewer.max - meshViewer.min) < BED_TRAMMING_PROBE_TOLERANCE) { - EXIT_TRAMWIZ: + uint8_t p = 0; + float max = 0.0f; + FSTR_P plabel; + bool s = true; + for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) { + const float d = fabsf(zval[x][y]); + if (max < d) { + s = (zval[x][y] >= 0); + max = d; + p = y + 2 * x; + } + } + if (fabsf(meshViewer.max - meshViewer.min) < BED_TRAMMING_PROBE_TOLERANCE || UNEAR_ZERO(max)) { DWINUI::drawCenteredString(140, GET_TEXT_F(MSG_TRAMMING_DONE)); DWINUI::drawCenteredString(160, GET_TEXT_F(MSG_TOLERANCE_ACHIEVED)); } else { - uint8_t p = 0; - float max = 0.0f; - FSTR_P plabel; - bool s = true; - for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) { - const float d = ABS(zval[x][y]); - if (max < d) { - s = (zval[x][y] >= 0); - max = d; - p = y + 2 * x; - } - else { goto EXIT_TRAMWIZ; } // fail-safe if Corners are = 0.00 - } switch (p) { case 0b00 : plabel = GET_TEXT_F(MSG_TRAM_FL); break; - case 0b01 : plabel = GET_TEXT_F(MSG_TRAM_FR); break; - case 0b10 : plabel = GET_TEXT_F(MSG_TRAM_BR); break; - case 0b11 : plabel = GET_TEXT_F(MSG_TRAM_BL); break; + case 0b01 : plabel = GET_TEXT_F(MSG_TRAM_BL); break; + case 0b10 : plabel = GET_TEXT_F(MSG_TRAM_FR); break; + case 0b11 : plabel = GET_TEXT_F(MSG_TRAM_BR); break; default : plabel = F(""); break; } DWINUI::drawCenteredString(120, GET_TEXT_F(MSG_CORNERS_NOT_LEVELED)); From 85ab3762e1186c82e7526d711447d3b52b9cc6bf Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 19 Feb 2024 03:07:34 -0500 Subject: [PATCH 087/109] update printtime --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index ce4602054518..88246c307b5d 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1346,9 +1346,9 @@ void eachMomentUpdate() { #endif // Elapsed print time - const uint16_t min = print_job_timer.duration(); - if (_printtime.minute() + 1 <= min) { // 1 minute update - _printtime.value = min; + const duration_t min = print_job_timer.duration(); + if ((min.value % 60) == 0) { // 1 minute update + _printtime = min; drawPrintProgressElapsed(); } } From ed845d4e363c1c1b73db635dfb3ccc88f6238559 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 19 Feb 2024 04:51:57 -0500 Subject: [PATCH 088/109] add millis_t to duration_t.h --- Marlin/src/libs/duration_t.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index d648924dc95c..3f552fb342e6 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -27,7 +27,7 @@ struct duration_t { /** * @brief Duration is stored in seconds */ - uint32_t value; + millis_t value; /** * @brief Constructor @@ -40,7 +40,7 @@ struct duration_t { * * @param seconds The number of seconds */ - duration_t(uint32_t const &seconds) { + duration_t(millis_t const &seconds) { this->value = seconds; } @@ -51,7 +51,7 @@ struct duration_t { * @param value The number of seconds to compare to * @return True if both durations are equal */ - bool operator==(const uint32_t &value) const { + bool operator==(const millis_t &value) const { return (this->value == value); } @@ -62,7 +62,7 @@ struct duration_t { * @param value The number of seconds to compare to * @return False if both durations are equal */ - bool operator!=(const uint32_t &value) const { + bool operator!=(const millis_t &value) const { return ! this->operator==(value); } @@ -86,7 +86,7 @@ struct duration_t { * @brief Format the duration as hours * @return The number of hours */ - inline uint32_t hour() const { + inline millis_t hour() const { return this->minute() / 60; } @@ -94,7 +94,7 @@ struct duration_t { * @brief Format the duration as minutes * @return The number of minutes */ - inline uint32_t minute() const { + inline millis_t minute() const { return this->second() / 60; } @@ -102,7 +102,7 @@ struct duration_t { * @brief Format the duration as seconds * @return The number of seconds */ - inline uint32_t second() const { + inline millis_t second() const { return this->value; } From 22614cdbac2be87b4d850d41486b6788cbebc584 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 19 Feb 2024 10:24:07 -0500 Subject: [PATCH 089/109] swap const char * w/ PGM_P - ignore previous commits of same --- Marlin/src/lcd/e3v2/common/dwin_api.cpp | 2 +- Marlin/src/lcd/e3v2/common/dwin_api.h | 4 +-- Marlin/src/lcd/e3v2/creality/dwin.cpp | 6 ++-- Marlin/src/lcd/e3v2/creality/dwin.h | 2 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 26 ++++++++-------- Marlin/src/lcd/e3v2/jyersui/dwin.h | 16 +++++----- Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp | 4 +-- Marlin/src/lcd/e3v2/marlinui/dwin_string.h | 12 ++++---- .../src/lcd/e3v2/marlinui/lcdprint_dwin.cpp | 6 ++-- Marlin/src/lcd/e3v2/marlinui/ui_common.cpp | 8 ++--- .../lcd/e3v2/marlinui/ui_status_480x272.cpp | 4 +-- Marlin/src/lcd/e3v2/proui/dwin.cpp | 10 +++---- Marlin/src/lcd/e3v2/proui/dwin.h | 6 ++-- Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp | 2 +- Marlin/src/lcd/e3v2/proui/dwinui.cpp | 12 ++++---- Marlin/src/lcd/e3v2/proui/dwinui.h | 30 +++++++++---------- Marlin/src/lcd/e3v2/proui/gcode_preview.cpp | 10 +++---- Marlin/src/lcd/e3v2/proui/gcode_preview.h | 2 +- Marlin/src/lcd/e3v2/proui/menus.cpp | 12 ++++---- Marlin/src/lcd/e3v2/proui/menus.h | 12 ++++---- 20 files changed, 93 insertions(+), 93 deletions(-) diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index 16492be96ac2..1f6f93d28366 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -235,7 +235,7 @@ void dwinFrameAreaMove(uint8_t mode, uint8_t dir, uint16_t dis, // x/y: Upper-left coordinate of the string // *string: The string // rlimit: To limit the drawn string length -void dwinDrawString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit/*=0xFFFF*/) { +void dwinDrawString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, PGM_P const string, uint16_t rlimit/*=0xFFFF*/) { #if ENABLED(DWIN_CREALITY_LCD) dwinDrawRectangle(1, bColor, x, y, x + (fontWidth(size) * strlen_P(string)), y + fontHeight(size)); #endif diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h index c72fd18a5007..6d5eee4aa5a7 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -64,7 +64,7 @@ inline void dwinLong(size_t &i, const uint32_t lval) { // Send the data in the buffer plus the packet tail void dwinSend(size_t &i); -inline void dwinText(size_t &i, const char * const string, uint16_t rlimit=0xFFFF) { +inline void dwinText(size_t &i, PGM_P const string, uint16_t rlimit=0xFFFF) { if (!string) return; const size_t len = _MIN(sizeof(dwinSendBuf) - i, _MIN(strlen(string), rlimit)); if (len == 0) return; @@ -172,7 +172,7 @@ void dwinFrameAreaMove(uint8_t mode, uint8_t dir, uint16_t dis, // x/y: Upper-left coordinate of the string // *string: The string // rlimit: For draw less chars than string length use rlimit -void dwinDrawString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit=0xFFFF); +void dwinDrawString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, PGM_P const string, uint16_t rlimit=0xFFFF); inline void dwinDrawString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, FSTR_P const ftitle) { #ifdef __AVR__ diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 3f11f50dc1ee..906f21d96536 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -404,7 +404,7 @@ void _decorateMenuItem(const uint8_t line, const uint8_t icon, bool more) { if (icon) drawMenuIcon(line, icon); if (more) drawMoreIcon(line); } -void drawMenuItem(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { +void drawMenuItem(const uint8_t line, const uint8_t icon=0, PGM_P const label=nullptr, bool more=false) { if (label) dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLACK, LBLX, MBASE(line) - 1, (char*)label); _decorateMenuItem(line, icon, more); } @@ -413,7 +413,7 @@ void drawMenuItem(const uint8_t line, const uint8_t icon=0, FSTR_P const flabel= _decorateMenuItem(line, icon, more); } -void drawMenuLine(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { +void drawMenuLine(const uint8_t line, const uint8_t icon=0, PGM_P const label=nullptr, bool more=false) { drawMenuItem(line, icon, label, more); dwinDrawLine(COLOR_LINE, 16, MBASE(line) + 33, 256, MBASE(line) + 34); } @@ -4306,7 +4306,7 @@ void dwinLevelingDone() { if (checkkey == ID_Leveling) gotoMainMenu(); } -void dwinStatusChanged(const char * const cstr/*=nullptr*/) { +void dwinStatusChanged(PGM_P const cstr/*=nullptr*/) { dwinDrawRectangle(1, COLOR_BG_BLUE, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 24); const int8_t x = _MAX(0U, DWIN_WIDTH - strlen(cstr) * MENU_CHR_W) / 2; dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLUE, x, STATUS_Y + 3, cstr); diff --git a/Marlin/src/lcd/e3v2/creality/dwin.h b/Marlin/src/lcd/e3v2/creality/dwin.h index fce52d8cf41b..17ec1313709d 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.h +++ b/Marlin/src/lcd/e3v2/creality/dwin.h @@ -246,7 +246,7 @@ void hmiInit(); void dwinInitScreen(); void eachMomentUpdate(); void dwinHandleScreen(); -void dwinStatusChanged(const char * const cstr=nullptr); +void dwinStatusChanged(PGM_P const cstr=nullptr); void dwinStatusChanged(FSTR_P const fstr); inline void dwinHomingStart() { hmiFlag.home_flag = true; } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index f9ca1e6b9acd..77a251d50650 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -213,7 +213,7 @@ class TextScroller { scrollpos = 0; } - const char* scroll(size_t& pos, Buffer &buf, const char * text, bool *updated = nullptr) { + const char* scroll(size_t& pos, Buffer &buf, PGM_P text, bool *updated = nullptr) { const size_t len = strlen(text); if (len > SIZE) { if (updated) *updated = true; @@ -430,8 +430,8 @@ class TextScroller { // struct JyersDWIN::EEPROM_Settings JyersDWIN::eeprom_settings{0}; -constexpr const char * const JyersDWIN::color_names[11]; -constexpr const char * const JyersDWIN::preheat_modes[3]; +constexpr PGM_P const JyersDWIN::color_names[11]; +constexpr PGM_P const JyersDWIN::preheat_modes[3]; // Clear a part of the screen // 4=Entire screen @@ -457,7 +457,7 @@ void JyersDWIN::drawFloat(const_float_t value, const uint8_t row, const bool sel } } -void JyersDWIN::drawOption(const uint8_t value, const char * const * options, const uint8_t row, const bool selected/*=false*/, const bool color/*=false*/) { +void JyersDWIN::drawOption(const uint8_t value, PGM_P const * options, const uint8_t row, const bool selected/*=false*/, const bool color/*=false*/) { const uint16_t bColor = selected ? COLOR_SELECT : COLOR_BG_BLACK, tColor = color ? getColor(value, COLOR_WHITE, false) : COLOR_WHITE; dwinDrawRectangle(1, bColor, 202, MBASE(row) + 14, 258, MBASE(row) - 2); @@ -481,7 +481,7 @@ uint16_t JyersDWIN::getColor(const uint8_t color, const uint16_t original, const return COLOR_WHITE; } -void JyersDWIN::drawTitle(const char * const ctitle) { +void JyersDWIN::drawTitle(PGM_P const ctitle) { dwinDrawString(false, DWIN_FONT_HEAD, getColor(eeprom_settings.menu_top_txt, COLOR_WHITE, false), COLOR_BG_BLUE, (DWIN_WIDTH - strlen(ctitle) * STAT_CHR_W) / 2, 5, ctitle); } void JyersDWIN::drawTitle(FSTR_P const ftitle) { @@ -494,7 +494,7 @@ void _decorateMenuItem(uint8_t row, uint8_t icon, bool more) { dwinDrawLine(jyersDWIN.getColor(jyersDWIN.eeprom_settings.menu_split_line, COLOR_LINE, true), 16, MBASE(row) + 33, 256, MBASE(row) + 33); // Draw Menu Line } -void JyersDWIN::drawMenuItem(const uint8_t row, const uint8_t icon/*=0*/, const char * const label1, const char * const label2, const bool more/*=false*/, const bool centered/*=false*/) { +void JyersDWIN::drawMenuItem(const uint8_t row, const uint8_t icon/*=0*/, PGM_P const label1, PGM_P const label2, const bool more/*=false*/, const bool centered/*=false*/) { const uint8_t label_offset_y = label2 ? MENU_CHR_H * 3 / 5 : 0, label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2), label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); @@ -4486,12 +4486,12 @@ void JyersDWIN::optionControl() { else if (valuepointer == &preheat_modes) preheatmode = tempvalue; - drawOption(tempvalue, static_cast(valuepointer), selection - scrollpos, false, (valuepointer == &color_names)); + drawOption(tempvalue, static_cast(valuepointer), selection - scrollpos, false, (valuepointer == &color_names)); dwinUpdateLCD(); return; } LIMIT(tempvalue, valuemin, valuemax); - drawOption(tempvalue, static_cast(valuepointer), selection - scrollpos, true); + drawOption(tempvalue, static_cast(valuepointer), selection - scrollpos, true); dwinUpdateLCD(); } @@ -4842,9 +4842,9 @@ void JyersDWIN::modifyValue(int8_t &value, const_float_t min, const_float_t max, setupValue((float)value, min, max, unit, 5); } -void JyersDWIN::modifyOption(const uint8_t value, const char * const * options, const uint8_t max) { +void JyersDWIN::modifyOption(const uint8_t value, PGM_P const * options, const uint8_t max) { tempvalue = value; - valuepointer = const_cast(options); + valuepointer = const_cast(options); valuemin = 0; valuemax = max; process = Proc_Option; @@ -4856,7 +4856,7 @@ void JyersDWIN::modifyOption(const uint8_t value, const char * const * options, // Main Functions // -void JyersDWIN::updateStatus(const char * const text) { +void JyersDWIN::updateStatus(PGM_P const text) { if (strncmp_P(text, PSTR(""), 3) == 0) { for (uint8_t i = 0; i < _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text)); ++i) filename[i] = text[i + 3]; filename[_MIN((size_t)LONG_FILENAME_LENGTH - 1, strlen(text))] = '\0'; @@ -4877,7 +4877,7 @@ void JyersDWIN::startPrint(const bool sd) { #if ENABLED(POWER_LOSS_RECOVERY) if (recovery.valid()) { MediaFile *diveDir = nullptr; - const char * const fname = card.diveToFile(true, diveDir, recovery.info.sd_filename); + PGM_P const fname = card.diveToFile(true, diveDir, recovery.info.sd_filename); card.selectFileByName(fname); } #endif @@ -5091,7 +5091,7 @@ void JyersDWIN::saveSettings(char * const buff) { memcpy(buff, &eeprom_settings, _MIN(sizeof(eeprom_settings), eeprom_data_size)); } -void JyersDWIN::loadSettings(const char * const buff) { +void JyersDWIN::loadSettings(PGM_P const buff) { memcpy(&eeprom_settings, buff, _MIN(sizeof(eeprom_settings), eeprom_data_size)); TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); if (eeprom_settings.corner_pos == 0) eeprom_settings.corner_pos = 325; diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h index 48e413efbbb9..63c0d35b6002 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -197,17 +197,17 @@ class JyersDWIN { uint8_t coordinates_split_line : 4; } eeprom_settings; - static constexpr const char * const color_names[11] = { "Default", "White", "Green", "Cyan", "Blue", "Magenta", "Red", "Orange", "Yellow", "Brown", "Black" }; - static constexpr const char * const preheat_modes[3] = { "Both", "Hotend", "Bed" }; + static constexpr PGM_P const color_names[11] = { "Default", "White", "Green", "Cyan", "Blue", "Magenta", "Red", "Orange", "Yellow", "Brown", "Black" }; + static constexpr PGM_P const preheat_modes[3] = { "Both", "Hotend", "Bed" }; static void clearScreen(const uint8_t e=3); static void drawFloat(const_float_t value, const uint8_t row, const bool selected=false, const uint8_t minunit=10); - static void drawOption(const uint8_t value, const char * const * options, const uint8_t row, const bool selected=false, const bool color=false); + static void drawOption(const uint8_t value, PGM_P const * options, const uint8_t row, const bool selected=false, const bool color=false); static uint16_t getColor(const uint8_t color, const uint16_t original, const bool light=false); static void drawCheckbox(const uint8_t row, const bool value); - static void drawTitle(const char * const title); + static void drawTitle(PGM_P const title); static void drawTitle(FSTR_P const title); - static void drawMenuItem(const uint8_t row, uint8_t icon=0, const char * const label1=nullptr, const char * const label2=nullptr, const bool more=false, const bool centered=false); + static void drawMenuItem(const uint8_t row, uint8_t icon=0, PGM_P const label1=nullptr, PGM_P const label2=nullptr, const bool more=false, const bool centered=false); static void drawMenuItem(const uint8_t row, uint8_t icon=0, FSTR_P const flabel1=nullptr, FSTR_P const flabel2=nullptr, const bool more=false, const bool centered=false); static void drawMenu(const uint8_t menu, const uint8_t select=0, const uint8_t scroll=0); static void redrawMenu(const bool lastproc=true, const bool lastsel=false, const bool lastmenu=false); @@ -254,9 +254,9 @@ class JyersDWIN { static void modifyValue(int16_t &value, const_float_t min, const_float_t max, const_float_t unit, void (*f)()=nullptr); static void modifyValue(uint32_t &value, const_float_t min, const_float_t max, const_float_t unit, void (*f)()=nullptr); static void modifyValue(int8_t &value, const_float_t min, const_float_t max, const_float_t unit, void (*f)()=nullptr); - static void modifyOption(const uint8_t value, const char * const * options, const uint8_t max); + static void modifyOption(const uint8_t value, PGM_P const * options, const uint8_t max); - static void updateStatus(const char * const text); + static void updateStatus(PGM_P const text); static void startPrint(const bool sd); static void stopPrint(); static void update(); @@ -264,7 +264,7 @@ class JyersDWIN { static void screenUpdate(); static void audioFeedback(const bool success=true); static void saveSettings(char * const buff); - static void loadSettings(const char * const buff); + static void loadSettings(PGM_P const buff); static void resetSettings(); }; diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp index 7830d5a37cd2..05b8d0146e40 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp @@ -49,7 +49,7 @@ uint8_t read_byte(const uint8_t *byte) { return *byte; } * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder */ -void DWIN_String::add(const char *tpl, const int8_t index, const char *cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/) { +void DWIN_String::add(PGM_P tpl, const int8_t index, PGM_P cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/) { lchar_t wc; while (*tpl) { @@ -79,7 +79,7 @@ void DWIN_String::add(const char *tpl, const int8_t index, const char *cstr/*=nu eol(); } -void DWIN_String::add(const char *cstr, uint8_t max_len/*=MAX_STRING_LENGTH*/) { +void DWIN_String::add(PGM_P cstr, uint8_t max_len/*=MAX_STRING_LENGTH*/) { lchar_t wc; while (*cstr && max_len) { cstr = get_utf8_value_cb(cstr, read_byte, wc); diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h index 03f55233e251..352ceeafc7a7 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -80,8 +80,8 @@ class DWIN_String { * @param cstr The string * @param max_len Character limit */ - static void add(const char *cstr, uint8_t max_len=MAX_STRING_LENGTH); - static void set(const char *cstr) { set(); add(cstr); } + static void add(PGM_P cstr, uint8_t max_len=MAX_STRING_LENGTH); + static void set(PGM_P cstr) { set(); add(cstr); } /** * @brief Append / Set F-string @@ -100,8 +100,8 @@ class DWIN_String { * @param cstr An SRAM C-string to use for $ substitution * @param fstr A ROM F-string to use for $ substitution */ - static void add(const char *tpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr); - static void set(const char *tpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { set(); add(tpl, index, cstr, fstr); } + static void add(PGM_P tpl, const int8_t index, PGM_P cstr=nullptr, FSTR_P const fstr=nullptr); + static void set(PGM_P tpl, const int8_t index, PGM_P cstr=nullptr, FSTR_P const fstr=nullptr) { set(); add(tpl, index, cstr, fstr); } /** * @brief Append / Set F-string with optional substitution @@ -111,8 +111,8 @@ class DWIN_String { * @param cstr An SRAM C-string to use for $ substitution * @param fstr A ROM F-string to use for $ substitution */ - static void add(FSTR_P const ftpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { add(FTOP(ftpl), index, cstr, fstr); } - static void set(FSTR_P const ftpl, const int8_t index, const char *cstr=nullptr, FSTR_P const fstr=nullptr) { set(); add(ftpl, index, cstr, fstr); } + static void add(FSTR_P const ftpl, const int8_t index, PGM_P cstr=nullptr, FSTR_P const fstr=nullptr) { add(FTOP(ftpl), index, cstr, fstr); } + static void set(FSTR_P const ftpl, const int8_t index, PGM_P cstr=nullptr, FSTR_P const fstr=nullptr) { set(); add(ftpl, index, cstr, fstr); } // Common string ops static void trim(const char character=' '); diff --git a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp index f689a6ff698d..d265c58721a4 100644 --- a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp @@ -83,7 +83,7 @@ int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { * * Draw a UTF-8 string */ -static int lcd_put_u8str_max_cb(const char * utf8_str, read_byte_cb_t cb_read_byte, const pixel_len_t max_length) { +static int lcd_put_u8str_max_cb(PGM_P utf8_str, read_byte_cb_t cb_read_byte, const pixel_len_t max_length) { const uint8_t *p = (uint8_t *)utf8_str; dwin_string.set(); while (dwin_string.length < max_length) { @@ -97,7 +97,7 @@ static int lcd_put_u8str_max_cb(const char * utf8_str, read_byte_cb_t cb_read_by return dwin_string.length; } -int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { +int lcd_put_u8str_max(PGM_P utf8_str, const pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); } @@ -105,7 +105,7 @@ int lcd_put_u8str_max_P(PGM_P utf8_pstr, const pixel_len_t max_length) { return lcd_put_u8str_max_cb(utf8_pstr, read_byte_rom, max_length); } -lcd_uint_t lcd_put_u8str_P(PGM_P const ptpl, const int8_t ind, const char * const cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { +lcd_uint_t lcd_put_u8str_P(PGM_P const ptpl, const int8_t ind, PGM_P const cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { dwin_string.set(ptpl, ind, cstr, fstr); dwin_string.truncate(maxlen); dwinDrawString(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, dwin_string.string()); diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index 6a4cb6afde5e..b27c93f2da16 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -216,7 +216,7 @@ void MarlinUI::draw_status_message(const bool blink) { // Get a pointer to the next valid UTF8 character // and the string remaining length uint8_t rlen; - const char *stat = status_and_len(rlen); + PGM_P stat = status_and_len(rlen); lcd_put_u8str_max(stat, max_status_chars); // If the string doesn't completely fill the line... @@ -305,7 +305,7 @@ void MarlinUI::draw_status_message(const bool blink) { // Draw a static line of text in the same idiom as a menu item - void MenuItem_static::draw(const uint8_t row, FSTR_P const ftpl, const uint8_t style/*=SS_DEFAULT*/, const char *vstr/*=nullptr*/) { + void MenuItem_static::draw(const uint8_t row, FSTR_P const ftpl, const uint8_t style/*=SS_DEFAULT*/, PGM_P vstr/*=nullptr*/) { // Call mark_as_selected to draw a bigger selection box // and draw the text without a background if (!mark_as_selected(row, (bool)(style & SS_INVERT), true)) return; @@ -386,7 +386,7 @@ void MarlinUI::draw_status_message(const bool blink) { // // Draw a menu item with an editable value // - void MenuEditItemBase::draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char * const inStr, const bool pgm) { + void MenuEditItemBase::draw(const bool sel, const uint8_t row, FSTR_P const ftpl, PGM_P const inStr, const bool pgm) { if (!mark_as_selected(row, sel)) return; ui.set_font(DWIN_FONT_MENU); @@ -464,7 +464,7 @@ void MarlinUI::draw_status_message(const bool blink) { void MenuItem_confirm::draw_select_screen( FSTR_P const yes, FSTR_P const no, const bool yesno, - FSTR_P const fpre, const char * const string/*=nullptr*/, FSTR_P const fsuf/*=nullptr*/ + FSTR_P const fpre, PGM_P const string/*=nullptr*/, FSTR_P const fsuf/*=nullptr*/ ) { ui.set_font(DWIN_FONT_MENU); dwin_font.solid = false; diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp index c0b7ba90eccc..db0e7a5f91ed 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp @@ -68,7 +68,7 @@ bool old_is_printing; // Homed but unknown... '123' <-> ' '. // Homed and known, display constantly. // -void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink, const uint16_t x, const uint16_t y) { +void _draw_axis_value(const AxisEnum axis, PGM_P value, const bool blink, const uint16_t x, const uint16_t y) { const bool x_redraw = !ui.did_first_redraw || old_is_printing != print_job_timer.isRunning(); if (x_redraw) { dwin_string.set('X' + axis); @@ -250,7 +250,7 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater, const uint16_t x /** * Draw the current "feed rate" percentage preceded by the >> character */ -FORCE_INLINE void _draw_feedrate_status(const char *value, uint16_t x, uint16_t y) { +FORCE_INLINE void _draw_feedrate_status(PGM_P value, uint16_t x, uint16_t y) { if (!ui.did_first_redraw) { dwin_string.set(LCD_STR_FEEDRATE); dwinDrawString(true, font14x28, COLOR_ICONBLUE, COLOR_BG_BLACK, x, y, S(dwin_string.string())); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 88246c307b5d..97adef76404f 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -462,7 +462,7 @@ void popupPauseOrStop() { // // Draw status line // -void dwinDrawStatusLine(const char *text) { +void dwinDrawStatusLine(PGM_P text) { dwinDrawRectangle(1, hmiData.colorStatusBg, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); if (text) DWINUI::drawCenteredString(hmiData.colorStatusTxt, STATUS_Y + 2, text); } @@ -508,7 +508,7 @@ void dwinDrawStatusMessage() { // Get a pointer to the next valid UTF8 character // and the string remaining length uint8_t rlen; - const char *stat = ui.status_and_len(rlen); + PGM_P stat = ui.status_and_len(rlen); dwinDrawRectangle(1, hmiData.colorStatusBg, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); DWINUI::moveTo(0, STATUS_Y + 2); DWINUI::drawString(hmiData.colorStatusTxt, stat, LCD_WIDTH); @@ -578,7 +578,7 @@ void iconResumeOrPause() { } // Update filename on print -void dwinPrintHeader(const char *text = nullptr) { +void dwinPrintHeader(PGM_P text = nullptr) { static char headertxt[31] = ""; // Print header text if (text) { const int8_t size = _MIN(30U, strlen_P(text)); @@ -1380,7 +1380,7 @@ void eachMomentUpdate() { DWINUI::drawButton(BTN_Continue, 146, 280); } MediaFile *dir = nullptr; - const char * const filename = card.diveToFile(true, dir, recovery.info.sd_filename); + PGM_P const filename = card.diveToFile(true, dir, recovery.info.sd_filename); card.selectFileByName(filename); DWINUI::drawCenteredString(hmiData.colorPopupTxt, 207, card.longest_filename()); dwinPrintHeader(card.longest_filename()); // Save filename @@ -1837,7 +1837,7 @@ void dwinCopySettingsTo(char * const buff) { memcpy(buff, &hmiData, eeprom_data_size); } -void dwinCopySettingsFrom(const char * const buff) { +void dwinCopySettingsFrom(PGM_P const buff) { memcpy(&hmiData, buff, sizeof(hmi_data_t)); if (hmiData.colorText == hmiData.colorBackground) dwinSetColorDefaults(); DWINUI::setColors(hmiData.colorText, hmiData.colorBackground, hmiData.colorStatusBg); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index 94c1efcc8034..ba33065a727b 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -260,7 +260,7 @@ void gotoPowerLossRecovery(); void gotoConfirmToPrint(); void dwinDrawDashboard(); // Status Area void drawMainArea(); // Redraw main area -void dwinDrawStatusLine(const char *text = ""); // Draw simple status text +void dwinDrawStatusLine(PGM_P text = ""); // Draw simple status text void dwinRedrawDash(); // Redraw Dash and Status line void dwinRedrawScreen(); // Redraw all screen elements void hmiMainMenu(); // Main process screen @@ -289,10 +289,10 @@ void dwinPrintAborted(); #if HAS_FILAMENT_SENSOR void dwinFilamentRunout(const uint8_t extruder); #endif -void dwinPrintHeader(const char *text); +void dwinPrintHeader(PGM_P text); void dwinSetColorDefaults(); void dwinCopySettingsTo(char * const buff); -void dwinCopySettingsFrom(const char * const buff); +void dwinCopySettingsFrom(PGM_P const buff); void dwinSetDataDefaults(); void dwinRebootScreen(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp index e72752fdee41..d437d542e2ca 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp @@ -159,7 +159,7 @@ void dwinSRAMToPic(uint8_t picID) { //--------------------------Test area ------------------------- -//void dwinReadSRAM(uint16_t addr, const uint8_t length, const char * const data) { +//void dwinReadSRAM(uint16_t addr, const uint8_t length, PGM_P const data) { // size_t i = 0; // dwinByte(i, 0x32); // dwinByte(i, 0x5A); // 0x5A Read from SRAM - 0xA5 Read from Flash diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.cpp b/Marlin/src/lcd/e3v2/proui/dwinui.cpp index b17eccf59d53..880a9d32193d 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwinui.cpp @@ -135,7 +135,7 @@ void DWINUI::moveBy(xy_int_t point) { } // Draw a Centered string using arbitrary x1 and x2 margins -void DWINUI::drawCenteredString(bool bShow, fontid_t fid, uint16_t color, uint16_t bColor, uint16_t x1, uint16_t x2, uint16_t y, const char * const string) { +void DWINUI::drawCenteredString(bool bShow, fontid_t fid, uint16_t color, uint16_t bColor, uint16_t x1, uint16_t x2, uint16_t y, PGM_P const string) { const uint16_t x = _MAX(0U, x2 + x1 - strlen_P(string) * fontWidth(fid)) / 2 - 1; dwinDrawString(bShow, fid, color, bColor, x, y, string); } @@ -160,11 +160,11 @@ void DWINUI::drawChar(uint16_t color, const char c) { // color: Character color // *string: The string // rlimit: For draw less chars than string length use rlimit -void DWINUI::drawString(const char * const string, uint16_t rlimit) { +void DWINUI::drawString(PGM_P const string, uint16_t rlimit) { dwinDrawString(false, fontID, textColor, backColor, cursor.x, cursor.y, string, rlimit); moveBy(strlen(string) * fontWidth(fontID), 0); } -void DWINUI::drawString(uint16_t color, const char * const string, uint16_t rlimit) { +void DWINUI::drawString(uint16_t color, PGM_P const string, uint16_t rlimit) { dwinDrawString(false, fontID, color, backColor, cursor.x, cursor.y, string, rlimit); moveBy(strlen(string) * fontWidth(fontID), 0); } @@ -214,7 +214,7 @@ void DWINUI::ICON_Show(bool BG, uint8_t icon, uint16_t x, uint16_t y) { // ------------------------- Buttons ------------------------------// -void DWINUI::drawButton(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, const char * const caption) { +void DWINUI::drawButton(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, PGM_P const caption) { dwinDrawRectangle(1, bcolor, x1, y1, x2, y2); drawCenteredString(0, fontID, color, bcolor, x1, x2, (y2 + y1 - fontHeight()) / 2, caption); } @@ -327,7 +327,7 @@ void Title::draw() { if (DWINUI::onTitleDraw != nullptr) (*DWINUI::onTitleDraw)(this); } -void Title::setCaption(const char * const titleStr) { +void Title::setCaption(PGM_P const titleStr) { frameid = 0; if ( caption == titleStr ) return; const uint8_t len = _MIN(sizeof(caption) - 1, strlen(titleStr)); @@ -335,7 +335,7 @@ void Title::setCaption(const char * const titleStr) { caption[len] = '\0'; } -void Title::showCaption(const char * const titleStr) { +void Title::showCaption(PGM_P const titleStr) { setCaption(titleStr); draw(); } diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h index ffcbb8420a18..7348150110ab 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.h +++ b/Marlin/src/lcd/e3v2/proui/dwinui.h @@ -213,9 +213,9 @@ class Title { uint8_t frameid = 0; rect_t frame = {0}; void draw(); - void setCaption(const char * const titleStr); + void setCaption(PGM_P const titleStr); inline void setCaption(FSTR_P fTitle) { setCaption((char *)fTitle); } - void showCaption(const char * const titleStr); + void showCaption(PGM_P const titleStr); inline void showCaption(FSTR_P fTitle) { showCaption((char *)fTitle); } void setFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); void setFrame(uint16_t x, uint16_t y, uint16_t w, uint16_t h); @@ -426,8 +426,8 @@ namespace DWINUI { // color: Character color // *string: The string // rlimit: For draw less chars than string length use rlimit - void drawString(const char * const string, uint16_t rlimit = 0xFFFF); - void drawString(uint16_t color, const char * const string, uint16_t rlimit = 0xFFFF); + void drawString(PGM_P const string, uint16_t rlimit = 0xFFFF); + void drawString(uint16_t color, PGM_P const string, uint16_t rlimit = 0xFFFF); inline void drawString(FSTR_P string, uint16_t rlimit = 0xFFFF) { drawString(FTOP(string), rlimit); } @@ -441,25 +441,25 @@ namespace DWINUI { // bColor: Background color // x/y: Upper-left coordinate of the string // *string: The string - inline void drawString(uint16_t x, uint16_t y, const char * const string) { + inline void drawString(uint16_t x, uint16_t y, PGM_P const string) { dwinDrawString(false, fontID, textColor, backColor, x, y, string); } inline void drawString(uint16_t x, uint16_t y, FSTR_P fTitle) { dwinDrawString(false, fontID, textColor, backColor, x, y, FTOP(fTitle)); } - inline void drawString(uint16_t color, uint16_t x, uint16_t y, const char * const string) { + inline void drawString(uint16_t color, uint16_t x, uint16_t y, PGM_P const string) { dwinDrawString(false, fontID, color, backColor, x, y, string); } inline void drawString(uint16_t color, uint16_t x, uint16_t y, FSTR_P fTitle) { dwinDrawString(false, fontID, color, backColor, x, y, fTitle); } - inline void drawString(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const char * const string) { + inline void drawString(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, PGM_P const string) { dwinDrawString(true, fontID, color, bgcolor, x, y, string); } inline void drawString(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, FSTR_P fTitle) { dwinDrawString(true, fontID, color, bgcolor, x, y, fTitle); } - inline void drawString(fontid_t fid, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const char * const string) { + inline void drawString(fontid_t fid, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, PGM_P const string) { dwinDrawString(true, fid, color, bgcolor, x, y, string); } inline void drawString(fontid_t fid, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, FSTR_P fTitle) { @@ -473,29 +473,29 @@ namespace DWINUI { // bColor: Background color // y: Upper coordinate of the string // *string: The string - void drawCenteredString(bool bShow, fontid_t fid, uint16_t color, uint16_t bColor, uint16_t x1, uint16_t x2, uint16_t y, const char * const string); - inline void drawCenteredString(bool bShow, fontid_t fid, uint16_t color, uint16_t bColor, uint16_t y, const char * const string) { + void drawCenteredString(bool bShow, fontid_t fid, uint16_t color, uint16_t bColor, uint16_t x1, uint16_t x2, uint16_t y, PGM_P const string); + inline void drawCenteredString(bool bShow, fontid_t fid, uint16_t color, uint16_t bColor, uint16_t y, PGM_P const string) { drawCenteredString(bShow, fid, color, bColor, 0, DWIN_WIDTH, y, string); } inline void drawCenteredString(bool bShow, fontid_t fid, uint16_t color, uint16_t bColor, uint16_t y, FSTR_P string) { drawCenteredString(bShow, fid, color, bColor, y, FTOP(string)); } - inline void drawCenteredString(uint16_t color, uint16_t bcolor, uint16_t y, const char * const string) { + inline void drawCenteredString(uint16_t color, uint16_t bcolor, uint16_t y, PGM_P const string) { drawCenteredString(true, fontID, color, bcolor, y, string); } - inline void drawCenteredString(fontid_t fid, uint16_t color, uint16_t y, const char * const string) { + inline void drawCenteredString(fontid_t fid, uint16_t color, uint16_t y, PGM_P const string) { drawCenteredString(false, fid, color, backColor, y, string); } inline void drawCenteredString(fontid_t fid, uint16_t color, uint16_t y, FSTR_P fTitle) { drawCenteredString(false, fid, color, backColor, y, fTitle); } - inline void drawCenteredString(uint16_t color, uint16_t y, const char * const string) { + inline void drawCenteredString(uint16_t color, uint16_t y, PGM_P const string) { drawCenteredString(false, fontID, color, backColor, y, string); } inline void drawCenteredString(uint16_t color, uint16_t y, FSTR_P fTitle) { drawCenteredString(false, fontID, color, backColor, y, fTitle); } - inline void drawCenteredString(uint16_t y, const char * const string) { + inline void drawCenteredString(uint16_t y, PGM_P const string) { drawCenteredString(false, fontID, textColor, backColor, y, string); } inline void drawCenteredString(uint16_t y, FSTR_P fTitle) { @@ -540,7 +540,7 @@ namespace DWINUI { // ------------------------- Buttons ------------------------------// - void drawButton(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, const char * const caption); + void drawButton(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, PGM_P const caption); inline void drawButton(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, FSTR_P caption) { drawButton(color, bcolor, x1, y1, x2, y2, FTOP(caption)); } diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp index c14e35f513f4..d0aaa4abbcd5 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -53,7 +53,7 @@ Preview preview; fileprop_t fileprop; -void fileprop_t::setname(const char * const fn) { +void fileprop_t::setname(PGM_P const fn) { const uint8_t len = _MIN(sizeof(name) - 1, strlen(fn)); memcpy(name, fn, len); name[len] = '\0'; @@ -70,10 +70,10 @@ void fileprop_t::clear() { height = width = length = 0; } -void getValue(const char * const buf, PGM_P const key, float &value) { +void getValue(PGM_P const buf, PGM_P const key, float &value) { if (value != 0.0f) return; - const char *posptr = strstr_P(buf, key); + PGM_P posptr = strstr_P(buf, key); if (posptr == nullptr) return; char num[10] = ""; @@ -90,8 +90,8 @@ void getValue(const char * const buf, PGM_P const key, float &value) { } bool Preview::hasPreview() { - const char * const tbstart = PSTR("; thumbnail begin " STRINGIFY(THUMBWIDTH) "x" STRINGIFY(THUMBHEIGHT)); - const char *posptr = nullptr; + PGM_P const tbstart = PSTR("; thumbnail begin " STRINGIFY(THUMBWIDTH) "x" STRINGIFY(THUMBHEIGHT)); + PGM_P posptr = nullptr; uint32_t indx = 0; float tmp = 0; diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.h b/Marlin/src/lcd/e3v2/proui/gcode_preview.h index 4d8325678ecb..dc4e5c13c518 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.h +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.h @@ -49,7 +49,7 @@ typedef struct { layer, width, height, length; - void setname(const char * const fn); + void setname(PGM_P const fn); void clear(); } fileprop_t; diff --git a/Marlin/src/lcd/e3v2/proui/menus.cpp b/Marlin/src/lcd/e3v2/proui/menus.cpp index 97eed1d0104c..62bbba591190 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.cpp +++ b/Marlin/src/lcd/e3v2/proui/menus.cpp @@ -72,7 +72,7 @@ void eraseMenuText(const int8_t line) { DWINUI::drawBox(1, hmiData.colorBackground, {LBLX, ypos, DWIN_WIDTH - LBLX, MLINE - 2}); } -void drawMenuLine(const uint8_t line, const uint8_t icon/*=0*/, const char * const label/*=nullptr*/, bool more/*=false*/, bool selected/*=false*/) { +void drawMenuLine(const uint8_t line, const uint8_t icon/*=0*/, PGM_P const label/*=nullptr*/, bool more/*=false*/, bool selected/*=false*/) { if (icon) DWINUI::drawIcon(icon, ICOX, MBASE(line) - 3); if (label) DWINUI::drawString(LBLX, MBASE(line) - 1, (char*)label); if (more) DWINUI::drawIcon(ICON_More, VALX + 16, MBASE(line) - 3); @@ -410,7 +410,7 @@ CustomMenuItem::CustomMenuItem(OnDrawItem ondraw, OnClickItem onclick) { onDraw = ondraw; } -MenuItem::MenuItem(uint8_t cicon, const char * const text, OnDrawItem ondraw, OnClickItem onclick) : CustomMenuItem(ondraw, onclick) { +MenuItem::MenuItem(uint8_t cicon, PGM_P const text, OnDrawItem ondraw, OnClickItem onclick) : CustomMenuItem(ondraw, onclick) { icon = cicon; setCaption(text); } @@ -422,7 +422,7 @@ MenuItem::MenuItem(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t frame = { x1, y1, x2, y2 }; } -void MenuItem::setCaption(const char * const text) { +void MenuItem::setCaption(PGM_P const text) { const uint8_t len = _MIN(sizeof(caption) - 1, strlen(text)); memcpy(&caption[0], text, len); caption[len] = '\0'; @@ -434,7 +434,7 @@ void MenuItem::setFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint1 frame = { x1, y1, x2, y2 }; } -MenuItemPtr::MenuItemPtr(uint8_t cicon, const char * const text, OnDrawItem ondraw, OnClickItem onclick, void* val) : MenuItem(cicon, text, ondraw, onclick) { +MenuItemPtr::MenuItemPtr(uint8_t cicon, PGM_P const text, OnDrawItem ondraw, OnClickItem onclick, void* val) : MenuItem(cicon, text, ondraw, onclick) { value = val; }; @@ -474,7 +474,7 @@ CustomMenuItem* menuItemAdd(OnDrawItem ondraw/*=nullptr*/, OnClickItem onclick/* else return nullptr; } -MenuItem* menuItemAdd(uint8_t cicon, const char * const text/*=nullptr*/, OnDrawItem ondraw/*=nullptr*/, OnClickItem onclick/*=nullptr*/) { +MenuItem* menuItemAdd(uint8_t cicon, PGM_P const text/*=nullptr*/, OnDrawItem ondraw/*=nullptr*/, OnClickItem onclick/*=nullptr*/) { if (MenuItemCount < MenuItemTotal) { MenuItem* menuitem = new MenuItem(cicon, text, ondraw, onclick); return menuItemAdd(menuitem); @@ -490,7 +490,7 @@ MenuItem* menuItemAdd(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint1 else return nullptr; } -MenuItem* editItemAdd(uint8_t cicon, const char * const text, OnDrawItem ondraw, OnClickItem onclick, void* val) { +MenuItem* editItemAdd(uint8_t cicon, PGM_P const text, OnDrawItem ondraw, OnClickItem onclick, void* val) { if (MenuItemCount < MenuItemTotal) { MenuItem* menuitem = new MenuItemPtr(cicon, text, ondraw, onclick, val); return menuItemAdd(menuitem); diff --git a/Marlin/src/lcd/e3v2/proui/menus.h b/Marlin/src/lcd/e3v2/proui/menus.h index d1f5cdb698ba..4c14735a0f38 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.h +++ b/Marlin/src/lcd/e3v2/proui/menus.h @@ -90,17 +90,17 @@ class MenuItem: public CustomMenuItem { uint8_t frameid = 0; rect_t frame = {0}; using CustomMenuItem::CustomMenuItem; - MenuItem(uint8_t cicon, const char * const text=nullptr, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); + MenuItem(uint8_t cicon, PGM_P const text=nullptr, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); MenuItem(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); void setFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); - void setCaption(const char * const text=nullptr); + void setCaption(PGM_P const text=nullptr); }; class MenuItemPtr: public MenuItem { public: void *value = nullptr; using MenuItem::MenuItem; - MenuItemPtr(uint8_t cicon, const char * const text, OnDrawItem ondraw, OnClickItem onclick, void* val); + MenuItemPtr(uint8_t cicon, PGM_P const text, OnDrawItem ondraw, OnClickItem onclick, void* val); MenuItemPtr(uint8_t cicon, FSTR_P text, OnDrawItem ondraw, OnClickItem onclick, void* val) : MenuItemPtr(cicon, FTOP(text), ondraw, onclick, val){} }; @@ -129,7 +129,7 @@ void drawTitle(Title* aTitle); void drawMenuCursor(const int8_t line); void eraseMenuCursor(const int8_t line); void eraseMenuText(const int8_t line); -void drawMenuLine(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false, bool selected=false); +void drawMenuLine(const uint8_t line, const uint8_t icon=0, PGM_P const label=nullptr, bool more=false, bool selected=false); void drawMenuLine(const uint8_t line, const uint8_t icon=0, FSTR_P label=nullptr, bool more=false, bool selected=false); void drawCheckboxLine(const uint8_t line, const bool checked); void showCheckboxLine(const bool checked); @@ -203,12 +203,12 @@ bool isMenu(Menu* menu); // Add elements to the menuItems array CustomMenuItem* menuItemAdd(OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); -MenuItem* menuItemAdd(uint8_t cicon, const char * const text=nullptr, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); +MenuItem* menuItemAdd(uint8_t cicon, PGM_P const text=nullptr, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); inline MenuItem* menuItemAdd(uint8_t cicon, FSTR_P text=nullptr, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr) { return menuItemAdd(cicon, FTOP(text), ondraw, onclick); } MenuItem* menuItemAdd(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); -MenuItem* editItemAdd(uint8_t cicon, const char * const text, OnDrawItem ondraw, OnClickItem onclick, void* val); +MenuItem* editItemAdd(uint8_t cicon, PGM_P const text, OnDrawItem ondraw, OnClickItem onclick, void* val); inline MenuItem* editItemAdd(uint8_t cicon, FSTR_P text, OnDrawItem ondraw, OnClickItem onclick, void* val) { return editItemAdd(cicon, FTOP(text), ondraw, onclick, val); } From 819145f589ab47857e2337f3c28efed43c896cfa Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Mon, 19 Feb 2024 10:38:45 -0500 Subject: [PATCH 090/109] revert PGM_P swap on gcode_preview --- Marlin/src/lcd/e3v2/proui/gcode_preview.cpp | 10 +++++----- Marlin/src/lcd/e3v2/proui/gcode_preview.h | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp index d0aaa4abbcd5..a4b870eada4d 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -53,7 +53,7 @@ Preview preview; fileprop_t fileprop; -void fileprop_t::setname(PGM_P const fn) { +void fileprop_t::setname(const char * const fn) { const uint8_t len = _MIN(sizeof(name) - 1, strlen(fn)); memcpy(name, fn, len); name[len] = '\0'; @@ -70,10 +70,10 @@ void fileprop_t::clear() { height = width = length = 0; } -void getValue(PGM_P const buf, PGM_P const key, float &value) { +void getValue(const char * const buf, const char * const key, float &value) { if (value != 0.0f) return; - PGM_P posptr = strstr_P(buf, key); + const char * posptr = strstr_P(buf, key); if (posptr == nullptr) return; char num[10] = ""; @@ -90,8 +90,8 @@ void getValue(PGM_P const buf, PGM_P const key, float &value) { } bool Preview::hasPreview() { - PGM_P const tbstart = PSTR("; thumbnail begin " STRINGIFY(THUMBWIDTH) "x" STRINGIFY(THUMBHEIGHT)); - PGM_P posptr = nullptr; + const char * const tbstart = PSTR("; thumbnail begin " STRINGIFY(THUMBWIDTH) "x" STRINGIFY(THUMBHEIGHT)); + const char * posptr = nullptr; uint32_t indx = 0; float tmp = 0; diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.h b/Marlin/src/lcd/e3v2/proui/gcode_preview.h index dc4e5c13c518..4d8325678ecb 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.h +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.h @@ -49,7 +49,7 @@ typedef struct { layer, width, height, length; - void setname(PGM_P const fn); + void setname(const char * const fn); void clear(); } fileprop_t; From db3684da79226f97d8c96b47dec5cddd5d929deb Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 20 Feb 2024 20:27:02 -0500 Subject: [PATCH 091/109] tweak caselightbrightness --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 97adef76404f..824aef7d12fc 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2215,8 +2215,9 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, } #if CASELIGHT_USES_BRIGHTNESS bool enableLiveCaseLightBrightness = true; - void liveCaseLightBrightness() { caselight.brightness = menuData.value; caselight.update_brightness(); } - void setCaseLightBrightness() { setIntOnClick(0, 255, caselight.brightness, liveCaseLightBrightness, enableLiveCaseLightBrightness ? liveCaseLightBrightness : nullptr); } + void applyCaseLightBrightness() { caselight.brightness = menuData.value; } + void liveCaseLightBrightness() { caselight.update_brightness(); } + void setCaseLightBrightness() { setIntOnClick(0, 255, caselight.brightness, applyCaseLightBrightness, enableLiveCaseLightBrightness ? liveCaseLightBrightness : nullptr); } #endif #endif From 9c7813dd1f751b9a216a9b28c288d52ca425604e Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 20 Feb 2024 22:18:48 -0500 Subject: [PATCH 092/109] revert duration_t.h for other PR --- Marlin/src/libs/duration_t.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 3f552fb342e6..d648924dc95c 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -27,7 +27,7 @@ struct duration_t { /** * @brief Duration is stored in seconds */ - millis_t value; + uint32_t value; /** * @brief Constructor @@ -40,7 +40,7 @@ struct duration_t { * * @param seconds The number of seconds */ - duration_t(millis_t const &seconds) { + duration_t(uint32_t const &seconds) { this->value = seconds; } @@ -51,7 +51,7 @@ struct duration_t { * @param value The number of seconds to compare to * @return True if both durations are equal */ - bool operator==(const millis_t &value) const { + bool operator==(const uint32_t &value) const { return (this->value == value); } @@ -62,7 +62,7 @@ struct duration_t { * @param value The number of seconds to compare to * @return False if both durations are equal */ - bool operator!=(const millis_t &value) const { + bool operator!=(const uint32_t &value) const { return ! this->operator==(value); } @@ -86,7 +86,7 @@ struct duration_t { * @brief Format the duration as hours * @return The number of hours */ - inline millis_t hour() const { + inline uint32_t hour() const { return this->minute() / 60; } @@ -94,7 +94,7 @@ struct duration_t { * @brief Format the duration as minutes * @return The number of minutes */ - inline millis_t minute() const { + inline uint32_t minute() const { return this->second() / 60; } @@ -102,7 +102,7 @@ struct duration_t { * @brief Format the duration as seconds * @return The number of seconds */ - inline millis_t second() const { + inline uint32_t second() const { return this->value; } From 27413e0a6065921b18585ccedfcd34dd7e89241d Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Tue, 20 Feb 2024 22:37:36 -0500 Subject: [PATCH 093/109] change to update every second --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 824aef7d12fc..8399a470d55e 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1347,10 +1347,9 @@ void eachMomentUpdate() { // Elapsed print time const duration_t min = print_job_timer.duration(); - if ((min.value % 60) == 0) { // 1 minute update - _printtime = min; - drawPrintProgressElapsed(); - } + //if ((min.value % 60) == 0) // 1 minute update, else every second + _printtime = min; + drawPrintProgressElapsed(); } #if ENABLED(POWER_LOSS_RECOVERY) else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // Resume print before power off From 5f93b1cbcba992fef9bf07385f0dbf84edb6d71e Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 21 Feb 2024 23:01:58 -0500 Subject: [PATCH 094/109] update ubl_g29.cpp comment spacing --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 226 +++++++++----------- 1 file changed, 106 insertions(+), 120 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 250a70f066af..2dad10d4e164 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -126,9 +126,9 @@ * L # Load Load Mesh from the specified location in the EEPROM. Set this location as activated * for subsequent Load and Store operations. * - * The P or Phase commands are used for the bulk of the work to setup a Mesh. In general, your Mesh will - * start off being initialized with a G29 P0 or a G29 P1. Further refinement of the Mesh happens with - * each additional Phase that processes it. + * NOTE: The P or Phase commands are used for the bulk of the work to setup a Mesh. In general, your Mesh + * will start off being initialized with a G29 P0 or a G29 P1. Further refinement of the Mesh happens + * with each additional Phase that processes it. * * P0 Phase 0 Zero Mesh Data and turn off the Mesh Compensation System. This reverts the * 3D Printer to the same state it was in before the Unified Bed Leveling Compensation @@ -215,7 +215,7 @@ * * !!Use with caution, as a very poor mesh could cause the nozzle to crash into the bed!! * - * NOTE: P4 is not available unless you have LCD support enabled! + * NOTE: P4 is not available unless you have LCD support enabled! * * P5 Phase 5 Find Mean Mesh Height and Standard Deviation. Typically, it is easier to use and * work with the Mesh if it is Mean Adjusted. You can specify a C parameter to @@ -359,9 +359,11 @@ void unified_bed_leveling::G29() { while (count--) { if ((count & 0x0F) == 0x0F) idle(); const mesh_index_pair closest = find_closest_mesh_point_of_type(REAL, param.XY_pos); - // No more REAL mesh points to invalidate? Assume the user meant - // to invalidate the ENTIRE mesh, which can't be done with - // find_closest_mesh_point (which only returns REAL points). + /** + * No more REAL mesh points to invalidate? Assume the user meant + * to invalidate the ENTIRE mesh, which can't be done with + * find_closest_mesh_point (which only returns REAL points). + */ if (closest.pos.x < 0) { invalidate_all = true; break; } z_values[closest.pos.x][closest.pos.y] = NAN; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(closest.pos, 0.0f)); @@ -388,8 +390,8 @@ void unified_bed_leveling::G29() { default: case -1: TERN_(UBL_DEVEL_DEBUGGING, g29_eeprom_dump()); break; - case 0: - GRID_LOOP(x, y) { // Create a bowl shape similar to a poorly-calibrated Delta + case 0: // Create a bowl shape similar to a poorly-calibrated Delta + GRID_LOOP(x, y) { const float p1 = 0.5f * (GRID_MAX_POINTS_X) - x, p2 = 0.5f * (GRID_MAX_POINTS_Y) - y; z_values[x][y] += 2.0f * HYPOT(p1, p2); @@ -397,8 +399,8 @@ void unified_bed_leveling::G29() { } break; - case 1: - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; ++x) { // Create a diagonal line several Mesh cells thick that is raised + case 1: // Create a diagonal line several Mesh cells thick that is raised + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; ++x) { const uint8_t x2 = x + (x < (GRID_MAX_POINTS_Y) - 1 ? 1 : -1); z_values[x][x] += 9.999f; z_values[x][x2] += 9.999f; // We want the altered line several mesh points thick @@ -409,12 +411,11 @@ void unified_bed_leveling::G29() { } break; - case 2: - // Allow the user to specify the height because 10mm is a little extreme in some cases. - for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in - for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) { // the center of the bed - z_values[x][y] += parser.seen_test('C') ? param.C_constant : 9.99f; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); + case 2: // Create a rectangular raised area in the center of the bed + for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) + for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) { + z_values[x][y] += parser.seen_test('C') ? param.C_constant : 9.99f; // Allow the user to specify the height because + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y])); // 10mm is a little extreme in some cases. } break; } @@ -442,20 +443,15 @@ void unified_bed_leveling::G29() { } switch (param.P_phase) { - case 0: - // - // Zero Mesh Data - // + case 0: // Zero Mesh Data reset(); SERIAL_ECHOLNPGM("Mesh zeroed."); break; #if HAS_BED_PROBE - case 1: { - // - // Invalidate Entire Mesh and Automatically Probe Mesh in areas that can be reached by the probe - // + case 1: { // Invalidate Entire Mesh and Automatically Probe Mesh + // in areas that can be reached by the probe if (!parser.seen_test('C')) { invalidate(); SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh."); @@ -470,16 +466,13 @@ void unified_bed_leveling::G29() { #endif // HAS_BED_PROBE - case 2: { + case 2: { // Manually Probe Mesh in areas that can't be reached by the probe #if HAS_MARLINUI_MENU - // - // Manually Probe Mesh in areas that can't be reached by the probe - // + SERIAL_ECHOLNPGM("Manually probing unreachable points."); do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); if (parser.seen_test('C') && !param.XY_seen) { - /** * Use a good default location for the path. * The flipped > and < operators in these comparisons is intentional. @@ -526,20 +519,19 @@ void unified_bed_leveling::G29() { #endif } break; - case 3: { + case 3: { // Populate invalid mesh areas /** - * Populate invalid mesh areas. Proceed with caution. + * Proceed with caution. * Two choices are available: * - Specify a constant with the 'C' parameter. * - Allow 'G29 P3' to choose a 'reasonable' constant. */ - if (param.C_seen) { if (param.R_repetition >= GRID_MAX_POINTS) { set_all_mesh_points_to_value(param.C_constant); } else { - while (param.R_repetition--) { // this only populates reachable mesh points near + while (param.R_repetition--) { // This only populates reachable mesh points near const mesh_index_pair closest = find_closest_mesh_point_of_type(INVALID, param.XY_pos); const xy_int8_t &cpos = closest.pos; if (cpos.x < 0) { @@ -557,25 +549,26 @@ void unified_bed_leveling::G29() { } else { const float cvf = parser.value_float(); - switch ((int)TRUNC(cvf * 10.0f) - 30) { // 3.1 -> 1 + switch ((int)TRUNC(cvf * 10.0f) - 30) { // 3.1 -> 1 #if ENABLED(UBL_G29_P31) case 1: { - - // P3.1 use least squares fit to fill missing mesh values - // P3.10 zero weighting for distance, all grid points equal, best fit tilted plane - // P3.11 10X weighting for nearest grid points versus farthest grid points - // P3.12 100X distance weighting - // P3.13 1000X distance weighting, approaches simple average of nearest points - - const float weight_power = (cvf - 3.10f) * 100.0f, // 3.12345 -> 2.345 + /** + * P3.1 use least squares fit to fill missing mesh values + * P3.10 zero weighting for distance, all grid points equal, best fit tilted plane + * P3.11 10X weighting for nearest grid points versus farthest grid points + * P3.12 100X distance weighting + * P3.13 1000X distance weighting, approaches simple average of nearest points + */ + const float weight_power = (cvf - 3.10f) * 100.0f, // 3.12345 -> 2.345 weight_factor = weight_power ? POW(10.0f, weight_power) : 0; smart_fill_wlsf(weight_factor); } break; #endif - case 0: // P3 or P3.0 - default: // and anything P3.x that's not P3.1 - smart_fill_mesh(); // Do a 'Smart' fill using nearby known values + case 0: // P3 or P3.0 + default: // and anything P3.x that's not P3.1 + // Do a 'Smart' fill using nearby known values + smart_fill_mesh(); break; } } @@ -610,16 +603,15 @@ void unified_bed_leveling::G29() { // use cases for the users. So we can wait and see what to do with it. // - if (parser.seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh - g29_compare_current_mesh_to_stored_mesh(); + // Kompare Current Mesh Data to Specified Stored Mesh + if (parser.seen('K')) g29_compare_current_mesh_to_stored_mesh(); #endif // UBL_DEVEL_DEBUGGING // // Load a Mesh from the EEPROM // - - if (parser.seen('L')) { // Load Current Mesh Data + if (parser.seen('L')) { // Load Current Mesh Data param.KLS_storage_slot = parser.has_value() ? (int8_t)parser.value_int() : storage_slot; int16_t a = settings.calc_num_meshes(); @@ -643,12 +635,11 @@ void unified_bed_leveling::G29() { // // Store a Mesh in the EEPROM // - - if (parser.seen('S')) { // Store (or Save) Current Mesh Data + if (parser.seen('S')) { // Store (or Save) Current Mesh Data param.KLS_storage_slot = parser.has_value() ? (int8_t)parser.value_int() : storage_slot; - if (param.KLS_storage_slot == -1) // Special case: 'Export' the mesh to the - return report_current_mesh(); // host so it can be saved in a file. + if (param.KLS_storage_slot == -1) // Special case: 'Export' the mesh to the + return report_current_mesh(); // host so it can be saved in a file. int16_t a = settings.calc_num_meshes(); @@ -756,7 +747,7 @@ void unified_bed_leveling::shift_mesh_height() { TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); TERN_(DWIN_LCD_PROUI, dwinLevelingStart()); - save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained + save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained grid_count_t count = GRID_MAX_POINTS; mesh_index_pair best; @@ -791,10 +782,10 @@ void unified_bed_leveling::shift_mesh_height() { ? find_furthest_invalid_mesh_point() : find_closest_mesh_point_of_type(INVALID, nearby, true); - if (best.pos.x >= 0) { // mesh point found and is reachable by probe + if (best.pos.x >= 0) { // mesh point found and is reachable by probe TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::G29_POINT_START)); const float measured_z = probe.probe_at_point(best.meshpos(), stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); - z_values[best.pos.x][best.pos.y] = isnan(measured_z) ? HUGE_VALF : measured_z; // Mark invalid point already probed with HUGE_VALF to omit it in the next loop + z_values[best.pos.x][best.pos.y] = isnan(measured_z) ? HUGE_VALF : measured_z; // Mark invalid point already probed with HUGE_VALF to omit it in the next loop #if ENABLED(EXTENSIBLE_UI) ExtUI::onMeshUpdate(best.pos, ExtUI::G29_POINT_FINISH); ExtUI::onMeshUpdate(best.pos, measured_z); @@ -843,11 +834,11 @@ void set_message_with_feedback(FSTR_P const fstr) { bool _click_and_hold(const clickFunc_t func=nullptr) { if (ui.button_pressed()) { - ui.quick_feedback(false); // Preserve button state for click-and-hold + ui.quick_feedback(false); // Preserve button state for click-and-hold const millis_t nxt = millis() + 1500UL; - while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag! - idle(); // idle, of course - if (ELAPSED(millis(), nxt)) { // After 1.5 seconds + while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag! + idle(); // idle, of course + if (ELAPSED(millis(), nxt)) { // After 1.5 seconds ui.quick_feedback(); if (func) (*func)(); ui.wait_for_release(); @@ -882,7 +873,7 @@ void set_message_with_feedback(FSTR_P const fstr) { float unified_bed_leveling::measure_business_card_thickness() { ui.capture(); - save_ubl_active_state_and_disable(); // Disable bed level correction for probing + save_ubl_active_state_and_disable(); // Disable bed level correction for probing do_blocking_move_to( xyz_pos_t({ @@ -946,7 +937,7 @@ void set_message_with_feedback(FSTR_P const fstr) { ui.capture(); TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); - save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained + save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained do_blocking_move_to_xy_z(current_position, z_clearance); ui.return_to_status(); @@ -970,7 +961,7 @@ void set_message_with_feedback(FSTR_P const fstr) { KEEPALIVE_STATE(PAUSED_FOR_USER); ui.capture(); - if (do_ubl_mesh_map) display_map(param.T_map_type); // Show user where we're probing + if (do_ubl_mesh_map) display_map(param.T_map_type); // Show user where we're probing if (parser.seen_test('B')) { SERIAL_ECHOPGM("Place Shim & Measure"); @@ -981,7 +972,7 @@ void set_message_with_feedback(FSTR_P const fstr) { LCD_MESSAGE(MSG_UBL_BC_INSERT2); } - const float z_step = 0.01f; // 0.01mm per encoder tick, occasionally step + const float z_step = 0.01f; // 0.01mm per encoder tick, occasionally step move_z_with_encoder(z_step); if (_click_and_hold([]{ @@ -1000,7 +991,7 @@ void set_message_with_feedback(FSTR_P const fstr) { SERIAL_FLUSH(); // Prevent host M105 buffer overrun. } while (location.valid()); - if (do_ubl_mesh_map) display_map(param.T_map_type); // show user where we're probing + if (do_ubl_mesh_map) display_map(param.T_map_type); // show user where we're probing restore_ubl_active_state_and_leave(); do_blocking_move_to_xy_z(pos, Z_CLEARANCE_DEPLOY_PROBE); @@ -1013,8 +1004,9 @@ void set_message_with_feedback(FSTR_P const fstr) { * NOTE: Blocks the G-code queue and captures Marlin UI during use. */ void unified_bed_leveling::fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) { - if (!parser.seen_test('R')) // fine_tune_mesh() is special. If no repetition count flag is specified - param.R_repetition = 1; // do exactly one mesh location. Otherwise use what the parser decided. + // fine_tune_mesh() is special. If no repetition count flag is specified, + // do exactly one mesh location, otherwise use what the parser decided. + if (!parser.seen_test('R')) param.R_repetition = 1; #if ENABLED(UBL_MESH_EDIT_MOVES_Z) const float h_offset = parser.seenval('H') ? parser.value_linear_units() : MANUAL_PROBE_START_Z; @@ -1034,30 +1026,30 @@ void set_message_with_feedback(FSTR_P const fstr) { save_ubl_active_state_and_disable(); LCD_MESSAGE(MSG_UBL_FINE_TUNE_MESH); - ui.capture(); // Take over control of the LCD encoder + ui.capture(); // Take over control of the LCD encoder - do_blocking_move_to_xy_z(pos, Z_TWEEN_SAFE_CLEARANCE); // Move to the given XY with probe clearance + do_blocking_move_to_xy_z(pos, Z_TWEEN_SAFE_CLEARANCE); // Move to the given XY with probe clearance MeshFlags done_flags{0}; const xy_int8_t &lpos = location.pos; #if IS_TFTGLCD_PANEL - ui.ubl_mesh_edit_start(0); // Change current screen before calling ui.ubl_plot + ui.ubl_mesh_edit_start(0); // Change current screen before calling ui.ubl_plot safe_delay(50); #endif do { location = find_closest_mesh_point_of_type(SET_IN_BITMAP, pos, false, &done_flags); - if (lpos.x < 0) break; // Stop when there are no more reachable points + if (lpos.x < 0) break; // Stop when there are no more reachable points - done_flags.mark(lpos); // Mark this location as 'adjusted' so a new - // location is used on the next loop + done_flags.mark(lpos); // Mark this location as 'adjusted' so a new + // location is used on the next loop const xyz_pos_t raw = { get_mesh_x(lpos.x), get_mesh_y(lpos.y), Z_TWEEN_SAFE_CLEARANCE }; - if (!position_is_reachable(raw)) break; // SHOULD NOT OCCUR (find_closest_mesh_point_of_type only returns reachable) + if (!position_is_reachable(raw)) break; // SHOULD NOT OCCUR (find_closest_mesh_point_of_type only returns reachable) - do_blocking_move_to(raw); // Move the nozzle to the edit point with probe clearance + do_blocking_move_to(raw); // Move the nozzle to the edit point with probe clearance TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset before editing @@ -1072,8 +1064,8 @@ void set_message_with_feedback(FSTR_P const fstr) { ui.refresh(); float new_z = z_values[lpos.x][lpos.y]; - if (isnan(new_z)) new_z = 0; // Invalid points begin at 0 - new_z = FLOOR(new_z * 1000) * 0.001f; // Chop off digits after the 1000ths place + if (isnan(new_z)) new_z = 0; // Invalid points begin at 0 + new_z = FLOOR(new_z * 1000) * 0.001f; // Chop off digits after the 1000ths place ui.ubl_mesh_edit_start(new_z); @@ -1083,12 +1075,12 @@ void set_message_with_feedback(FSTR_P const fstr) { idle_no_sleep(); new_z = ui.ubl_mesh_value(); TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited - SERIAL_FLUSH(); // Prevent host M105 buffer overrun. + SERIAL_FLUSH(); // Prevent host M105 buffer overrun. } while (!ui.button_pressed()); SET_SOFT_ENDSTOP_LOOSE(false); - if (!lcd_map_control) ui.return_to_status(); // Just editing a single point? Return to status + if (!lcd_map_control) ui.return_to_status(); // Just editing a single point? Return to status // Button held down? Abort editing if (_click_and_hold([]{ @@ -1099,13 +1091,13 @@ void set_message_with_feedback(FSTR_P const fstr) { // TODO: Disable leveling here so the Z value becomes the 'native' Z value. - z_values[lpos.x][lpos.y] = new_z; // Save the updated Z value + z_values[lpos.x][lpos.y] = new_z; // Save the updated Z value // TODO: Re-enable leveling here so Z is correctly based on the updated mesh. TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, new_z)); - serial_delay(20); // No switch noise + serial_delay(20); // No switch noise ui.refresh(); } while (lpos.x >= 0 && --param.R_repetition > 0); @@ -1283,11 +1275,10 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { mesh_index_pair farthest { -1, -1, -99999.99 }; GRID_LOOP(i, j) { - if (!isnan(z_values[i][j])) continue; // Skip valid mesh points + if (!isnan(z_values[i][j])) continue; // Skip valid mesh points // Skip unreachable points - if (!probe.can_reach(get_mesh_x(i), get_mesh_y(j))) - continue; + if (!probe.can_reach(get_mesh_x(i), get_mesh_y(j))) continue; found_a_NAN = true; @@ -1304,23 +1295,21 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { d1 = HYPOT(i - k, j - l) + (1.0f / ((millis() % 47) + 13)); - if (d1 < d2) { // Invalid mesh point (i,j) is closer to the defined point (k,l) + if (d1 < d2) { // Invalid mesh point (i,j) is closer to the defined point (k,l) d2 = d1; nearby.set(i, j); } } - // // At this point d2 should have the near defined mesh point to invalid mesh point (i,j) - // - if (found_a_real && nearby.x >= 0 && d2 > farthest.distance) { farthest.pos = nearby; // Found an invalid location farther from the defined mesh point farthest.distance = d2; } } // GRID_LOOP - if (!found_a_real && found_a_NAN) { // if the mesh is totally unpopulated, start the probing + // If the mesh is totally unpopulated, start the probing + if (!found_a_real && found_a_NAN) { farthest.pos.set((GRID_MAX_POINTS_X) / 2, (GRID_MAX_POINTS_Y) / 2); farthest.distance = 1; } @@ -1340,14 +1329,13 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { find_closest_t *d = (find_closest_t*)data; if ( d->type == CLOSEST || d->type == (isnan(bedlevel.z_values[i][j]) ? INVALID : REAL) || (d->type == SET_IN_BITMAP && !d->done_flags->marked(i, j)) - ) { - // Found a Mesh Point of the specified type! + ) { // Found a Mesh Point of the specified type! + /** + * If using the probe as the reference there are some unreachable locations. + * Also for round beds, there are grid points outside the bed the nozzle can't reach. + * Prune them from the list and ignore them till the next Phase (manual nozzle probing). + */ const xy_pos_t mpos = { bedlevel.get_mesh_x(i), bedlevel.get_mesh_y(j) }; - - // If using the probe as the reference there are some unreachable locations. - // Also for round beds, there are grid points outside the bed the nozzle can't reach. - // Prune them from the list and ignore them till the next Phase (manual nozzle probing). - if (!(d->probe_relative ? probe.can_reach(mpos) : position_is_reachable(mpos))) return false; d->closest.pos.set(i, j); @@ -1384,14 +1372,13 @@ mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const Mesh GRID_LOOP(i, j) { if ( type == CLOSEST || type == (isnan(z_values[i][j]) ? INVALID : REAL) || (type == SET_IN_BITMAP && !done_flags->marked(i, j)) - ) { - // Found a Mesh Point of the specified type! + ) { // Found a Mesh Point of the specified type! + /** + * If using the probe as the reference there are some unreachable locations. + * Also for round beds, there are grid points outside the bed the nozzle can't reach. + * Prune them from the list and ignore them till the next Phase (manual nozzle probing). + */ const xy_pos_t mpos = { get_mesh_x(i), get_mesh_y(j) }; - - // If using the probe as the reference there are some unreachable locations. - // Also for round beds, there are grid points outside the bed the nozzle can't reach. - // Prune them from the list and ignore them till the next Phase (manual nozzle probing). - if (!(probe_relative ? probe.can_reach(mpos) : position_is_reachable(mpos))) continue; @@ -1400,10 +1387,10 @@ mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const Mesh const xy_pos_t diff = current_position - mpos; const float distance = (ref - mpos).magnitude() + diff.magnitude() * 0.1f; - // factor in the distance from the current location for the normal case + // Factor in the distance from the current location for the normal case // so the nozzle isn't running all over the bed. - if (distance < best_so_far) { - best_so_far = distance; // Found a closer location with the desired value type. + if (distance < best_so_far) { // Found a closer location with the desired value type. + best_so_far = distance; closest.pos.set(i, j); closest.distance = best_so_far; } @@ -1420,7 +1407,6 @@ mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const Mesh * If an invalid location is found, use the next two points (if valid) to * calculate a 'reasonable' value for the unprobed mesh point. */ - bool unified_bed_leveling::smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir) { const float v = z_values[x][y]; if (isnan(v)) { // A NAN... @@ -1442,10 +1428,10 @@ typedef struct { uint8_t sx, ex, sy, ey; bool yfirst; } smart_fill_info; void unified_bed_leveling::smart_fill_mesh() { static const smart_fill_info - info0 PROGMEM = { 0, GRID_MAX_POINTS_X, 0, (GRID_MAX_POINTS_Y) - 2, false }, // Bottom of the mesh looking up - info1 PROGMEM = { 0, GRID_MAX_POINTS_X, (GRID_MAX_POINTS_Y) - 1, 0, false }, // Top of the mesh looking down - info2 PROGMEM = { 0, (GRID_MAX_POINTS_X) - 2, 0, GRID_MAX_POINTS_Y, true }, // Left side of the mesh looking right - info3 PROGMEM = { (GRID_MAX_POINTS_X) - 1, 0, 0, GRID_MAX_POINTS_Y, true }; // Right side of the mesh looking left + info0 PROGMEM = { 0, GRID_MAX_POINTS_X, 0, (GRID_MAX_POINTS_Y) - 2, false }, // Bottom of the mesh looking up + info1 PROGMEM = { 0, GRID_MAX_POINTS_X, (GRID_MAX_POINTS_Y) - 1, 0, false }, // Top of the mesh looking down + info2 PROGMEM = { 0, (GRID_MAX_POINTS_X) - 2, 0, GRID_MAX_POINTS_Y, true }, // Left side of the mesh looking right + info3 PROGMEM = { (GRID_MAX_POINTS_X) - 1, 0, 0, GRID_MAX_POINTS_Y, true }; // Right side of the mesh looking left static const smart_fill_info * const info[] PROGMEM = { &info0, &info1, &info2, &info3 }; for (uint8_t i = 0; i < COUNT(info); ++i) { @@ -1494,7 +1480,7 @@ void unified_bed_leveling::smart_fill_mesh() { #endif #if ENABLED(VALIDATE_MESH_TILT) - float gotz[3]; // Used for algorithm validation below + float gotz[3]; // Used for algorithm validation below #endif for (uint8_t i = 0; i < 3; ++i) { @@ -1674,12 +1660,12 @@ void unified_bed_leveling::smart_fill_mesh() { #if ENABLED(UBL_G29_P31) void unified_bed_leveling::smart_fill_wlsf(const_float_t weight_factor) { - - // For each undefined mesh point, compute a distance-weighted least squares fit - // from all the originally populated mesh points, weighted toward the point - // being extrapolated so that nearby points will have greater influence on - // the point being extrapolated. Then extrapolate the mesh point from WLSF. - + /** + * For each undefined mesh point, compute a distance-weighted least squares fit + * from all the originally populated mesh points, weighted toward the point + * being extrapolated so that nearby points will have greater influence on + * the point being extrapolated. Then extrapolate the mesh point from WLSF. + */ static_assert((GRID_MAX_POINTS_Y) <= 16, "GRID_MAX_POINTS_Y too big"); uint16_t bitmap[GRID_MAX_POINTS_X] = { 0 }; struct linear_fit_data lsf_results; @@ -1696,7 +1682,7 @@ void unified_bed_leveling::smart_fill_mesh() { for (uint8_t iy = 0; iy < GRID_MAX_POINTS_Y; ++iy) { ppos.y = get_mesh_y(iy); if (isnan(z_values[ix][iy])) { - // undefined mesh point at (ppos.x,ppos.y), compute weighted LSF from original valid mesh points. + // Undefined mesh point at (ppos.x,ppos.y), compute weighted LSF from original valid mesh points. incremental_LSF_reset(&lsf_results); xy_pos_t rpos; for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; ++jx) { From 51b786fc8800fc58a100875a881143b4c5556874 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 21 Feb 2024 23:09:44 -0500 Subject: [PATCH 095/109] captialize letter --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 2dad10d4e164..6127a5aa46d5 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -782,7 +782,7 @@ void unified_bed_leveling::shift_mesh_height() { ? find_furthest_invalid_mesh_point() : find_closest_mesh_point_of_type(INVALID, nearby, true); - if (best.pos.x >= 0) { // mesh point found and is reachable by probe + if (best.pos.x >= 0) { // Mesh point found and is reachable by probe TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::G29_POINT_START)); const float measured_z = probe.probe_at_point(best.meshpos(), stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); z_values[best.pos.x][best.pos.y] = isnan(measured_z) ? HUGE_VALF : measured_z; // Mark invalid point already probed with HUGE_VALF to omit it in the next loop From a2d7fe969c29e4757ae87eaf79a0e5dd76f4846d Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 22 Feb 2024 00:07:17 -0500 Subject: [PATCH 096/109] update comments+spacing, ubl files --- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 31 ++-- Marlin/src/feature/bedlevel/ubl/ubl.h | 39 +++-- .../src/feature/bedlevel/ubl/ubl_motion.cpp | 156 +++++++++--------- 3 files changed, 115 insertions(+), 111 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 0228bd247ebd..b882a3730f42 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -181,10 +181,11 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { } else SERIAL_ECHOPGM(" for ", csv ? F("CSV:\n") : F("LCD:\n")); - - // Add XY probe offset from extruder because probe.probe_at_point() subtracts them when - // moving to the XY position to be measured. This ensures better agreement between - // the current Z position after G28 and the mesh values. + /** + * Add XY probe offset from extruder because probe.probe_at_point() subtracts them when + * moving to the XY position to be measured. This ensures better agreement between + * the current Z position after G28 and the mesh values. + */ const xy_int8_t curr = closest_indexes(xy_pos_t(current_position) + probe.offset_xy); if (!lcd) SERIAL_EOL(); @@ -212,8 +213,8 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { else if (isnan(f)) SERIAL_ECHO(human ? F(" . ") : F("NAN")); else if (human || csv) { - if (human && f >= 0) SERIAL_CHAR(f > 0 ? '+' : ' '); // Display sign also for positive numbers (' ' for 0) - SERIAL_ECHO(p_float_t(f, 3)); // Positive: 5 digits, Negative: 6 digits + if (human && f >= 0) SERIAL_CHAR(f > 0 ? '+' : ' '); // Display sign also for positive numbers (' ' for 0) + SERIAL_ECHO(p_float_t(f, 3)); // Positive: 5 digits, Negative: 6 digits } if (csv && i < (GRID_MAX_POINTS_X) - 1) SERIAL_CHAR('\t'); @@ -271,17 +272,17 @@ bool unified_bed_leveling::sanity_check() { #endif #if HAS_HEATED_BED - if (parser.seenval('B')) { // Handle B# parameter to set Bed temp - const celsius_t bed_temp = parser.value_int(); // Marlin never sends itself F or K, always C + if (parser.seenval('B')) { // Handle B# parameter to set Bed temp + const celsius_t bed_temp = parser.value_int(); // Marlin never sends itself F or K, always C thermalManager.setTargetBed(bed_temp); thermalManager.wait_for_bed(false); } #endif - process_subcommands_now(FPSTR(G28_STR)); // Home - process_subcommands_now(F(ALIGN_GCODE // Align multi z axis if available - PROBE_GCODE "\n" // Build mesh with available hardware - "G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice + process_subcommands_now(FPSTR(G28_STR)); // Home + process_subcommands_now(F(ALIGN_GCODE // Align multi z axis if available + PROBE_GCODE "\n" // Build mesh with available hardware + "G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice if (parser.seenval('S')) { char umw_gcode[32]; @@ -289,9 +290,9 @@ bool unified_bed_leveling::sanity_check() { queue.inject(umw_gcode); } - process_subcommands_now(F("G29A\nG29F10\n" // Set UBL Active & Fade 10 - "M140S0\nM104S0\n" // Turn off heaters - "M500")); // Store settings + process_subcommands_now(F("G29A\nG29F10\n" // Set UBL Active & Fade 10 + "M140S0\nM104S0\n" // Turn off heaters + "M500")); // Store settings } #endif // UBL_MESH_WIZARD diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 7377f7dfc03a..1701f35849c7 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -217,14 +217,15 @@ class unified_bed_leveling { const float xratio = (rx0 - get_mesh_x(x1_i)) * RECIPROCAL(MESH_X_DIST), z1 = z_values[x1_i][yi]; - return z1 + xratio * (z_values[_MIN(x1_i, (GRID_MAX_POINTS_X) - 2) + 1][yi] - z1); // Don't allow x1_i+1 to be past the end of the array - // If it is, it is clamped to the last element of the - // z_values[][] array and no correction is applied. + return z1 + xratio * (z_values[_MIN(x1_i, (GRID_MAX_POINTS_X) - 2) + 1][yi] - z1); + /** + * Don't allow x1_i+1 to be past the end of the array + * If it is, it is clamped to the last element of the + * z_values[][] array and no correction is applied. + */ } - // // See comments above for z_correction_for_x_on_horizontal_mesh_line - // static float z_correction_for_y_on_vertical_mesh_line(const_float_t ry0, const int xi, const int y1_i) { if (!WITHIN(xi, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(y1_i, 0, (GRID_MAX_POINTS_Y) - 1)) { @@ -240,9 +241,12 @@ class unified_bed_leveling { const float yratio = (ry0 - get_mesh_y(y1_i)) * RECIPROCAL(MESH_Y_DIST), z1 = z_values[xi][y1_i]; - return z1 + yratio * (z_values[xi][_MIN(y1_i, (GRID_MAX_POINTS_Y) - 2) + 1] - z1); // Don't allow y1_i+1 to be past the end of the array - // If it is, it is clamped to the last element of the - // z_values[][] array and no correction is applied. + return z1 + yratio * (z_values[xi][_MIN(y1_i, (GRID_MAX_POINTS_Y) - 2) + 1] - z1); + /** + * Don't allow y1_i+1 to be past the end of the array + * If it is, it is clamped to the last element of the + * z_values[][] array and no correction is applied. + */ } /** @@ -252,10 +256,10 @@ class unified_bed_leveling { * on the Y position within the cell. */ static float get_z_correction(const_float_t rx0, const_float_t ry0) { - const int8_t cx = cell_index_x(rx0), cy = cell_index_y(ry0); // return values are clamped + const int8_t cx = cell_index_x(rx0), cy = cell_index_y(ry0); // Return values are clamped /** - * Check if the requested location is off the mesh. If so, and + * Check if the requested location is off the mesh. If so, and * UBL_Z_RAISE_WHEN_OFF_MESH is specified, that value is returned. */ #ifdef UBL_Z_RAISE_WHEN_OFF_MESH @@ -269,12 +273,15 @@ class unified_bed_leveling { z2 = calc_z0(rx0, x0, z_values[cx][my], x1, z_values[mx][my]); float z0 = calc_z0(ry0, get_mesh_y(cy), z1, get_mesh_y(cy + 1), z2); - if (isnan(z0)) { // If part of the Mesh is undefined, it will show up as NAN - z0 = 0.0; // in z_values[][] and propagate through the calculations. - // If our correction is NAN, we throw it out because part of - // the Mesh is undefined and we don't have the information - // needed to complete the height correction. - + if (isnan(z0)) { + /** + * If part of the Mesh is undefined, it will show up as NAN + * in z_values[][] and propagate through the calculations. + * If our correction is NAN, we throw it out because part of + * the Mesh is undefined and we don't have the information + * needed to complete the height correction. + */ + z0 = 0.0; if (DEBUGGING(MESH_ADJUST)) DEBUG_ECHOLNPGM("??? Yikes! NAN in "); } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 053a68b77d78..ea4ebeef043f 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -40,12 +40,13 @@ #include "../../../core/debug_out.h" #if !UBL_SEGMENTED - - // TODO: The first and last parts of a move might result in very short segment(s) - // after getting split on the cell boundary, so moves like that should not - // get split. This will be most common for moves that start/end near the - // corners of cells. To fix the issue, simply check if the start/end of the line - // is very close to a cell boundary in advance and don't split the line there. + /** + * TODO: The first and last parts of a move might result in very short segment(s) + * after getting split on the cell boundary, so moves like that should not + * get split. This will be most common for moves that start/end near the + * corners of cells. To fix the issue, simply check if the start/end of the line + * is very close to a cell boundary in advance and don't split the line there. + */ void unified_bed_leveling::line_to_destination_cartesian(const_feedRate_t scaled_fr_mm_s, const uint8_t extruder) { /** @@ -72,11 +73,11 @@ #ifdef UBL_Z_RAISE_WHEN_OFF_MESH // For a move off the UBL mesh, use a constant Z raise if (!cell_index_x_valid(end.x) || !cell_index_y_valid(end.y)) { - - // Note: There is no Z Correction in this case. We are off the mesh and don't know what - // a reasonable correction would be, UBL_Z_RAISE_WHEN_OFF_MESH will be used instead of - // a calculated (Bi-Linear interpolation) correction. - + /** + * NOTE: There is no Z Correction in this case. We are off the mesh and don't know what + * a reasonable correction would be, UBL_Z_RAISE_WHEN_OFF_MESH will be used instead of + * a calculated (Bi-Linear interpolation) correction. + */ end.z += UBL_Z_RAISE_WHEN_OFF_MESH; planner.buffer_segment(end, scaled_fr_mm_s, extruder); current_position = destination; @@ -105,7 +106,6 @@ * Past this point the move is known to cross one or more mesh lines. Check for the most common * case - crossing only one X or Y line - after details are worked out to reduce computation. */ - const xy_float_t dist = end - start; const xy_bool_t neg { dist.x < 0, dist.y < 0 }; const xy_uint8_t ineg { uint8_t(neg.x), uint8_t(neg.y) }; @@ -119,7 +119,6 @@ * Also select a scaling factor based on the larger of the X and Y * components. The larger of the two is used to preserve precision. */ - const xy_float_t ad = sign * dist; const bool use_x_dist = ad.x > ad.y; @@ -133,7 +132,7 @@ xy_uint8_t icell = istart; - const float ratio = dist.y / dist.x, // Allow divide by zero + const float ratio = dist.y / dist.x, // Allow divide by zero c = start.y - ratio * start.x; const bool inf_ratio_flag = isinf(ratio); @@ -144,8 +143,8 @@ * Handle vertical lines that stay within one column. * These need not be perfectly vertical. */ - if (iadd.x == 0) { // Vertical line? - icell.y += ineg.y; // Line going down? Just go to the bottom. + if (iadd.x == 0) { // Vertical line? + icell.y += ineg.y; // Line going down? Just go to the bottom. while (icell.y != iend.y + ineg.y) { icell.y += iadd.y; const float next_mesh_line_y = get_mesh_y(icell.y); @@ -172,7 +171,7 @@ * it might be fine to remove this check and let planner.buffer_segment() filter it out. */ if (dest.y != start.y) { - if (!inf_normalized_flag) { // fall-through faster than branch + if (!inf_normalized_flag) { // Fall-through faster than branch on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); dest.z = start.z + on_axis_distance * z_normalized_dist; @@ -202,13 +201,13 @@ * Handle horizontal lines that stay within one row. * These need not be perfectly horizontal. */ - if (iadd.y == 0) { // Horizontal line? - icell.x += ineg.x; // Heading left? Just go to the left edge of the cell for the first move. + if (iadd.y == 0) { // Horizontal line? + icell.x += ineg.x; // Heading left? Just go to the left edge of the cell for the first move. while (icell.x != iend.x + ineg.x) { icell.x += iadd.x; dest.x = get_mesh_x(icell.x); - dest.y = ratio * dest.x + c; // Calculate Y at the next X mesh line + dest.y = ratio * dest.x + c; // Calculate Y at the next X mesh line float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x, icell.y) * planner.fade_scaling_factor_for_z(end.z); @@ -251,7 +250,6 @@ /** * Generic case of a line crossing both X and Y Mesh lines. */ - xy_uint8_t cnt = istart.diff(iend); icell += ineg; @@ -261,14 +259,14 @@ const float next_mesh_line_x = get_mesh_x(icell.x + iadd.x), next_mesh_line_y = get_mesh_y(icell.y + iadd.y); - dest.y = ratio * next_mesh_line_x + c; // Calculate Y at the next X mesh line - dest.x = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line - // (No need to worry about ratio == 0. - // In that case, it was already detected - // as a vertical line move above.) + dest.y = ratio * next_mesh_line_x + c; // Calculate Y at the next X mesh line + dest.x = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line + // (No need to worry about ratio == 0. + // In that case, it was already detected + // as a vertical line move above.) if (neg.x == (dest.x > next_mesh_line_x)) { // Check if we hit the Y line first - // Yes! Crossing a Y Mesh Line next + // Yes! Crossing a Y Mesh Line next float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x - ineg.x, icell.y + iadd.y) * planner.fade_scaling_factor_for_z(end.z); @@ -295,7 +293,7 @@ cnt.y--; } else { - // Yes! Crossing a X Mesh Line next + // Yes! Crossing a X Mesh Line next float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x + iadd.x, icell.y - ineg.y) * planner.fade_scaling_factor_for_z(end.z); @@ -350,11 +348,10 @@ * This calls planner.buffer_segment multiple times for small incremental moves. * Returns true if did NOT move, false if moved (requires current_position update). */ - bool __O2 unified_bed_leveling::line_to_destination_segmented(const_feedRate_t scaled_fr_mm_s) { - if (!position_is_reachable(destination)) // fail if moving outside reachable boundary - return true; // did not move, so current_position still accurate + if (!position_is_reachable(destination)) // Fail if moving outside reachable boundary + return true; // did not move, so current_position still accurate const xyze_pos_t total = destination - current_position; @@ -380,10 +377,10 @@ #endif xyze_float_t diff = total * inv_segments; - - // Note that E segment distance could vary slightly as z mesh height - // changes for each segment, but small enough to ignore. - + /** + * NOTE: E segment distance could vary slightly as z mesh height + * changes for each segment, but small enough to ignore. + */ xyze_pos_t raw = current_position; // Just do plain segmentation if UBL is inactive or the target is above the fade height @@ -395,7 +392,6 @@ planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, hints); return false; // Did not set current from destination } - // Otherwise perform per-segment leveling #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) @@ -405,15 +401,16 @@ // Move to first segment destination raw += diff; - for (;;) { // for each mesh cell encountered during the move - - // Compute mesh cell invariants that remain constant for all segments within cell. - // Note for cell index, if point is outside the mesh grid (in MESH_INSET perimeter) - // the bilinear interpolation from the adjacent cell within the mesh will still work. - // Inner loop will exit each time (because out of cell bounds) but will come back - // in top of loop and again re-find same adjacent cell and use it, just less efficient - // for mesh inset area. + for (;;) { // For each mesh cell encountered during the move + /** + * Compute mesh cell invariants that remain constant for all segments within cell. + * Note for cell index, if point is outside the mesh grid (in MESH_INSET perimeter) + * the bilinear interpolation from the adjacent cell within the mesh will still work. + * Inner loop will exit each time (because out of cell bounds) but will come back + * in top of loop and again re-find same adjacent cell and use it, just less efficient + * for mesh inset area. + */ xy_int8_t icell = { int8_t((raw.x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST)), int8_t((raw.y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST)) @@ -423,68 +420,67 @@ const int8_t ncellx = _MIN(icell.x+1, GRID_MAX_CELLS_X), ncelly = _MIN(icell.y+1, GRID_MAX_CELLS_Y); - float z_x0y0 = z_values[icell.x][icell.y], // z at lower left corner - z_x1y0 = z_values[ncellx ][icell.y], // z at upper left corner - z_x0y1 = z_values[icell.x][ncelly ], // z at lower right corner - z_x1y1 = z_values[ncellx ][ncelly ]; // z at upper right corner + float z_x0y0 = z_values[icell.x][icell.y], // Z at lower left corner + z_x1y0 = z_values[ncellx ][icell.y], // Z at upper left corner + z_x0y1 = z_values[icell.x][ncelly ], // Z at lower right corner + z_x1y1 = z_values[ncellx ][ncelly ]; // Z at upper right corner - if (isnan(z_x0y0)) z_x0y0 = 0; // ideally activating planner.leveling_active (G29 A) - if (isnan(z_x1y0)) z_x1y0 = 0; // should refuse if any invalid mesh points - if (isnan(z_x0y1)) z_x0y1 = 0; // in order to avoid isnan tests per cell, - if (isnan(z_x1y1)) z_x1y1 = 0; // thus guessing zero for undefined points + if (isnan(z_x0y0)) z_x0y0 = 0; // Ideally activating planner.leveling_active (G29 A) + if (isnan(z_x1y0)) z_x1y0 = 0; // should refuse if any invalid mesh points + if (isnan(z_x0y1)) z_x0y1 = 0; // in order to avoid isnan tests per cell, + if (isnan(z_x1y1)) z_x1y1 = 0; // thus guessing zero for undefined points const xy_pos_t pos = { get_mesh_x(icell.x), get_mesh_y(icell.y) }; xy_pos_t cell = raw - pos; - const float z_xmy0 = (z_x1y0 - z_x0y0) * RECIPROCAL(MESH_X_DIST), // z slope per x along y0 (lower left to lower right) - z_xmy1 = (z_x1y1 - z_x0y1) * RECIPROCAL(MESH_X_DIST); // z slope per x along y1 (upper left to upper right) - - float z_cxy0 = z_x0y0 + z_xmy0 * cell.x; // z height along y0 at cell.x (changes for each cell.x in cell) + const float z_xmy0 = (z_x1y0 - z_x0y0) * RECIPROCAL(MESH_X_DIST), // Z slope per x along y0 (lower left to lower right) + z_xmy1 = (z_x1y1 - z_x0y1) * RECIPROCAL(MESH_X_DIST); // Z slope per x along y1 (upper left to upper right) - const float z_cxy1 = z_x0y1 + z_xmy1 * cell.x, // z height along y1 at cell.x - z_cxyd = z_cxy1 - z_cxy0; // z height difference along cell.x from y0 to y1 + float z_cxy0 = z_x0y0 + z_xmy0 * cell.x; // Z height along y0 at cell.x (changes for each cell.x in cell) - float z_cxym = z_cxyd * RECIPROCAL(MESH_Y_DIST); // z slope per y along cell.x from pos.y to y1 (changes for each cell.x in cell) + const float z_cxy1 = z_x0y1 + z_xmy1 * cell.x, // Z height along y1 at cell.x + z_cxyd = z_cxy1 - z_cxy0; // Z height difference along cell.x from y0 to y1 - // float z_cxcy = z_cxy0 + z_cxym * cell.y; // interpolated mesh z height along cell.x at cell.y (do inside the segment loop) + float z_cxym = z_cxyd * RECIPROCAL(MESH_Y_DIST); // Z slope per Y along cell.x from pos.y to y1 (changes for each cell.x in cell) - // As subsequent segments step through this cell, the z_cxy0 intercept will change - // and the z_cxym slope will change, both as a function of cell.x within the cell, and - // each change by a constant for fixed segment lengths. + /** + * As subsequent segments step through this cell, the z_cxy0 intercept will change + * and the z_cxym slope will change, both as a function of cell.x within the cell, and + * each change by a constant for fixed segment lengths. + */ + const float z_sxy0 = z_xmy0 * diff.x, // Per-segment adjustment to z_cxy0 + z_sxym = (z_xmy1 - z_xmy0) * RECIPROCAL(MESH_Y_DIST) * diff.x; // Per-segment adjustment to z_cxym - const float z_sxy0 = z_xmy0 * diff.x, // per-segment adjustment to z_cxy0 - z_sxym = (z_xmy1 - z_xmy0) * RECIPROCAL(MESH_Y_DIST) * diff.x; // per-segment adjustment to z_cxym + for (;;) { // For all segments within this mesh cell - for (;;) { // for all segments within this mesh cell + if (--segments == 0) raw = destination; // If this is last segment, use destination for exact - if (--segments == 0) raw = destination; // if this is last segment, use destination for exact + const float z_cxcy = (z_cxy0 + z_cxym * cell.y) // Interpolated mesh Z height along cell.x at cell.y + TERN_(ENABLE_LEVELING_FADE_HEIGHT, * fade_scaling_factor); // Apply fade factor to interpolated height - const float z_cxcy = (z_cxy0 + z_cxym * cell.y) // interpolated mesh z height along cell.x at cell.y - TERN_(ENABLE_LEVELING_FADE_HEIGHT, * fade_scaling_factor); // apply fade factor to interpolated height - - const float oldz = raw.z; raw.z += z_cxcy; + const float oldz = raw.z; + raw.z += z_cxcy; planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, hints); raw.z = oldz; - if (segments == 0) // done with last segment - return false; // didn't set current from destination + if (segments == 0) // Done with last segment + return false; // Didn't set current from destination raw += diff; cell += diff; - if (!WITHIN(cell.x, 0, MESH_X_DIST) || !WITHIN(cell.y, 0, MESH_Y_DIST)) // done within this cell, break to next + if (!WITHIN(cell.x, 0, MESH_X_DIST) || !WITHIN(cell.y, 0, MESH_Y_DIST)) // Done within this cell, break to next break; // Next segment still within same mesh cell, adjust the per-segment // slope and intercept to compute next z height. + z_cxy0 += z_sxy0; // Adjust z_cxy0 by per-segment z_sxy0 + z_cxym += z_sxym; // Adjust z_cxym by per-segment z_sxym - z_cxy0 += z_sxy0; // adjust z_cxy0 by per-segment z_sxy0 - z_cxym += z_sxym; // adjust z_cxym by per-segment z_sxym - - } // segment loop - } // cell loop + } // Segment loop + } // Cell loop - return false; // caller will update current_position + return false; // Caller will update current_position } #endif // UBL_SEGMENTED From 0a006e07cb37f7baecb07ca90ac9259593864f84 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 22 Feb 2024 15:27:00 -0500 Subject: [PATCH 097/109] update ubl_G29 --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 6127a5aa46d5..291a27b4ede7 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1383,7 +1383,6 @@ mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const Mesh continue; // Reachable. Check if it's the best_so_far location to the nozzle. - const xy_pos_t diff = current_position - mpos; const float distance = (ref - mpos).magnitude() + diff.magnitude() * 0.1f; From 37f3c36883e0d5db9d1c6b2eee2e1826f1214fa8 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Thu, 22 Feb 2024 15:47:08 -0500 Subject: [PATCH 098/109] update ubl_G29 --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 344 ++++++++++---------- 1 file changed, 171 insertions(+), 173 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 291a27b4ede7..806187d33e89 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -71,226 +71,226 @@ #define BIG_RAISE_NOT_NEEDED 0 /** - * G29: Unified Bed Leveling by Roxy + * G29: Unified Bed Leveling by Roxy * - * Parameters understood by this leveling system: + * Parameters understood by this leveling system: * - * A Activate Activate the Unified Bed Leveling system. + * A Activate Activate the Unified Bed Leveling system. * - * B # Business Use the 'Business Card' mode of the Manual Probe subsystem with P2. - * Note: A non-compressible Spark Gap feeler gauge is recommended over a business card. - * In this mode of G29 P2, a business or index card is used as a shim that the nozzle can - * grab onto as it is lowered. In principle, the nozzle-bed distance is the same when the - * same resistance is felt in the shim. You can omit the numerical value on first invocation - * of G29 P2 B to measure shim thickness. Subsequent use of 'B' will apply the previously- - * measured thickness by default. + * B # Business Use the 'Business Card' mode of the Manual Probe subsystem with P2. + * Note: A non-compressible Spark Gap feeler gauge is recommended over a business card. + * In this mode of G29 P2, a business or index card is used as a shim that the nozzle can + * grab onto as it is lowered. In principle, the nozzle-bed distance is the same when the + * same resistance is felt in the shim. You can omit the numerical value on first invocation + * of G29 P2 B to measure shim thickness. Subsequent use of 'B' will apply the previously- + * measured thickness by default. * - * C Continue G29 P1 C continues the generation of a partially-constructed Mesh without invalidating - * previous measurements. + * C Continue G29 P1 C continues the generation of a partially-constructed Mesh without invalidating + * previous measurements. * - * C G29 P2 C tells the Manual Probe subsystem to not use the current nozzle - * location in its search for the closest unmeasured Mesh Point. Instead, attempt to - * start at one end of the uprobed points and Continue sequentially. + * C G29 P2 C tells the Manual Probe subsystem to not use the current nozzle + * location in its search for the closest unmeasured Mesh Point. Instead, attempt to + * start at one end of the uprobed points and Continue sequentially. * - * G29 P3 C specifies the Constant for the fill. Otherwise, uses a "reasonable" value. + * G29 P3 C specifies the Constant for the fill. Otherwise, uses a "reasonable" value. * - * C Current G29 Z C uses the Current location (instead of bed center or nearest edge). + * C Current G29 Z C uses the Current location (instead of bed center or nearest edge). * - * D Disable Disable the Unified Bed Leveling system. + * D Disable Disable the Unified Bed Leveling system. * - * E Stow_probe Stow the probe after each sampled point. + * E Stow_probe Stow the probe after each sampled point. * - * F # Fade Fade the amount of Mesh Based Compensation over a specified height. At the - * specified height, no correction is applied and natural printer kenimatics take over. If no - * number is specified for the command, 10mm is assumed to be reasonable. + * F # Fade Fade the amount of Mesh Based Compensation over a specified height. At the + * specified height, no correction is applied and natural printer kenimatics take over. If no + * number is specified for the command, 10mm is assumed to be reasonable. * - * H # Height With P2, 'H' specifies the Height to raise the nozzle after each manual probe of the bed. - * If omitted, the nozzle will raise by Z_CLEARANCE_BETWEEN_PROBES. + * H # Height With P2, 'H' specifies the Height to raise the nozzle after each manual probe of the bed. + * If omitted, the nozzle will raise by Z_CLEARANCE_BETWEEN_PROBES. * - * H # Offset With P4, 'H' specifies the Offset above the mesh height to place the nozzle. - * If omitted, Z_TWEEN_SAFE_CLEARANCE will be used. + * H # Offset With P4, 'H' specifies the Offset above the mesh height to place the nozzle. + * If omitted, Z_TWEEN_SAFE_CLEARANCE will be used. * - * I # Invalidate Invalidate the specified number of Mesh Points near the given 'X' 'Y'. If X or Y are omitted, - * the nozzle location is used. If no 'I' value is given, only the point nearest to the location - * is invalidated. Use 'T' to produce a map afterward. This command is useful to invalidate a - * portion of the Mesh so it can be adjusted using other UBL tools. When attempting to invalidate - * an isolated bad mesh point, the 'T' option shows the nozzle position in the Mesh with (#). You - * can move the nozzle around and use this feature to select the center of the area (or cell) to - * invalidate. + * I # Invalidate Invalidate the specified number of Mesh Points near the given 'X' 'Y'. If X or Y are omitted, + * the nozzle location is used. If no 'I' value is given, only the point nearest to the location + * is invalidated. Use 'T' to produce a map afterward. This command is useful to invalidate a + * portion of the Mesh so it can be adjusted using other UBL tools. When attempting to invalidate + * an isolated bad mesh point, the 'T' option shows the nozzle position in the Mesh with (#). You + * can move the nozzle around and use this feature to select the center of the area (or cell) to + * invalidate. * - * J # Grid Perform a Grid Based Leveling of the current Mesh using a grid with n points on a side. - * Not specifying a grid size will invoke the 3-Point leveling function. + * J # Grid Perform a Grid Based Leveling of the current Mesh using a grid with n points on a side. + * Not specifying a grid size will invoke the 3-Point leveling function. * - * L Load Load Mesh from the previously activated location in the EEPROM. + * L Load Load Mesh from the previously activated location in the EEPROM. * - * L # Load Load Mesh from the specified location in the EEPROM. Set this location as activated - * for subsequent Load and Store operations. + * L # Load Load Mesh from the specified location in the EEPROM. Set this location as activated + * for subsequent Load and Store operations. * - * NOTE: The P or Phase commands are used for the bulk of the work to setup a Mesh. In general, your Mesh - * will start off being initialized with a G29 P0 or a G29 P1. Further refinement of the Mesh happens - * with each additional Phase that processes it. + * NOTE: The P or Phase commands are used for the bulk of the work to setup a Mesh. In general, your Mesh + * will start off being initialized with a G29 P0 or a G29 P1. Further refinement of the Mesh happens + * with each additional Phase that processes it. * - * P0 Phase 0 Zero Mesh Data and turn off the Mesh Compensation System. This reverts the - * 3D Printer to the same state it was in before the Unified Bed Leveling Compensation - * was turned on. Setting the entire Mesh to Zero is a special case that allows - * a subsequent G or T leveling operation for backward compatibility. + * P0 Phase 0 Zero Mesh Data and turn off the Mesh Compensation System. This reverts the + * 3D Printer to the same state it was in before the Unified Bed Leveling Compensation + * was turned on. Setting the entire Mesh to Zero is a special case that allows + * a subsequent G or T leveling operation for backward compatibility. * - * P1 Phase 1 Invalidate entire Mesh and continue with automatic generation of the Mesh data using - * the Z-Probe. Usually the probe can't reach all areas that the nozzle can reach. For delta - * printers only the areas where the probe and nozzle can both reach will be automatically probed. + * P1 Phase 1 Invalidate entire Mesh and continue with automatic generation of the Mesh data using + * the Z-Probe. Usually the probe can't reach all areas that the nozzle can reach. For delta + * printers only the areas where the probe and nozzle can both reach will be automatically probed. * - * Unreachable points will be handled in Phase 2 and Phase 3. + * Unreachable points will be handled in Phase 2 and Phase 3. * - * Use 'C' to leave the previous mesh intact and automatically probe needed points. This allows you - * to invalidate parts of the Mesh but still use Automatic Probing. + * Use 'C' to leave the previous mesh intact and automatically probe needed points. This allows you + * to invalidate parts of the Mesh but still use Automatic Probing. * - * The 'X' and 'Y' parameters prioritize where to try and measure points. If omitted, the current - * probe position is used. + * The 'X' and 'Y' parameters prioritize where to try and measure points. If omitted, the current + * probe position is used. * - * Use 'T' (Topology) to generate a report of mesh generation. + * Use 'T' (Topology) to generate a report of mesh generation. * - * P1 will suspend Mesh generation if the controller button is held down. Note that you may need - * to press and hold the switch for several seconds if moves are underway. + * P1 will suspend Mesh generation if the controller button is held down. Note that you may need + * to press and hold the switch for several seconds if moves are underway. * - * P2 Phase 2 Probe unreachable points. + * P2 Phase 2 Probe unreachable points. * - * Use 'H' to set the height between Mesh points. If omitted, Z_CLEARANCE_BETWEEN_PROBES is used. - * Smaller values will be quicker. Move the nozzle down till it barely touches the bed. Make sure the - * nozzle is clean and unobstructed. Use caution and move slowly. This can damage your printer! - * (Uses SIZE_OF_LITTLE_RAISE mm if the nozzle is moving less than BIG_RAISE_NOT_NEEDED mm.) + * Use 'H' to set the height between Mesh points. If omitted, Z_CLEARANCE_BETWEEN_PROBES is used. + * Smaller values will be quicker. Move the nozzle down till it barely touches the bed. Make sure the + * nozzle is clean and unobstructed. Use caution and move slowly. This can damage your printer! + * (Uses SIZE_OF_LITTLE_RAISE mm if the nozzle is moving less than BIG_RAISE_NOT_NEEDED mm.) * - * The 'H' value can be negative if the Mesh dips in a large area. Press and hold the - * controller button to terminate the current Phase 2 command. You can then re-issue "G29 P 2" - * with an 'H' parameter more suitable for the area you're manually probing. Note that the command - * tries to start in a corner of the bed where movement will be predictable. Override the distance - * calculation location with the X and Y parameters. You can print a Mesh Map (G29 T) to see where - * the mesh is invalidated and where the nozzle needs to move to complete the command. Use 'C' to - * indicate that the search should be based on the current position. + * The 'H' value can be negative if the Mesh dips in a large area. Press and hold the + * controller button to terminate the current Phase 2 command. You can then re-issue "G29 P 2" + * with an 'H' parameter more suitable for the area you're manually probing. Note that the command + * tries to start in a corner of the bed where movement will be predictable. Override the distance + * calculation location with the X and Y parameters. You can print a Mesh Map (G29 T) to see where + * the mesh is invalidated and where the nozzle needs to move to complete the command. Use 'C' to + * indicate that the search should be based on the current position. * - * The 'B' parameter for this command is described above. It places the manual probe subsystem into - * Business Card mode where the thickness of a business card is measured and then used to accurately - * set the nozzle height in all manual probing for the duration of the command. A Business card can - * be used, but you'll get better results with a flexible Shim that doesn't compress. This makes it - * easier to produce similar amounts of force and get more accurate measurements. Google if you're - * not sure how to use a shim. + * The 'B' parameter for this command is described above. It places the manual probe subsystem into + * Business Card mode where the thickness of a business card is measured and then used to accurately + * set the nozzle height in all manual probing for the duration of the command. A Business card can + * be used, but you'll get better results with a flexible Shim that doesn't compress. This makes it + * easier to produce similar amounts of force and get more accurate measurements. Google if you're + * not sure how to use a shim. * - * The 'T' (Map) parameter helps track Mesh building progress. + * The 'T' (Map) parameter helps track Mesh building progress. * - * NOTE: P2 requires an LCD controller! + * NOTE: P2 requires an LCD controller! * - * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths to - * go down: + * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths to + * go down: * - * - If a 'C' constant is specified, the closest invalid mesh points to the nozzle will be filled, - * and a repeat count can then also be specified with 'R'. + * - If a 'C' constant is specified, the closest invalid mesh points to the nozzle will be filled, + * and a repeat count can then also be specified with 'R'. * - * - Leaving out 'C' invokes Smart Fill, which scans the mesh from the edges inward looking for - * invalid mesh points. Adjacent points are used to determine the bed slope. If the bed is sloped - * upward from the invalid point, it takes the value of the nearest point. If sloped downward, it's - * replaced by a value that puts all three points in a line. This version of G29 P3 is a quick, easy - * and (usually) safe way to populate unprobed mesh regions before continuing to G26 Mesh Validation - * Pattern. Note that this populates the mesh with unverified values. Pay attention and use caution. + * - Leaving out 'C' invokes Smart Fill, which scans the mesh from the edges inward looking for + * invalid mesh points. Adjacent points are used to determine the bed slope. If the bed is sloped + * upward from the invalid point, it takes the value of the nearest point. If sloped downward, it's + * replaced by a value that puts all three points in a line. This version of G29 P3 is a quick, easy + * and (usually) safe way to populate unprobed mesh regions before continuing to G26 Mesh Validation + * Pattern. Note that this populates the mesh with unverified values. Pay attention and use caution. * - * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assumes the existence of - * an LCD Panel. It is possible to fine tune the mesh without an LCD Panel using - * G42 and M421. See the UBL documentation for further details. + * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assumes the existence of + * an LCD Panel. It is possible to fine tune the mesh without an LCD Panel using + * G42 and M421. See the UBL documentation for further details. * - * Phase 4 is meant to be used with G26 Mesh Validation to fine tune the mesh by direct editing - * of Mesh Points. Raise and lower points to fine tune the mesh until it gives consistently reliable - * adhesion. + * Phase 4 is meant to be used with G26 Mesh Validation to fine tune the mesh by direct editing + * of Mesh Points. Raise and lower points to fine tune the mesh until it gives consistently reliable + * adhesion. * - * P4 moves to the closest Mesh Point (and/or the given X Y), raises the nozzle above the mesh height - * by the given 'H' offset (or default 0), and waits while the controller is used to adjust the nozzle - * height. On click the displayed height is saved in the mesh. + * P4 moves to the closest Mesh Point (and/or the given X Y), raises the nozzle above the mesh height + * by the given 'H' offset (or default 0), and waits while the controller is used to adjust the nozzle + * height. On click the displayed height is saved in the mesh. * - * Start Phase 4 at a specific location with X and Y. Adjust a specific number of Mesh Points with - * the 'R' (Repeat) parameter. (If 'R' is left out, the whole matrix is assumed.) This command can be - * terminated early (e.g., after editing the area of interest) by pressing and holding the encoder button. + * Start Phase 4 at a specific location with X and Y. Adjust a specific number of Mesh Points with + * the 'R' (Repeat) parameter. (If 'R' is left out, the whole matrix is assumed.) This command can be + * terminated early (e.g., after editing the area of interest) by pressing and holding the encoder button. * - * The general form is G29 P4 [R points] [X position] [Y position] + * The general form is G29 P4 [R points] [X position] [Y position] * - * The H [offset] parameter is useful if a shim is used to fine-tune the mesh. For a 0.4mm shim the - * command would be G29 P4 H0.4. The nozzle is moved to the shim height, you adjust height to the shim, - * and on click the height minus the shim thickness will be saved in the mesh. + * The H [offset] parameter is useful if a shim is used to fine-tune the mesh. For a 0.4mm shim the + * command would be G29 P4 H0.4. The nozzle is moved to the shim height, you adjust height to the shim, + * and on click the height minus the shim thickness will be saved in the mesh. * - * !!Use with caution, as a very poor mesh could cause the nozzle to crash into the bed!! + * !!Use with caution, as a very poor mesh could cause the nozzle to crash into the bed!! * - * NOTE: P4 is not available unless you have LCD support enabled! + * NOTE: P4 is not available unless you have LCD support enabled! * - * P5 Phase 5 Find Mean Mesh Height and Standard Deviation. Typically, it is easier to use and - * work with the Mesh if it is Mean Adjusted. You can specify a C parameter to - * Correct the Mesh to a 0.00 Mean Height. Adding a C parameter will automatically - * execute a G29 P6 C . + * P5 Phase 5 Find Mean Mesh Height and Standard Deviation. Typically, it is easier to use and + * work with the Mesh if it is Mean Adjusted. You can specify a C parameter to + * Correct the Mesh to a 0.00 Mean Height. Adding a C parameter will automatically + * execute a G29 P6 C . * - * P6 Phase 6 Shift Mesh height. The entire Mesh's height is adjusted by the height specified - * with the C parameter. Being able to adjust the height of a Mesh is useful tool. It - * can be used to compensate for poorly calibrated Z-Probes and other errors. Ideally, - * you should have the Mesh adjusted for a Mean Height of 0.00 and the Z-Probe measuring - * 0.000 at the Z Home location. + * P6 Phase 6 Shift Mesh height. The entire Mesh's height is adjusted by the height specified + * with the C parameter. Being able to adjust the height of a Mesh is useful tool. It + * can be used to compensate for poorly calibrated Z-Probes and other errors. Ideally, + * you should have the Mesh adjusted for a Mean Height of 0.00 and the Z-Probe measuring + * 0.000 at the Z Home location. * - * Q Test Load specified Test Pattern to assist in checking correct operation of system. This - * command is not anticipated to be of much value to the typical user. It is intended - * for developers to help them verify correct operation of the Unified Bed Leveling System. + * Q Test Load specified Test Pattern to assist in checking correct operation of system. This + * command is not anticipated to be of much value to the typical user. It is intended + * for developers to help them verify correct operation of the Unified Bed Leveling System. * - * R # Repeat Repeat this command the specified number of times. If no number is specified the - * command will be repeated GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y times. + * R # Repeat Repeat this command the specified number of times. If no number is specified the + * command will be repeated GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y times. * - * S Store Store the current Mesh in the Activated area of the EEPROM. It will also store the - * current state of the Unified Bed Leveling system in the EEPROM. + * S Store Store the current Mesh in the Activated area of the EEPROM. It will also store the + * current state of the Unified Bed Leveling system in the EEPROM. * - * S # Store Store the current Mesh at the specified location in EEPROM. Activate this location - * for subsequent Load and Store operations. Valid storage slot numbers begin at 0 and - * extend to a limit related to the available EEPROM storage. + * S # Store Store the current Mesh at the specified location in EEPROM. Activate this location + * for subsequent Load and Store operations. Valid storage slot numbers begin at 0 and + * extend to a limit related to the available EEPROM storage. * - * S -1 Store Print the current Mesh as G-code that can be used to restore the mesh anytime. + * S-1 Store Print the current Mesh as G-code that can be used to restore the mesh anytime. * - * T Topology Display the Mesh Map Topology. - * 'T' can be used alone (e.g., G29 T) or in combination with most of the other commands. - * This option works with all Phase commands (e.g., G29 P4 R 5 T X 50 Y100 C -.1 O) - * This parameter can also specify a Map Type. T0 (the default) is user-readable. T1 - * is suitable to paste into a spreadsheet for a 3D graph of the mesh. + * T Topology Display the Mesh Map Topology. + * 'T' can be used alone (e.g., G29 T) or in combination with most of the other commands. + * This option works with all Phase commands (e.g., G29 P4 R 5 T X 50 Y100 C -.1 O) + * This parameter can also specify a Map Type. T0 (the default) is user-readable. T1 + * is suitable to paste into a spreadsheet for a 3D graph of the mesh. * - * U Unlevel Perform a probe of the outer perimeter to assist in physically leveling unlevel beds. - * Only used for G29 P1 T U. This speeds up the probing of the edge of the bed. Useful - * when the entire bed doesn't need to be probed because it will be adjusted. + * U Unlevel Perform a probe of the outer perimeter to assist in physically leveling unlevel beds. + * Only used for G29 P1 T U. This speeds up the probing of the edge of the bed. Useful + * when the entire bed doesn't need to be probed because it will be adjusted. * - * V # Verbosity Set the verbosity level (0-4) for extra details. (Default 0) + * V # Verbosity Set the verbosity level (0-4) for extra details. (Default 0) * - * X # X Location for this command + * X # X Location for this command * - * Y # Y Location for this command + * Y # Y Location for this command * * With UBL_DEVEL_DEBUGGING: * - * K # Kompare Kompare current Mesh with stored Mesh #, replacing current Mesh with the result. - * This command literally performs a diff between two Meshes. + * K # Kompare Kompare current Mesh with stored Mesh #, replacing current Mesh with the result. + * This command literally performs a diff between two Meshes. * - * Q-1 Dump EEPROM Dump the UBL contents stored in EEPROM as HEX format. Useful for developers to help - * verify correct operation of the UBL. + * Q-1 Dump EEPROM Dump the UBL contents stored in EEPROM as HEX format. Useful for developers to help + * verify correct operation of the UBL. * - * W What? Display valuable UBL data. + * W What? Display valuable UBL data. * * - * Release Notes: - * You MUST do M502, M500 to initialize the storage. Failure to do this will cause all - * kinds of problems. Enabling EEPROM Storage is required. + * Release Notes: + * You MUST do M502, M500 to initialize the storage. Failure to do this will cause all + * kinds of problems. Enabling EEPROM Storage is required. * - * When you do a G28 and G29 P1 to automatically build your first mesh, you are going to notice that - * UBL probes points increasingly further from the starting location. (The starting location defaults - * to the center of the bed.) In contrast, ABL and MBL follow a zigzag pattern. The spiral pattern is - * especially better for Delta printers, since it populates the center of the mesh first, allowing for - * a quicker test print to verify settings. You don't need to populate the entire mesh to use it. - * After all, you don't want to spend a lot of time generating a mesh only to realize the resolution - * or probe offsets are incorrect. Mesh-generation gathers points starting closest to the nozzle unless - * an (X,Y) coordinate pair is given. + * When you do a G28 and G29 P1 to automatically build your first mesh, you are going to notice that + * UBL probes points increasingly further from the starting location. (The starting location defaults + * to the center of the bed.) In contrast, ABL and MBL follow a zigzag pattern. The spiral pattern is + * especially better for Delta printers, since it populates the center of the mesh first, allowing for + * a quicker test print to verify settings. You don't need to populate the entire mesh to use it. + * After all, you don't want to spend a lot of time generating a mesh only to realize the resolution + * or probe offsets are incorrect. Mesh-generation gathers points starting closest to the nozzle unless + * an (X,Y) coordinate pair is given. * - * Unified Bed Leveling uses a lot of EEPROM storage to hold its data, and it takes some effort to get - * the mesh just right. To prevent this valuable data from being destroyed as the EEPROM structure - * evolves, UBL stores all mesh data at the end of EEPROM. + * Unified Bed Leveling uses a lot of EEPROM storage to hold its data, and it takes some effort to get + * the mesh just right. To prevent this valuable data from being destroyed as the EEPROM structure + * evolves, UBL stores all mesh data at the end of EEPROM. * - * UBL is founded on Edward Patel's Mesh Bed Leveling code. A big 'Thanks!' to him and the creators of - * 3-Point and Grid Based leveling. Combining their contributions we now have the functionality and - * features of all three systems combined. + * UBL is founded on Edward Patel's Mesh Bed Leveling code. A big 'Thanks!' to him and the creators of + * 3-Point and Grid Based leveling. Combining their contributions we now have the functionality and + * features of all three systems combined. */ G29_parameters_t unified_bed_leveling::param; @@ -360,10 +360,10 @@ void unified_bed_leveling::G29() { if ((count & 0x0F) == 0x0F) idle(); const mesh_index_pair closest = find_closest_mesh_point_of_type(REAL, param.XY_pos); /** - * No more REAL mesh points to invalidate? Assume the user meant - * to invalidate the ENTIRE mesh, which can't be done with - * find_closest_mesh_point (which only returns REAL points). - */ + * No more REAL mesh points to invalidate? Assume the user meant + * to invalidate the ENTIRE mesh, which can't be done with + * find_closest_mesh_point (which only returns REAL points). + */ if (closest.pos.x < 0) { invalidate_all = true; break; } z_values[closest.pos.x][closest.pos.y] = NAN; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(closest.pos, 0.0f)); @@ -553,11 +553,11 @@ void unified_bed_leveling::G29() { #if ENABLED(UBL_G29_P31) case 1: { /** - * P3.1 use least squares fit to fill missing mesh values - * P3.10 zero weighting for distance, all grid points equal, best fit tilted plane - * P3.11 10X weighting for nearest grid points versus farthest grid points - * P3.12 100X distance weighting - * P3.13 1000X distance weighting, approaches simple average of nearest points + * P3.1 use least squares fit to fill missing mesh values + * P3.10 zero weighting for distance, all grid points equal, best fit tilted plane + * P3.11 10X weighting for nearest grid points versus farthest grid points + * P3.12 100X distance weighting + * P3.13 1000X distance weighting, approaches simple average of nearest points */ const float weight_power = (cvf - 3.10f) * 100.0f, // 3.12345 -> 2.345 weight_factor = weight_power ? POW(10.0f, weight_power) : 0; @@ -1118,9 +1118,7 @@ void set_message_with_feedback(FSTR_P const fstr) { #endif // HAS_MARLINUI_MENU -/** - * Parse and validate most G29 parameters, store for use by G29 functions. - */ +// Parse and validate most G29 parameters, store for use by G29 functions. bool unified_bed_leveling::G29_parse_parameters() { bool err_flag = false; @@ -1331,10 +1329,10 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { || (d->type == SET_IN_BITMAP && !d->done_flags->marked(i, j)) ) { // Found a Mesh Point of the specified type! /** - * If using the probe as the reference there are some unreachable locations. - * Also for round beds, there are grid points outside the bed the nozzle can't reach. - * Prune them from the list and ignore them till the next Phase (manual nozzle probing). - */ + * If using the probe as the reference there are some unreachable locations. + * Also for round beds, there are grid points outside the bed the nozzle can't reach. + * Prune them from the list and ignore them till the next Phase (manual nozzle probing). + */ const xy_pos_t mpos = { bedlevel.get_mesh_x(i), bedlevel.get_mesh_y(j) }; if (!(d->probe_relative ? probe.can_reach(mpos) : position_is_reachable(mpos))) return false; From 66cc5666088f49ac32e266f3b9eb4cf87213a028 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 13 Apr 2024 23:34:39 -0400 Subject: [PATCH 099/109] remove HAS_STATUS_MESSAGE w/HAS_DISPLAY, update DWIN, use ALL(...) --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 4 ++-- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 6 +++--- Marlin/src/lcd/e3v2/proui/dwin.cpp | 8 ++++---- Marlin/src/lcd/e3v2/proui/gcode_preview.cpp | 8 ++++---- Marlin/src/lcd/e3v2/proui/meshviewer.cpp | 2 +- Marlin/src/lcd/marlinui.cpp | 2 +- Marlin/src/lcd/marlinui.h | 2 +- 7 files changed, 16 insertions(+), 16 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index bc227e1ce562..054550b00d51 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1497,7 +1497,7 @@ void hmiMoveDone(const AxisEnum axis) { #endif // HAS_HEATED_BED -#if HAS_PREHEAT && HAS_FAN +#if ALL(HAS_PREHEAT, HAS_FAN) void hmiFanSpeed() { EncoderState encoder_diffState = encoderReceiveAnalyze(); @@ -4266,7 +4266,7 @@ void dwinHandleScreen() { #if HAS_HEATED_BED case ID_BedTemp: hmiBedTemp(); break; #endif - #if HAS_PREHEAT && HAS_FAN + #if ALL(HAS_PREHEAT, HAS_FAN) case ID_FanSpeed: hmiFanSpeed(); break; #endif case ID_PrintSpeed: hmiPrintSpeed(); break; diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 6e65bd62ac6a..2e7c37c55736 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -97,7 +97,7 @@ #define MAX_XY_OFFSET 100 -#if HAS_ZOFFSET_ITEM && HAS_BED_PROBE +#if ALL(HAS_ZOFFSET_ITEM, HAS_BED_PROBE) #define MAX_Z_OFFSET 20 #define MIN_Z_OFFSET -20 #else @@ -3970,7 +3970,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra } break; - #if HAS_PREHEAT && HAS_HOTEND + #if ALL(HAS_PREHEAT, HAS_HOTEND) case ID_PreheatHotend: @@ -4281,7 +4281,7 @@ uint8_t JyersDWIN::getMenuSize(const uint8_t menu) { #endif case ID_Tune: return TUNE_TOTAL; - #if HAS_PREHEAT && HAS_HOTEND + #if ALL(HAS_PREHEAT, HAS_HOTEND) case ID_PreheatHotend: return PREHEATHOTEND_TOTAL; #endif diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index c4dd28054fd5..26a5c57aff4d 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -69,7 +69,7 @@ #include "../../../feature/host_actions.h" #endif -#if HAS_MESH || (HAS_LEVELING && HAS_ZOFFSET_ITEM) +#if HAS_MESH || ALL(HAS_LEVELING, HAS_ZOFFSET_ITEM) #include "../../../feature/bedlevel/bedlevel.h" #include "bedlevel_tools.h" #endif @@ -2481,7 +2481,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, )); } - #endif + #endif // HAS_BED_PROBE #if HAS_TRAMMING_WIZARD @@ -2558,7 +2558,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, toggleCheckboxLine(hmiData.fullManualTramming); } - #endif // HAS_BED_PROBE && HAS_MESH && HAS_TRAMMING_WIZARD + #endif // HAS_TRAMMING_WIZARD #endif // LCD_BED_TRAMMING @@ -3128,7 +3128,7 @@ void drawPrepareMenu() { checkkey = ID_Menu; if (SET_MENU(trammingMenu, MSG_BED_TRAMMING, 8)) { BACK_ITEM(drawPrepareMenu); - #if HAS_BED_PROBE && HAS_MESH + #if ALL(HAS_BED_PROBE, HAS_MESH) MENU_ITEM(ICON_Tram, MSG_TRAMMING_WIZARD, onDrawMenuItem, trammingwizard); EDIT_ITEM(ICON_Version, MSG_BED_TRAMMING_MANUAL, onDrawChkbMenu, setManualTramming, &hmiData.fullManualTramming); #elif !HAS_BED_PROBE && HAS_ZOFFSET_ITEM diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp index a4b870eada4d..b205a4dcf00e 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -70,10 +70,10 @@ void fileprop_t::clear() { height = width = length = 0; } -void getValue(const char * const buf, const char * const key, float &value) { +void getValue(const char * const buf, PGM_P const key, float &value) { if (value != 0.0f) return; - const char * posptr = strstr_P(buf, key); + const char *posptr = strstr_P(buf, key); if (posptr == nullptr) return; char num[10] = ""; @@ -91,7 +91,7 @@ void getValue(const char * const buf, const char * const key, float &value) { bool Preview::hasPreview() { const char * const tbstart = PSTR("; thumbnail begin " STRINGIFY(THUMBWIDTH) "x" STRINGIFY(THUMBHEIGHT)); - const char * posptr = nullptr; + const char *posptr = nullptr; uint32_t indx = 0; float tmp = 0; @@ -176,7 +176,7 @@ bool Preview::hasPreview() { void Preview::drawFromSD() { hasPreview(); - MString<45> buf; + TString buf; dwinDrawRectangle(1, hmiData.colorBackground, 0, 0, DWIN_WIDTH, STATUS_Y - 1); if (fileprop.time) { buf.setf(F("Estimated time: %i:%02i"), (uint16_t)fileprop.time / 3600, ((uint16_t)fileprop.time % 3600) / 60); diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp index 9a0ea86c878d..1c5f08bb4dfa 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp @@ -87,7 +87,7 @@ void MeshViewer::drawMeshPoint(const uint8_t x, const uint8_t y, const float z) else DWINUI::drawSignedFloat(meshfont, 1, 2, px(x) - 3 * fs, fy, z); } else { - char msg[9] = ""; + char msg[9]; msg[0] = '\0'; switch (v) { case -999 ... -100: case 100 ... 999: DWINUI::drawSignedFloat(meshfont, 1, 1, px(x) - 3 * fs, fy, z); break; diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 3df1ed2dc550..f74bd199d3e8 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -66,7 +66,7 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; -#if HAS_STATUS_MESSAGE +#if HAS_DISPLAY #if ENABLED(STATUS_MESSAGE_SCROLLING) uint8_t MarlinUI::status_scroll_offset; // = 0 #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 8fdf3471b8cd..86c7a79b4b31 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -53,7 +53,7 @@ #include "e3v2/proui/dwin.h" #endif -#if ALL(HAS_STATUS_MESSAGE, IS_DWIN_MARLINUI) +#if ENABLED(IS_DWIN_MARLINUI) #include "e3v2/marlinui/marlinui_dwin.h" // for LCD_WIDTH #endif From 9011371d1320401a69b3204376b2290ad3072ed9 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 14 Apr 2024 00:49:58 -0400 Subject: [PATCH 100/109] add kill_screen to CrealityUI, group MarlinUI functions in JyersUI --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 15 +++++++++++++++ Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 24 ++++++++++++++---------- 2 files changed, 29 insertions(+), 10 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 054550b00d51..a92090d21935 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1809,6 +1809,21 @@ void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) void hmiSDCardInit() { card.cdroot(); } +void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const) { + clearMainWindow(); + drawPopupBkgd60(); + dwinIconShow(ICON, ICON_Info_1, 81, 90); + uint8_t slen = utf8_strlen(lcd_error); + if (hmiIsChinese()) { + // Chinese "Printer Killed" + } + else { + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 15) / 2, 210, GET_TEXT_F(MSG_PRINTER_KILLED)); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * slen) / 2, 240, lcd_error); + dwinDrawString(true, font8x16, COLOR_ERROR_RED, COLOR_BG_WINDOW, (272 - 8 * 20) / 2, 270, GET_TEXT_F(MSG_TURN_OFF)); + } +} + // Initialize or re-initialize the LCD void MarlinUI::init_lcd() { dwinStartup(); } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 2e7c37c55736..84c185a6173c 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -942,10 +942,6 @@ void JyersDWIN::drawPopup(FSTR_P const line1, FSTR_P const line2, FSTR_P const l } } -void MarlinUI::kill_screen(FSTR_P const error, FSTR_P const) { - jyersDWIN.drawPopup(F("Printer Kill Reason:"), error, F("Restart Required"), Proc_Wait, ICON_BLTouch); -} - void JyersDWIN::popupSelect() { const uint16_t c1 = selection ? COLOR_BG_WINDOW : getColor(eeprom_settings.highlight_box, COLOR_WHITE), c2 = selection ? getColor(eeprom_settings.highlight_box, COLOR_WHITE) : COLOR_BG_WINDOW; @@ -4915,12 +4911,6 @@ void JyersDWIN::update() { } } -void MarlinUI::update() { jyersDWIN.update(); } - -#if HAS_LCD_BRIGHTNESS - void MarlinUI::_set_brightness() { dwinLCDBrightness(backlight ? brightness : 0); } -#endif - void JyersDWIN::stateUpdate() { if ((print_job_timer.isRunning() || print_job_timer.isPaused()) != printing) { if (!printing) startPrint(card.isFileOpen() || TERN0(POWER_LOSS_RECOVERY, recovery.valid())); @@ -5127,6 +5117,20 @@ void JyersDWIN::resetSettings() { redrawScreen(); } +// +// MarlinUI Functions +// + +void MarlinUI::kill_screen(FSTR_P const error, FSTR_P const) { + jyersDWIN.drawPopup(F("Printer Kill Reason:"), error, F("Restart Required"), Proc_Wait, ICON_BLTouch); +} + +void MarlinUI::update() { jyersDWIN.update(); } + +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { dwinLCDBrightness(backlight ? brightness : 0); } +#endif + void MarlinUI::init_lcd() { delay(800); SERIAL_ECHOPGM("\nDWIN handshake "); From e1b965b301d636d5c696de5c4604642c04c8cebd Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sun, 14 Apr 2024 15:38:20 -0400 Subject: [PATCH 101/109] add dwinPopupConfirm/Continue, update Creality/JyersUI dwinDrawString --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 46 +++++++++++++------------- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 18 +++++----- Marlin/src/lcd/e3v2/proui/dwin.cpp | 11 +++--- Marlin/src/lcd/e3v2/proui/dwin_popup.h | 7 ++++ 4 files changed, 45 insertions(+), 37 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index a92090d21935..e48b31e93b61 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -115,8 +115,8 @@ constexpr uint16_t MROWS = TROWS - 1, // Last Row Index #define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) -#define DWIN_BOTTOM (DWIN_HEIGHT-1) -#define DWIN_RIGHT (DWIN_WIDTH-1) +#define DWIN_BOTTOM (DWIN_HEIGHT - 1) +#define DWIN_RIGHT (DWIN_WIDTH - 1) // Value Init hmi_value_t hmiValues; @@ -1112,9 +1112,9 @@ void popupWindowResume() { dwinIconShow(ICON, ICON_Continue_C, 146, 307); } 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, (DWIN_WIDTH - MENU_CHR_W * 14) / 2, 115, F("Continue Print")); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 22) / 2, 192, F("It looks like the last")); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 21) / 2, 212, F("file was interrupted.")); dwinIconShow(ICON, ICON_Cancel_E, 26, 307); dwinIconShow(ICON, ICON_Continue_E, 146, 307); } @@ -1130,8 +1130,8 @@ 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 * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); - dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 23) / 2, 260, F("Please wait until done.")); } } @@ -1146,8 +1146,8 @@ 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 * 23) / 2, 260, F("Please wait until done.")); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING)); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 23) / 2, 260, F("Please wait until done.")); } } @@ -1174,8 +1174,8 @@ void popupwindowPauseOrStop() { dwinIconShow(ICON, ICON_Cancel_C, 146, 280); } else { - if (select_print.now == PRINT_PAUSE_RESUME) dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); - else if (select_print.now == PRINT_STOP) dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); + if (select_print.now == PRINT_PAUSE_RESUME) dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); + else if (select_print.now == PRINT_STOP) dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); dwinIconShow(ICON, ICON_Confirm_E, 26, 280); dwinIconShow(ICON, ICON_Cancel_E, 146, 280); } @@ -1231,7 +1231,7 @@ void gotoPrintProcess() { // Copy into filebuf string before entry char * const name = card.longest_filename(); - const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * MENU_CHR_W) / 2; + const int8_t npos = _MAX(0U, DWIN_WIDTH - MENU_CHR_W * strlen(name)) / 2; dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLACK, npos, 60, name); dwinIconShow(ICON, ICON_PrintTime, 17, 163); @@ -1818,9 +1818,9 @@ void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const) { // Chinese "Printer Killed" } else { - dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * 15) / 2, 210, GET_TEXT_F(MSG_PRINTER_KILLED)); - dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * slen) / 2, 240, lcd_error); - dwinDrawString(true, font8x16, COLOR_ERROR_RED, COLOR_BG_WINDOW, (272 - 8 * 20) / 2, 270, GET_TEXT_F(MSG_TURN_OFF)); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 15) / 2, 210, GET_TEXT_F(MSG_PRINTER_KILLED)); + dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * slen) / 2, 240, lcd_error); + dwinDrawString(true, font8x16, COLOR_ERROR_RED, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * 20) / 2, 270, GET_TEXT_F(MSG_TURN_OFF)); } } @@ -1932,7 +1932,7 @@ void redrawSDList() { } else { dwinDrawRectangle(1, COLOR_BG_RED, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); - dwinDrawString(false, font16x32, COLOR_YELLOW, COLOR_BG_RED, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); + dwinDrawString(false, font16x32, COLOR_YELLOW, COLOR_BG_RED, (DWIN_WIDTH - 16 * 8) / 2, MBASE(3), F("No Media")); } } @@ -1985,7 +1985,7 @@ void hmiSDCardUpdate() { // void drawStatusArea(const bool with_update) { - dwinDrawRectangle(1, COLOR_BG_BLACK, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); + dwinDrawRectangle(1, COLOR_BG_BLACK, 0, STATUS_Y, DWIN_WIDTH, DWIN_BOTTOM); #if HAS_HOTEND dwinIconShow(ICON, ICON_HotendTemp, 10, 383); @@ -2048,8 +2048,8 @@ void hmiStartFrame(const bool with_update) { void drawInfoMenu() { clearMainWindow(); - dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLACK, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, F(MACHINE_SIZE)); - dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLACK, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, F(SHORT_BUILD_VERSION)); + dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLACK, (DWIN_WIDTH - MENU_CHR_W * strlen(MACHINE_SIZE)) / 2, 122, F(MACHINE_SIZE)); + dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLACK, (DWIN_WIDTH - MENU_CHR_W * strlen(SHORT_BUILD_VERSION)) / 2, 195, F(SHORT_BUILD_VERSION)); if (hmiIsChinese()) { dwinFrameTitleCopy(30, 17, 28, 13); // "Info" @@ -2069,7 +2069,7 @@ void drawInfoMenu() { dwinFrameAreaCopy(1, 146, 151, 254, 161, 82, 175); // "Firmware Version" dwinFrameAreaCopy(1, 1, 164, 96, 175, 89, 248); // "Contact details" } - dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLACK, (DWIN_WIDTH - strlen(CORP_WEBSITE) * MENU_CHR_W) / 2, 268, F(CORP_WEBSITE)); + dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLACK, (DWIN_WIDTH - MENU_CHR_W * strlen(CORP_WEBSITE)) / 2, 268, F(CORP_WEBSITE)); drawBackFirst(); for (uint8_t i = 0; i < 3; ++i) { @@ -4122,7 +4122,7 @@ void eachMomentUpdate() { drawPrintProgressBar(); // show print done confirm - dwinDrawRectangle(1, COLOR_BG_BLACK, 0, 250, DWIN_WIDTH - 1, STATUS_Y); + dwinDrawRectangle(1, COLOR_BG_BLACK, 0, 250, DWIN_RIGHT, STATUS_Y); dwinIconShow(ICON, hmiIsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); } else if (hmiFlag.pause_flag != printingIsPaused()) { @@ -4197,7 +4197,7 @@ void eachMomentUpdate() { update_selection(true); char * const name = card.longest_filename(); - const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; + const int8_t npos = _MAX(0U, DWIN_WIDTH - MENU_CHR_W * strlen(name)) / 2; dwinDrawString(true, font8x16, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, npos, 252, name); dwinUpdateLCD(); @@ -4319,7 +4319,7 @@ void dwinLevelingDone() { void dwinStatusChanged(PGM_P const cstr/*=nullptr*/) { dwinDrawRectangle(1, COLOR_BG_BLUE, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 24); - const int8_t x = _MAX(0U, DWIN_WIDTH - strlen(cstr) * MENU_CHR_W) / 2; + const int8_t x = _MAX(0U, DWIN_WIDTH - MENU_CHR_W * strlen(cstr)) / 2; dwinDrawString(false, font8x16, COLOR_WHITE, COLOR_BG_BLUE, x, STATUS_Y + 3, cstr); dwinUpdateLCD(); } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 84c185a6173c..d5378890f517 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -450,10 +450,10 @@ void JyersDWIN::drawFloat(const_float_t value, const uint8_t row, const bool sel const uint16_t xpos = 240 - (digits * 8); dwinDrawRectangle(1, COLOR_BG_BLACK, 194, MBASE(row), 234 - (digits * 8), MBASE(row) + 16); if (isnan(value)) - dwinDrawString(true, DWIN_FONT_MENU, COLOR_WHITE, bColor, xpos - 8, MBASE(row), F(" NaN")); + dwinDrawString(true, DWIN_FONT_MENU, COLOR_WHITE, bColor, xpos - MENU_CHR_W, MBASE(row), F(" NaN")); else { dwinDrawFloatValue(true, true, 0, DWIN_FONT_MENU, COLOR_WHITE, bColor, digits - log10(minunit) + 1, log10(minunit), xpos, MBASE(row), (value < 0 ? -value : value)); - dwinDrawString(true, DWIN_FONT_MENU, COLOR_WHITE, bColor, xpos - 8, MBASE(row), value < 0 ? F("-") : F(" ")); + dwinDrawString(true, DWIN_FONT_MENU, COLOR_WHITE, bColor, xpos - MENU_CHR_W, MBASE(row), value < 0 ? F("-") : F(" ")); } } @@ -698,7 +698,7 @@ void JyersDWIN::drawPrintFilename(const bool reset/*=false*/) { size_t outlen = 0; const char* outstr = scroller.scroll(outlen, buf, filename); dwinDrawRectangle(1, COLOR_BG_BLACK, 8, 50, DWIN_WIDTH - 8, 80); - const int8_t npos = (DWIN_WIDTH - outlen * MENU_CHR_W) / 2; + const int8_t npos = (DWIN_WIDTH - MENU_CHR_W * outlen) / 2; dwinDrawString(false, DWIN_FONT_MENU, COLOR_WHITE, COLOR_BG_BLACK, npos, 60, outstr); } } @@ -783,7 +783,7 @@ void JyersDWIN::drawSDList(const bool removed/*=false*/) { else { drawMenuItem(0, ICON_Back, GET_TEXT_F(MSG_BACK)); dwinDrawRectangle(1, COLOR_BG_RED, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); - dwinDrawString(false, font16x32, COLOR_YELLOW, COLOR_BG_RED, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), GET_TEXT_F(MSG_NO_MEDIA)); + dwinDrawString(false, font16x32, COLOR_YELLOW, COLOR_BG_RED, (DWIN_WIDTH - 16 * 8) / 2, MBASE(3), GET_TEXT_F(MSG_NO_MEDIA)); } dwinDrawRectangle(1, getColor(eeprom_settings.cursor_color, COLOR_RECTANGLE), 0, MBASE(0) - 18, 14, MBASE(0) + 33); } @@ -925,9 +925,9 @@ void JyersDWIN::drawPopup(FSTR_P const line1, FSTR_P const line2, FSTR_P const l dwinDrawRectangle(1, COLOR_BG_WINDOW, 14, 60, 258, 350); const uint8_t ypos = (mode == Proc_Popup || mode == Proc_Confirm) ? 150 : 230; if (icon > 0) dwinIconShow(ICON, icon, 101, 105); - dwinDrawString(true, DWIN_FONT_MENU, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * strlen_P(FTOP(line1))) / 2, ypos, line1); - dwinDrawString(true, DWIN_FONT_MENU, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * strlen_P(FTOP(line2))) / 2, ypos + 30, line2); - dwinDrawString(true, DWIN_FONT_MENU, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (272 - 8 * strlen_P(FTOP(line3))) / 2, ypos + 60, line3); + dwinDrawString(true, DWIN_FONT_MENU, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * strlen_P(FTOP(line1))) / 2, ypos, line1); + dwinDrawString(true, DWIN_FONT_MENU, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * strlen_P(FTOP(line2))) / 2, ypos + 30, line2); + dwinDrawString(true, DWIN_FONT_MENU, COLOR_POPUP_TEXT, COLOR_BG_WINDOW, (DWIN_WIDTH - MENU_CHR_W * strlen_P(FTOP(line3))) / 2, ypos + 60, line3); if (mode == Proc_Popup) { selection = 0; dwinDrawRectangle(1, COLOR_CONFIRM, 26, 280, 125, 317); @@ -968,12 +968,12 @@ void JyersDWIN::updateStatusBar(const bool refresh/*=false*/) { new_msg = false; if (process == Proc_Print) { dwinDrawRectangle(1, COLOR_GREY, 8, 214, DWIN_WIDTH - 8, 238); - const int8_t npos = (DWIN_WIDTH - len * MENU_CHR_W) / 2; + const int8_t npos = (DWIN_WIDTH - MENU_CHR_W * len) / 2; dwinDrawString(false, DWIN_FONT_MENU, getColor(eeprom_settings.status_bar_text, COLOR_WHITE), COLOR_BG_BLACK, npos, 219, dispmsg); } else { dwinDrawRectangle(1, COLOR_BG_BLACK, 8, 352, DWIN_WIDTH - 8, 376); - const int8_t npos = (DWIN_WIDTH - len * MENU_CHR_W) / 2; + const int8_t npos = (DWIN_WIDTH - MENU_CHR_W * len) / 2; dwinDrawString(false, DWIN_FONT_MENU, getColor(eeprom_settings.status_bar_text, COLOR_WHITE), COLOR_BG_BLACK, npos, 357, dispmsg); } } diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 26a5c57aff4d..c2591b99c583 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1719,15 +1719,15 @@ void dwinLevelingDone() { break; case PID_TEMP_TOO_HIGH: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_TEMP_TOO_HIGH)); + dwinPopupContinue(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_TEMP_TOO_HIGH)); break; case AUTOTUNE_DONE: checkkey = last_checkkey; - dwinPopupContinue(ICON_TempTooLow, GET_TEXT_F(MSG_PID_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); + dwinPopupConfirm(ICON_TempTooLow, GET_TEXT_F(MSG_PID_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); break; default: checkkey = last_checkkey; - dwinPopupConfirm(ICON_Info_0, GET_TEXT_F(MSG_ERROR), GET_TEXT_F(MSG_STOPPING)); + dwinPopupConfirm(ICON_Info_1, GET_TEXT_F(MSG_ERROR), GET_TEXT_F(MSG_STOPPING)); break; } } @@ -1759,11 +1759,12 @@ void dwinLevelingDone() { break; case AUTOTUNE_DONE: checkkey = last_checkkey; - dwinPopupContinue(ICON_TempTooLow, GET_TEXT_F(MSG_MPC_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); + dwinPopupConfirm(ICON_TempTooLow, GET_TEXT_F(MSG_MPC_AUTOTUNE), GET_TEXT_F(MSG_BUTTON_DONE)); ui.reset_alert_level(); break; default: checkkey = last_checkkey; + dwinPopupConfirm(ICON_Info_1, GET_TEXT_F(MSG_ERROR), GET_TEXT_F(MSG_STOPPING)); ui.reset_alert_level(); break; } @@ -2186,7 +2187,7 @@ void axisMove(AxisEnum axis) { #if HAS_HOTEND if (axis == E_AXIS && thermalManager.tooColdToExtrude(0)) { gcode.process_subcommands_now(F("G92E0")); // Reset extruder position - return dwinPopupContinue(ICON_TempTooLow, GET_TEXT_F(MSG_HOTEND_TOO_COLD), GET_TEXT_F(MSG_PLEASE_PREHEAT)); + return dwinPopupConfirm(ICON_TempTooLow, GET_TEXT_F(MSG_HOTEND_TOO_COLD), GET_TEXT_F(MSG_PLEASE_PREHEAT)); } #endif planner.synchronize(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.h b/Marlin/src/lcd/e3v2/proui/dwin_popup.h index 659c64472f20..f66dbb0462b4 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.h @@ -75,3 +75,10 @@ void dwinPopupContinue(const uint8_t icon, T amsg1, U amsg2) { dwinDrawPopup(icon, amsg1, amsg2, BTN_Continue); // Button Continue dwinUpdateLCD(); } + +template +void dwinPopupConfirm(const uint8_t icon, T amsg1, U amsg2) { + hmiSaveProcessID(ID_WaitResponse); + dwinDrawPopup(icon, amsg1, amsg2, BTN_Confirm); // Button Confirm + dwinUpdateLCD(); +} From 44114906b36f05edc46b6e76795682db1777d707 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Sat, 20 Apr 2024 07:50:33 -0400 Subject: [PATCH 102/109] #include in dwin.cpp --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index c2591b99c583..4f220723310c 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -37,6 +37,7 @@ #include "../../utf8.h" #include "../../marlinui.h" +#include "../../extui/ui_api.h" #include "../../../MarlinCore.h" #include "../../../core/serial.h" #include "../../../core/macros.h" From 2774a48a56896eadfd3a899b669243edfe824487 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 24 Apr 2024 04:57:44 -0400 Subject: [PATCH 103/109] remove characters causing issue with make format-pins --- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 26 +++++++++---------- Marlin/src/pins/mega/pins_HJC2560C_REV2.h | 4 +-- Marlin/src/pins/ramps/pins_RAMPS.h | 12 ++++----- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 2 +- .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 2 +- .../src/pins/stm32f1/pins_JGAURORA_A5S_A1.h | 3 --- 6 files changed, 23 insertions(+), 26 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 8a39e2790a73..dbacb0fa26f8 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -211,19 +211,19 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_01_PIN P1_31 -#define EXP1_02_PIN P1_30 -#define EXP1_03_PIN P0_18 -#define EXP1_04_PIN P0_16 -#define EXP1_05_PIN P0_15 - -#define EXP2_01_PIN P0_08 -#define EXP2_02_PIN P0_07 -#define EXP2_03_PIN P3_25 -#define EXP2_04_PIN P0_28 -#define EXP2_05_PIN P3_26 -#define EXP2_06_PIN P0_09 -#define EXP2_07_PIN P0_27 +#define EXP1_01_PIN P1_31 +#define EXP1_02_PIN P1_30 +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_16 +#define EXP1_05_PIN P0_15 + +#define EXP2_01_PIN P0_08 +#define EXP2_02_PIN P0_07 +#define EXP2_03_PIN P3_25 +#define EXP2_04_PIN P0_28 +#define EXP2_05_PIN P3_26 +#define EXP2_06_PIN P0_09 +#define EXP2_07_PIN P0_27 // // LCD / Controller diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index 638465f3b9eb..d0c0d77e6fa9 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -93,7 +93,7 @@ #define HEATER_BED_PIN 4 #ifndef FAN0_PIN - #define FAN0_PIN 7 //默认不使用PWM_FAN冷却喷嘴,如果需要,则取消注释 + #define FAN0_PIN 7 // PWM_FAN #endif // @@ -104,7 +104,7 @@ //#define LED_PIN 8 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 8 // 8 默认挤出机风扇作为Case LED,如果需要PWM FAN,则需要将FAN_PIN置为7,LED_PIN置为8 + #define CASE_LIGHT_PIN 8 // 8 Case LED,PWM FAN, FAN_PIN,LED_PIN #endif //#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 0e6e33e18e88..38684391021b 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -325,23 +325,23 @@ #if HAS_TMC_SPI #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI AUX2_09 + #define TMC_SPI_MOSI AUX2_09 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO AUX2_07 + #define TMC_SPI_MISO AUX2_07 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK AUX2_05 + #define TMC_SPI_SCK AUX2_05 #endif #else #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI AUX3_04 + #define TMC_SPI_MOSI AUX3_04 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO AUX3_03 + #define TMC_SPI_MISO AUX3_03 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK AUX3_05 + #define TMC_SPI_SCK AUX3_05 #endif #endif #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 2915c77d70c9..ba3c6767b261 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -101,7 +101,7 @@ #endif #if PIN_EXISTS(BEEPER) && (SERVO0_PIN == BEEPER_PIN || FIL_RUNOUT_PIN == BEEPER_PIN) #undef BEEPER_PIN - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 #endif /** diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index a381088ecf90..74d2b5549bc5 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -108,7 +108,7 @@ #endif #define E0_ENABLE_PIN 4 #else - #if !HAS_CUTTER && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // Use IO Header + #if !HAS_CUTTER && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // Use IO Header #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index 21ac51e279f5..2a75dbf9adae 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -22,9 +22,6 @@ #pragma once /** - * ╦╔═╗╔═╗┬ ┬┬─┐┌─┐┬─┐┌─┐╔═╗┌─┐┬─┐┬ ┬┌┬┐ ┌─┐┌─┐┌┬┐ - * ║║ ╦╠═╣│ │├┬┘│ │├┬┘├─┤╠╣ │ │├┬┘│ ││││ │ │ ││││ - * ╚╝╚═╝╩ ╩└─┘┴└─└─┘┴└─┴ ┴╚ └─┘┴└─└─┘┴ ┴o└─┘└─┘┴ ┴ * Pin assignments for 32-bit JGAurora A5S & A1 * * https://jgaurorawiki.com/_media/jgaurora_a5s_a1_pinout.png From 095230a28d7f248d721b48278ed1d1efb531057d Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 24 Apr 2024 06:08:20 -0400 Subject: [PATCH 104/109] revert pin *.h --- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 26 +++++++++---------- Marlin/src/pins/mega/pins_HJC2560C_REV2.h | 4 +-- Marlin/src/pins/ramps/pins_RAMPS.h | 12 ++++----- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 2 +- .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 2 +- .../src/pins/stm32f1/pins_JGAURORA_A5S_A1.h | 3 +++ 6 files changed, 26 insertions(+), 23 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index dbacb0fa26f8..8a39e2790a73 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -211,19 +211,19 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_01_PIN P1_31 -#define EXP1_02_PIN P1_30 -#define EXP1_03_PIN P0_18 -#define EXP1_04_PIN P0_16 -#define EXP1_05_PIN P0_15 - -#define EXP2_01_PIN P0_08 -#define EXP2_02_PIN P0_07 -#define EXP2_03_PIN P3_25 -#define EXP2_04_PIN P0_28 -#define EXP2_05_PIN P3_26 -#define EXP2_06_PIN P0_09 -#define EXP2_07_PIN P0_27 +#define EXP1_01_PIN P1_31 +#define EXP1_02_PIN P1_30 +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_16 +#define EXP1_05_PIN P0_15 + +#define EXP2_01_PIN P0_08 +#define EXP2_02_PIN P0_07 +#define EXP2_03_PIN P3_25 +#define EXP2_04_PIN P0_28 +#define EXP2_05_PIN P3_26 +#define EXP2_06_PIN P0_09 +#define EXP2_07_PIN P0_27 // // LCD / Controller diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index d0c0d77e6fa9..638465f3b9eb 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -93,7 +93,7 @@ #define HEATER_BED_PIN 4 #ifndef FAN0_PIN - #define FAN0_PIN 7 // PWM_FAN + #define FAN0_PIN 7 //默认不使用PWM_FAN冷却喷嘴,如果需要,则取消注释 #endif // @@ -104,7 +104,7 @@ //#define LED_PIN 8 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 8 // 8 Case LED,PWM FAN, FAN_PIN,LED_PIN + #define CASE_LIGHT_PIN 8 // 8 默认挤出机风扇作为Case LED,如果需要PWM FAN,则需要将FAN_PIN置为7,LED_PIN置为8 #endif //#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 38684391021b..0e6e33e18e88 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -325,23 +325,23 @@ #if HAS_TMC_SPI #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI AUX2_09 + #define TMC_SPI_MOSI AUX2_09 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO AUX2_07 + #define TMC_SPI_MISO AUX2_07 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK AUX2_05 + #define TMC_SPI_SCK AUX2_05 #endif #else #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI AUX3_04 + #define TMC_SPI_MOSI AUX3_04 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO AUX3_03 + #define TMC_SPI_MISO AUX3_03 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK AUX3_05 + #define TMC_SPI_SCK AUX3_05 #endif #endif #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index ba3c6767b261..2915c77d70c9 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -101,7 +101,7 @@ #endif #if PIN_EXISTS(BEEPER) && (SERVO0_PIN == BEEPER_PIN || FIL_RUNOUT_PIN == BEEPER_PIN) #undef BEEPER_PIN - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 #endif /** diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 74d2b5549bc5..a381088ecf90 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -108,7 +108,7 @@ #endif #define E0_ENABLE_PIN 4 #else - #if !HAS_CUTTER && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // Use IO Header + #if !HAS_CUTTER && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // Use IO Header #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index 2a75dbf9adae..21ac51e279f5 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -22,6 +22,9 @@ #pragma once /** + * ╦╔═╗╔═╗┬ ┬┬─┐┌─┐┬─┐┌─┐╔═╗┌─┐┬─┐┬ ┬┌┬┐ ┌─┐┌─┐┌┬┐ + * ║║ ╦╠═╣│ │├┬┘│ │├┬┘├─┤╠╣ │ │├┬┘│ ││││ │ │ ││││ + * ╚╝╚═╝╩ ╩└─┘┴└─└─┘┴└─┴ ┴╚ └─┘┴└─└─┘┴ ┴o└─┘└─┘┴ ┴ * Pin assignments for 32-bit JGAurora A5S & A1 * * https://jgaurorawiki.com/_media/jgaurora_a5s_a1_pinout.png From 0c1aee97f1f20b525558792be295506b6d8a4eb8 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 24 Apr 2024 06:19:23 -0400 Subject: [PATCH 105/109] Update jyersui dwin.cpp - manualValueUpdate --- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index d5378890f517..41463672e80e 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -259,11 +259,7 @@ class TextScroller { inline void manualValueUpdate(const bool undefined=false) { gcode.process_subcommands_now( - #if ENABLED(AUTO_BED_LEVELING_UBL) - TS(F("M421I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3), undefined ? "N" : "") - #else - TS(F("G29I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)) - #endif + TS('M421I', mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3), undefined ? "N" : "") ); planner.synchronize(); } From f6b4f754ad600796cd465e1b93ef69ec08abafa5 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 24 Apr 2024 06:21:42 -0400 Subject: [PATCH 106/109] Update proui bedlevel_tools.cpp - manualValueUpdate --- Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index 9832642f3983..d9c509347329 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -123,7 +123,7 @@ void BedLevelTools::manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y if (reset) { zval = 0; } else { zval = current_position.z; } gcode.process_subcommands_now( - TS(F(TERN(AUTO_BED_LEVELING_UBL, "M421 I", "G29 I")), mesh_x, 'J', mesh_y, 'Z', p_float_t(zval, 3)) + TS('M421 I', mesh_x, 'J', mesh_y, 'Z', p_float_t(zval, 3)) ); planner.synchronize(); } From 349235a12440e6e27dd4b3dd5afe53b4831d19a9 Mon Sep 17 00:00:00 2001 From: classicrocker883 Date: Wed, 24 Apr 2024 06:36:44 -0400 Subject: [PATCH 107/109] update proui spacing/comments --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 46 ++++++++++++++---------------- 1 file changed, 22 insertions(+), 24 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 1b1ee3c79d6d..2317b637c366 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -406,9 +406,10 @@ void iconStop() { iconButton(select_print.now == PRINT_STOP, ICON_Stop_0, ico, txt, GET_TEXT_F(MSG_BUTTON_STOP)); } -// -// PopUps -// +//----------------------------------------------------------------------------- +// Popups +//----------------------------------------------------------------------------- + void popupPauseOrStop() { if (hmiIsChinese()) { DWINUI::clearMainArea(); @@ -468,9 +469,11 @@ void popupPauseOrStop() { } #endif -// +//----------------------------------------------------------------------------- +// Main Menu & Print Screen +//----------------------------------------------------------------------------- + // Draw status line -// void dwinDrawStatusLine(PGM_P text) { dwinDrawRectangle(1, hmiData.colorStatusBg, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); if (text) DWINUI::drawCenteredString(hmiData.colorStatusTxt, STATUS_Y + 2, text); @@ -524,9 +527,9 @@ void dwinDrawStatusMessage() { // If the string doesn't completely fill the line... if (rlen < LCD_WIDTH) { - DWINUI::drawChar(hmiData.colorStatusTxt, '.'); // Always at 1+ spaces left, draw a dot - uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters - if (--chars) { // Draw a second dot if there's space + DWINUI::drawChar(hmiData.colorStatusTxt, '.'); // Always at 1+ spaces left, draw a dot + uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters + if (--chars) { // Draw a second dot if there's space DWINUI::drawChar(hmiData.colorStatusTxt, '.'); if (--chars) DWINUI::drawString(hmiData.colorStatusTxt, ui.status_message, chars); // Print a second copy of the message @@ -548,8 +551,8 @@ void dwinDrawStatusMessage() { void drawPrintLabels() { if (hmiIsChinese()) { - dwinFrameAreaCopy(1, 0, 72, 63, 86, 41, 173); // Printing Time - dwinFrameAreaCopy(1, 65, 72, 128, 86, 176, 173); // Remain + dwinFrameAreaCopy(1, 0, 72, 63, 86, 41, 173); // Printing Time + dwinFrameAreaCopy(1, 65, 72, 128, 86, 176, 173); // Remain } else { DWINUI::drawString( 46, 173, GET_TEXT_F(MSG_INFO_PRINT_TIME)); @@ -866,9 +869,9 @@ void updateVariable() { _drawZOffsetIcon(); } -/** - * Memory card and file management - */ +//----------------------------------------------------------------------------- +// Memory card and file management +//----------------------------------------------------------------------------- bool DWIN_lcd_sd_status = false; @@ -1025,9 +1028,7 @@ void drawPrintFileMenu() { TERN_(SCROLL_LONG_FILENAMES, fileMenuIdle(true)); } -// // Watch for media mount / unmount -// void hmiSDCardUpdate() { if (hmiFlag.home_flag) return; if (DWIN_lcd_sd_status != card.isMounted()) { @@ -1041,10 +1042,7 @@ void hmiSDCardUpdate() { } } -/** - * Dash board and indicators - */ - +// Dash board and indicators void dwinDrawDashboard() { dwinDrawRectangle(1, hmiData.colorBackground, 0, STATUS_Y + 21, DWIN_WIDTH, DWIN_HEIGHT - 1); dwinDrawRectangle(1, hmiData.colorSplitLine, 0, 449, DWIN_WIDTH, 451); @@ -1090,15 +1088,15 @@ void dwinDrawDashboard() { void drawInfoMenu() { DWINUI::clearMainArea(); if (hmiIsChinese()) - title.frameCopy(30, 17, 28, 13); // "Info" + title.frameCopy(30, 17, 28, 13); // "Info" else title.showCaption(GET_TEXT_F(MSG_INFO_SCREEN)); drawMenuLine(0, ICON_Back, GET_TEXT_F(MSG_BACK), false, true); if (hmiIsChinese()) { - dwinFrameAreaCopy(1, 197, 149, 252, 161, 108, 102); // "Size" - dwinFrameAreaCopy(1, 1, 164, 56, 176, 108, 175); // "Firmware Version" - dwinFrameAreaCopy(1, 58, 164, 113, 176, 105, 248); // "Contact Details" + dwinFrameAreaCopy(1, 197, 149, 252, 161, 108, 102); // "Size" + dwinFrameAreaCopy(1, 1, 164, 56, 176, 108, 175); // "Firmware Version" + dwinFrameAreaCopy(1, 58, 164, 113, 176, 105, 248); // "Contact Details" DWINUI::drawCenteredString(268, F(CORP_WEBSITE)); } else { @@ -1463,7 +1461,7 @@ void dwinHandleScreen() { } } -bool idIsPopUp() { // If ID is popup... +bool idIsPopUp() { // If ID is popup... switch (checkkey) { TERN_(HAS_BED_PROBE, case ID_Leveling:) TERN_(HAS_ESDIAG, case ID_ESDiagProcess:) From 84567d8aaad990fba4315297400e0485805b74b0 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 24 Apr 2024 06:58:51 -0400 Subject: [PATCH 108/109] Update jyers ui dwin.cpp --- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 41463672e80e..646c930fb2eb 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -259,7 +259,7 @@ class TextScroller { inline void manualValueUpdate(const bool undefined=false) { gcode.process_subcommands_now( - TS('M421I', mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3), undefined ? "N" : "") + TS("M421 I", mesh_x, "J", mesh_y, "Z", p_float_t(current_position.z, 3), undefined ? "N" : "") ); planner.synchronize(); } From 098a62eca0108f4613f324dc7ddb2cf8228e22f0 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 24 Apr 2024 07:01:40 -0400 Subject: [PATCH 109/109] Update dwin_popup.h spacing --- Marlin/src/lcd/e3v2/proui/dwin_popup.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.h b/Marlin/src/lcd/e3v2/proui/dwin_popup.h index f66dbb0462b4..e73047c0ec03 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.h @@ -72,13 +72,13 @@ void dwinShowPopup(const uint8_t icon, T amsg1=nullptr, U amsg2=nullptr, uint8_t template void dwinPopupContinue(const uint8_t icon, T amsg1, U amsg2) { hmiSaveProcessID(ID_WaitResponse); - dwinDrawPopup(icon, amsg1, amsg2, BTN_Continue); // Button Continue + dwinDrawPopup(icon, amsg1, amsg2, BTN_Continue); // Button Continue dwinUpdateLCD(); } template void dwinPopupConfirm(const uint8_t icon, T amsg1, U amsg2) { hmiSaveProcessID(ID_WaitResponse); - dwinDrawPopup(icon, amsg1, amsg2, BTN_Confirm); // Button Confirm + dwinDrawPopup(icon, amsg1, amsg2, BTN_Confirm); // Button Confirm dwinUpdateLCD(); }