merge with upstream/MK3

This commit is contained in:
PavelSindler 2018-07-17 16:36:53 +02:00
commit 33f9af65c8
43 changed files with 4239 additions and 5570 deletions

View file

@ -7,8 +7,8 @@
#define STR(x) STR_HELPER(x)
// Firmware version
#define FW_VERSION "3.3.0"
#define FW_COMMIT_NR 830
#define FW_VERSION "3.3.1"
#define FW_COMMIT_NR 845
// FW_VERSION_UNKNOWN means this is an unofficial build.
// The firmware should only be checked into github with this symbol.
#define FW_DEV_VERSION FW_VERSION_UNKNOWN
@ -621,154 +621,18 @@ your extruder heater takes 2 minutes to hit the target on heating.
#define HOST_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//LCD and SD support
#define ULTRA_LCD //general LCD support, also 16x2
#define SDSUPPORT // Enable SD Card Support in Hardware Console
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
#define ENCODER_PULSES_PER_STEP 4 // Increase if you have a high resolution encoder
#define ENCODER_STEPS_PER_MENU_ITEM 1 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
//#define ENCODER_STEPS_PER_MENU_ITEM 1 // Set according to ENCODER_PULSES_PER_STEP or your liking
// The RepRapDiscount Smart Controller (white PCB)
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
#define REPRAP_DISCOUNT_SMART_CONTROLLER
// The GADGETS3D G3D LCD/SD Controller (blue PCB)
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
//#define G3D_PANEL
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
// The Elefu RA Board Control Panel
// http://www.elefu.com/index.php?route=product/product&product_id=53
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
//#define RA_CONTROL_PANEL
//automatic expansion
#if defined (MAKRPANEL)
#define SDSUPPORT
#define ULTIPANEL
#define NEWPANEL
#define DEFAULT_LCD_CONTRAST 17
#endif
#if defined(ULTIMAKERCONTROLLER) || defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL)
#define ULTIPANEL
#define NEWPANEL
#endif
#if defined(REPRAPWORLD_KEYPAD)
#define NEWPANEL
#define ULTIPANEL
#endif
#if defined(RA_CONTROL_PANEL)
#define ULTIPANEL
#define NEWPANEL
#define LCD_I2C_TYPE_PCA8574
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
#endif
//I2C PANELS
//#define LCD_I2C_SAINSMART_YWROBOT
#ifdef LCD_I2C_SAINSMART_YWROBOT
// This uses the LiquidCrystal_I2C library ( https://bitbucket.org/fmalpartida/new-LiquidCrystal_Prusa/wiki/Home )
// Make sure it is placed in the Arduino libraries directory.
#define LCD_I2C_TYPE_PCF8575
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
#define NEWPANEL
#define ULTIPANEL
#endif
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
//#define LCD_I2C_PANELOLU2
#ifdef LCD_I2C_PANELOLU2
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
// (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
// Note: The PANELOLU2 encoder click input can either be directly connected to a pin
// (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
#define NEWPANEL
#define ULTIPANEL
#ifndef ENCODER_PULSES_PER_STEP
#define ENCODER_PULSES_PER_STEP 4
#endif
#ifndef ENCODER_STEPS_PER_MENU_ITEM
#define ENCODER_STEPS_PER_MENU_ITEM 2
#endif
#ifdef LCD_USE_I2C_BUZZER
#define LCD_FEEDBACK_FREQUENCY_HZ 1000
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
#endif
#endif
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
//#define LCD_I2C_VIKI
#ifdef LCD_I2C_VIKI
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
// Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
// Note: The pause/stop/resume LCD button pin should be connected to the Arduino
// BTN_ENC pin (or set BTN_ENC to -1 if not used)
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
#define NEWPANEL
#define ULTIPANEL
#endif
// Shift register panels
// ---------------------
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-LiquidCrystal_Prusa/wiki/schematics#!shiftregister-connection
//#define SAV_3DLCD
#ifdef SAV_3DLCD
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister
#define NEWPANEL
#define ULTIPANEL
#endif
#ifdef ULTIPANEL
// #define NEWPANEL //enable this if you have a click-encoder panel
#define SDSUPPORT
#define ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the DOG graphic display
#define LCD_WIDTH 20
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 20
#define LCD_HEIGHT 4
#endif
#else //no panel but just LCD
#ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20
#define LCD_HEIGHT 5
#else
#define LCD_WIDTH 16
#define LCD_HEIGHT 2
#endif
#endif
#endif
#define SDSUPPORT
#define LCD_WIDTH 20
#define LCD_HEIGHT 4
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino

View file

@ -68,13 +68,6 @@ void Config_StoreSettings(uint16_t offset, uint8_t level)
EEPROM_WRITE_VAR(i,max_jerk[Z_AXIS]);
EEPROM_WRITE_VAR(i,max_jerk[E_AXIS]);
EEPROM_WRITE_VAR(i,add_homing);
#ifndef ULTIPANEL
int plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP, plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP, plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED;
int absPreheatHotendTemp = ABS_PREHEAT_HOTEND_TEMP, absPreheatHPBTemp = ABS_PREHEAT_HPB_TEMP, absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED;
#endif
/* EEPROM_WRITE_VAR(i,plaPreheatHotendTemp);
EEPROM_WRITE_VAR(i,plaPreheatHPBTemp);
EEPROM_WRITE_VAR(i,plaPreheatFanSpeed);
@ -100,10 +93,7 @@ void Config_StoreSettings(uint16_t offset, uint8_t level)
EEPROM_WRITE_VAR(i, bedKi);
EEPROM_WRITE_VAR(i, bedKd);
#endif
#ifndef DOGLCD
int lcd_contrast = 32;
#endif
EEPROM_WRITE_VAR(i,lcd_contrast);
// EEPROM_WRITE_VAR(i,lcd_contrast);
#ifdef FWRETRACT
EEPROM_WRITE_VAR(i,autoretract_enabled);
EEPROM_WRITE_VAR(i,retract_length);
@ -154,132 +144,62 @@ void Config_StoreSettings(uint16_t offset, uint8_t level)
#ifndef DISABLE_M503
void Config_PrintSettings(uint8_t level)
{ // Always have this function, even with EEPROM_SETTINGS disabled, the current values will be shown
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Steps per unit:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M92 X",axis_steps_per_unit[X_AXIS]);
SERIAL_ECHOPAIR(" Y",axis_steps_per_unit[Y_AXIS]);
SERIAL_ECHOPAIR(" Z",axis_steps_per_unit[Z_AXIS]);
SERIAL_ECHOPAIR(" E",axis_steps_per_unit[E_AXIS]);
SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Maximum feedrates (mm/s):");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M203 X", max_feedrate[X_AXIS]);
SERIAL_ECHOPAIR(" Y", max_feedrate[Y_AXIS]);
SERIAL_ECHOPAIR(" Z", max_feedrate[Z_AXIS]);
SERIAL_ECHOPAIR(" E", max_feedrate[E_AXIS]);
SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Maximum Acceleration (mm/s2):");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M201 X" ,max_acceleration_units_per_sq_second[X_AXIS] );
SERIAL_ECHOPAIR(" Y" , max_acceleration_units_per_sq_second[Y_AXIS] );
SERIAL_ECHOPAIR(" Z" ,max_acceleration_units_per_sq_second[Z_AXIS] );
SERIAL_ECHOPAIR(" E" ,max_acceleration_units_per_sq_second[E_AXIS]);
SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Acceleration: S=acceleration, T=retract acceleration");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M204 S",acceleration );
SERIAL_ECHOPAIR(" T" ,retract_acceleration);
SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s), Z=maximum Z jerk (mm/s), E=maximum E jerk (mm/s)");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M205 S",minimumfeedrate );
SERIAL_ECHOPAIR(" T" ,mintravelfeedrate );
SERIAL_ECHOPAIR(" B" ,minsegmenttime );
SERIAL_ECHOPAIR(" X" ,max_jerk[X_AXIS] );
SERIAL_ECHOPAIR(" Y" ,max_jerk[Y_AXIS] );
SERIAL_ECHOPAIR(" Z" ,max_jerk[Z_AXIS] );
SERIAL_ECHOPAIR(" E" ,max_jerk[E_AXIS] );
SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Home offset (mm):");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M206 X",add_homing[X_AXIS] );
SERIAL_ECHOPAIR(" Y" ,add_homing[Y_AXIS] );
SERIAL_ECHOPAIR(" Z" ,add_homing[Z_AXIS] );
SERIAL_ECHOLN("");
printf_P(PSTR(
"%SSteps per unit:\n%S M92 X%.2f Y%.2f Z%.2f E%.2f\n"
"%SMaximum feedrates (mm/s):\n%S M203 X%.2f Y%.2f Z%.2f E%.2f\n"
"%SMaximum Acceleration (mm/s2):\n%S M201 X%.2f Y%.2f Z%.2f E%.2f\n"
"%SAcceleration: S=acceleration, T=retract acceleration\n%S M204 S%.2f T%.2f\n"
"%SAdvanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s), Z=maximum Z jerk (mm/s), E=maximum E jerk (mm/s)\n%S M205 S%.2f T%.2f B%.2f X%.2f Y%.2f Z%.2f E%.2f\n"
"%SHome offset (mm):\n%S M206 X%.2f Y%.2f Z%.2f\n"
),
echomagic, echomagic, axis_steps_per_unit[X_AXIS], axis_steps_per_unit[Y_AXIS], axis_steps_per_unit[Z_AXIS], axis_steps_per_unit[E_AXIS],
echomagic, echomagic, max_feedrate[X_AXIS], max_feedrate[Y_AXIS], max_feedrate[Z_AXIS], max_feedrate[E_AXIS],
echomagic, echomagic, max_acceleration_units_per_sq_second[X_AXIS], max_acceleration_units_per_sq_second[Y_AXIS], max_acceleration_units_per_sq_second[Z_AXIS], max_acceleration_units_per_sq_second[E_AXIS],
echomagic, echomagic, acceleration, retract_acceleration,
echomagic, echomagic, minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS],
echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS]
);
#ifdef PIDTEMP
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("PID settings:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M301 P",Kp);
SERIAL_ECHOPAIR(" I" ,unscalePID_i(Ki));
SERIAL_ECHOPAIR(" D" ,unscalePID_d(Kd));
SERIAL_ECHOLN("");
printf_P(PSTR("%SPID settings:\n%S M301 P%.2f I%.2f D%.2f\n"),
echomagic, echomagic, Kp, unscalePID_i(Ki), unscalePID_d(Kd));
#endif
#ifdef PIDTEMPBED
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("PID heatbed settings:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M304 P", bedKp);
SERIAL_ECHOPAIR(" I", unscalePID_i(bedKi));
SERIAL_ECHOPAIR(" D", unscalePID_d(bedKd));
SERIAL_ECHOLN("");
printf_P(PSTR("%SPID heatbed settings:\n%S M304 P%.2f I%.2f D%.2f\n"),
echomagic, echomagic, bedKp, unscalePID_i(bedKi), unscalePID_d(bedKd));
#endif
#ifdef FWRETRACT
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M207 S",retract_length);
SERIAL_ECHOPAIR(" F" ,retract_feedrate*60);
SERIAL_ECHOPAIR(" Z" ,retract_zlift);
SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Recover: S=Extra length (mm) F:Speed (mm/m)");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M208 S",retract_recover_length);
SERIAL_ECHOPAIR(" F", retract_recover_feedrate*60);
SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Auto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M209 S", (unsigned long)(autoretract_enabled ? 1 : 0));
SERIAL_ECHOLN("");
printf_P(PSTR(
"%SRetract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)\n%S M207 S%.2f F%.2f Z%.2f\n"
"%SRecover: S=Extra length (mm) F:Speed (mm/m)\n%S M208 S%.2f F%.2f\n"
"%SAuto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries\n%S M209 S%.2f\n"
),
echomagic, echomagic, retract_length, retract_feedrate*60, retract_zlift,
echomagic, echomagic, retract_recover_length, retract_recover_feedrate*60,
echomagic, echomagic, (unsigned long)(autoretract_enabled ? 1 : 0)
);
#if EXTRUDERS > 1
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Multi-extruder settings:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" Swap retract length (mm): ", retract_length_swap);
SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" Swap rec. addl. length (mm): ", retract_recover_length_swap);
SERIAL_ECHOLN("");
printf_P(PSTR("%SMulti-extruder settings:\n%S Swap retract length (mm): %.2f\n%S Swap rec. addl. length (mm): %.2f\n"),
echomagic, echomagic, retract_length_swap, echomagic, retract_recover_length_swap);
#endif
SERIAL_ECHO_START;
if (volumetric_enabled) {
SERIAL_ECHOLNPGM("Filament settings:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M200 D", filament_size[0]);
SERIAL_ECHOLN("");
if (volumetric_enabled) {
printf_P(PSTR("%SFilament settings:\n%S M200 D%.2f\n"),
echomagic, echomagic, filament_size[0]);
#if EXTRUDERS > 1
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M200 T1 D", filament_size[1]);
SERIAL_ECHOLN("");
printf_P(PSTR("%S M200 T1 D%.2f\n"),
echomagic, echomagic, filament_size[1]);
#if EXTRUDERS > 2
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M200 T2 D", filament_size[2]);
SERIAL_ECHOLN("");
printf_P(PSTR("%S M200 T1 D%.2f\n"),
echomagic, echomagic, filament_size[2]);
#endif
#endif
} else {
SERIAL_ECHOLNPGM("Filament settings: Disabled");
printf_P(PSTR("%SFilament settings: Disabled\n"), echomagic);
}
#endif
if (level >= 10) {
#ifdef LIN_ADVANCE
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Linear advance settings:");
SERIAL_ECHOPAIR(" M900 K", extruder_advance_k);
SERIAL_ECHOPAIR(" E/D = ", advance_ed_ratio);
printf_P(PSTR("%SLinear advance settings:\n M900 K%.2f E/D = %.2f\n"),
echomagic, extruder_advance_k, advance_ed_ratio);
#endif //LIN_ADVANCE
}
}
@ -317,11 +237,6 @@ bool Config_RetrieveSettings(uint16_t offset, uint8_t level)
if (max_jerk[X_AXIS] > DEFAULT_XJERK) max_jerk[X_AXIS] = DEFAULT_XJERK;
if (max_jerk[Y_AXIS] > DEFAULT_YJERK) max_jerk[Y_AXIS] = DEFAULT_YJERK;
EEPROM_READ_VAR(i,add_homing);
#ifndef ULTIPANEL
int plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed;
int absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed;
#endif
/*
EEPROM_READ_VAR(i,plaPreheatHotendTemp);
EEPROM_READ_VAR(i,plaPreheatHPBTemp);
@ -345,10 +260,7 @@ bool Config_RetrieveSettings(uint16_t offset, uint8_t level)
EEPROM_READ_VAR(i, bedKi);
EEPROM_READ_VAR(i, bedKd);
#endif
#ifndef DOGLCD
int lcd_contrast;
#endif
EEPROM_READ_VAR(i,lcd_contrast);
// EEPROM_READ_VAR(i,lcd_contrast);
#ifdef FWRETRACT
EEPROM_READ_VAR(i,autoretract_enabled);
@ -433,9 +345,6 @@ void Config_ResetDefault()
#ifdef ENABLE_AUTO_BED_LEVELING
zprobe_zoffset = -Z_PROBE_OFFSET_FROM_EXTRUDER;
#endif
#ifdef DOGLCD
lcd_contrast = DEFAULT_LCD_CONTRAST;
#endif
#ifdef PIDTEMP
Kp = DEFAULT_Kp;
Ki = scalePID_i(DEFAULT_Ki);

View file

@ -178,9 +178,7 @@
//Comment to disable setting feedrate multiplier via encoder
#ifdef ULTIPANEL
#define ULTIPANEL_FEEDMULTIPLY
#endif
#define ULTIPANEL_FEEDMULTIPLY
// minimum time in microseconds that a movement needs to take if the buffer is emptied.
#define DEFAULT_MINSEGMENTTIME 20000
@ -260,20 +258,6 @@
#define HAS_FOLDER_SORTING (FOLDER_SORTING || SDSORT_GCODE)
#endif
// Show a progress bar on the LCD when printing from SD?
//#define LCD_PROGRESS_BAR
#ifdef LCD_PROGRESS_BAR
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
#endif
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
@ -342,10 +326,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
// in the pins.h file. When using a push button pulling the pin to ground this will need inverted. This setting should
// be commented out otherwise
#define SDCARDDETECTINVERTED
#ifdef ULTIPANEL
#undef SDCARDDETECTINVERTED
#endif
#undef SDCARDDETECTINVERTED
// Power Signal Control Definitions
// By default use ATX definition

View file

@ -33,24 +33,3 @@
#include "Configuration.h"
#include "pins.h"
#ifdef ULTRA_LCD
#if defined(LCD_I2C_TYPE_PCF8575)
#include <Wire.h>
#include <LiquidCrystal_I2C.h>
#elif defined(LCD_I2C_TYPE_MCP23017) || defined(LCD_I2C_TYPE_MCP23008)
#include <Wire.h>
#include <LiquidTWI2.h>
#elif defined(DOGLCD)
#include <U8glib.h> // library for graphics LCD by Oli Kraus (https://code.google.com/p/u8glib/)
#else
#include "LiquidCrystal_Prusa.h" // library for character LCD
#endif
#endif
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
#include <SPI.h>
#endif
#if defined(DIGIPOT_I2C)
#include <Wire.h>
#endif

View file

@ -1,718 +0,0 @@
#include "LiquidCrystal_Prusa.h"
#include <stdio.h>
#include <string.h>
#include <inttypes.h>
#include "Arduino.h"
// When the display powers up, it is configured as follows:
//
// 1. Display clear
// 2. Function set:
// DL = 1; 8-bit interface data
// N = 0; 1-line display
// F = 0; 5x8 dot character font
// 3. Display on/off control:
// D = 0; Display off
// C = 0; Cursor off
// B = 0; Blinking off
// 4. Entry mode set:
// I/D = 1; Increment by 1
// S = 0; No shift
//
// Note, however, that resetting the Arduino doesn't reset the LCD, so we
// can't assume that it's in that state when a sketch starts (and the
// LiquidCrystal_Prusa constructor is called).
LiquidCrystal_Prusa::LiquidCrystal_Prusa(uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7)
{
init(0, rs, rw, enable, d0, d1, d2, d3, d4, d5, d6, d7);
}
LiquidCrystal_Prusa::LiquidCrystal_Prusa(uint8_t rs, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7)
{
init(0, rs, 255, enable, d0, d1, d2, d3, d4, d5, d6, d7);
}
LiquidCrystal_Prusa::LiquidCrystal_Prusa(uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3)
{
init(1, rs, rw, enable, d0, d1, d2, d3, 0, 0, 0, 0);
}
LiquidCrystal_Prusa::LiquidCrystal_Prusa(uint8_t rs, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3)
{
init(1, rs, 255, enable, d0, d1, d2, d3, 0, 0, 0, 0);
}
void LiquidCrystal_Prusa::init(uint8_t fourbitmode, uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7)
{
_rs_pin = rs;
_rw_pin = rw;
_enable_pin = enable;
_data_pins[0] = d0;
_data_pins[1] = d1;
_data_pins[2] = d2;
_data_pins[3] = d3;
_data_pins[4] = d4;
_data_pins[5] = d5;
_data_pins[6] = d6;
_data_pins[7] = d7;
pinMode(_rs_pin, OUTPUT);
// we can save 1 pin by not using RW. Indicate by passing 255 instead of pin#
if (_rw_pin != 255) {
pinMode(_rw_pin, OUTPUT);
}
pinMode(_enable_pin, OUTPUT);
if (fourbitmode)
_displayfunction = LCD_4BITMODE | LCD_1LINE | LCD_5x8DOTS;
else
_displayfunction = LCD_8BITMODE | LCD_1LINE | LCD_5x8DOTS;
begin(16, 1);
}
void LiquidCrystal_Prusa::begin(uint8_t cols, uint8_t lines, uint8_t dotsize) {
if (lines > 1) {
_displayfunction |= LCD_2LINE;
}
_numlines = lines;
_currline = 0;
// for some 1 line displays you can select a 10 pixel high font
if ((dotsize != 0) && (lines == 1)) {
_displayfunction |= LCD_5x10DOTS;
}
// SEE PAGE 45/46 FOR INITIALIZATION SPECIFICATION!
// according to datasheet, we need at least 40ms after power rises above 2.7V
// before sending commands. Arduino can turn on way befer 4.5V so we'll wait 50
delayMicroseconds(50000);
// Now we pull both RS and R/W low to begin commands
digitalWrite(_rs_pin, LOW);
digitalWrite(_enable_pin, LOW);
if (_rw_pin != 255) {
digitalWrite(_rw_pin, LOW);
}
//put the LCD into 4 bit or 8 bit mode
if (! (_displayfunction & LCD_8BITMODE)) {
// this is according to the hitachi HD44780 datasheet
// figure 24, pg 46
// we start in 8bit mode, try to set 4 bit mode
write4bits(0x03);
delayMicroseconds(4500); // wait min 4.1ms
// second try
write4bits(0x03);
delayMicroseconds(4500); // wait min 4.1ms
// third go!
write4bits(0x03);
delayMicroseconds(150);
// finally, set to 4-bit interface
write4bits(0x02);
} else {
// this is according to the hitachi HD44780 datasheet
// page 45 figure 23
// Send function set command sequence
command(LCD_FUNCTIONSET | _displayfunction);
delayMicroseconds(4500); // wait more than 4.1ms
// second try
command(LCD_FUNCTIONSET | _displayfunction);
delayMicroseconds(150);
// third go
command(LCD_FUNCTIONSET | _displayfunction);
}
// finally, set # lines, font size, etc.
command(LCD_FUNCTIONSET | _displayfunction);
delayMicroseconds(60);
// turn the display on with no cursor or blinking default
_displaycontrol = LCD_DISPLAYON | LCD_CURSOROFF | LCD_BLINKOFF;
display();
delayMicroseconds(60);
// clear it off
clear();
delayMicroseconds(3000);
// Initialize to default text direction (for romance languages)
_displaymode = LCD_ENTRYLEFT | LCD_ENTRYSHIFTDECREMENT;
// set the entry mode
command(LCD_ENTRYMODESET | _displaymode);
delayMicroseconds(60);
_escape[0] = 0;
}
void LiquidCrystal_Prusa::begin_noclear(uint8_t cols, uint8_t lines, uint8_t dotsize) {
if (lines > 1) {
_displayfunction |= LCD_2LINE;
}
_numlines = lines;
_currline = 0;
// for some 1 line displays you can select a 10 pixel high font
if ((dotsize != 0) && (lines == 1)) {
_displayfunction |= LCD_5x10DOTS;
}
// SEE PAGE 45/46 FOR INITIALIZATION SPECIFICATION!
// according to datasheet, we need at least 40ms after power rises above 2.7V
// before sending commands. Arduino can turn on way befer 4.5V so we'll wait 50
delayMicroseconds(50000);
// Now we pull both RS and R/W low to begin commands
digitalWrite(_rs_pin, LOW);
digitalWrite(_enable_pin, LOW);
if (_rw_pin != 255) {
digitalWrite(_rw_pin, LOW);
}
//put the LCD into 4 bit or 8 bit mode
if (! (_displayfunction & LCD_8BITMODE)) {
// this is according to the hitachi HD44780 datasheet
// figure 24, pg 46
// we start in 8bit mode, try to set 4 bit mode
write4bits(0x03);
delayMicroseconds(4500); // wait min 4.1ms
// second try
write4bits(0x03);
delayMicroseconds(4500); // wait min 4.1ms
// third go!
write4bits(0x03);
delayMicroseconds(150);
// finally, set to 4-bit interface
write4bits(0x02);
} else {
// this is according to the hitachi HD44780 datasheet
// page 45 figure 23
// Send function set command sequence
command(LCD_FUNCTIONSET | _displayfunction);
delayMicroseconds(4500); // wait more than 4.1ms
// second try
command(LCD_FUNCTIONSET | _displayfunction);
delayMicroseconds(150);
// third go
command(LCD_FUNCTIONSET | _displayfunction);
}
// finally, set # lines, font size, etc.
command(LCD_FUNCTIONSET | _displayfunction);
delayMicroseconds(60);
// turn the display on with no cursor or blinking default
_displaycontrol = LCD_DISPLAYON | LCD_CURSOROFF | LCD_BLINKOFF;
display();
delayMicroseconds(60);
// clear it off
//clear();
home();
delayMicroseconds(1600);
// Initialize to default text direction (for romance languages)
_displaymode = LCD_ENTRYLEFT | LCD_ENTRYSHIFTDECREMENT;
// set the entry mode
command(LCD_ENTRYMODESET | _displaymode);
delayMicroseconds(60);
setCursor(8,0);
print(" ");
setCursor(8,1);
print(" ");
setCursor(6,2);
print(" ");
}
/********** high level commands, for the user! */
void LiquidCrystal_Prusa::clear()
{
command(LCD_CLEARDISPLAY); // clear display, set cursor position to zero
delayMicroseconds(1600); // this command takes a long time
}
void LiquidCrystal_Prusa::home()
{
command(LCD_RETURNHOME); // set cursor position to zero
delayMicroseconds(1600); // this command takes a long time!
}
void LiquidCrystal_Prusa::setCursor(uint8_t col, uint8_t row)
{
int row_offsets[] = { 0x00, 0x40, 0x14, 0x54 };
if ( row >= _numlines ) {
row = _numlines-1; // we count rows starting w/0
}
_currline = row;
command(LCD_SETDDRAMADDR | (col + row_offsets[row]));
}
// Turn the display on/off (quickly)
void LiquidCrystal_Prusa::noDisplay() {
_displaycontrol &= ~LCD_DISPLAYON;
command(LCD_DISPLAYCONTROL | _displaycontrol);
}
void LiquidCrystal_Prusa::display() {
_displaycontrol |= LCD_DISPLAYON;
command(LCD_DISPLAYCONTROL | _displaycontrol);
}
// Turns the underline cursor on/off
void LiquidCrystal_Prusa::noCursor() {
_displaycontrol &= ~LCD_CURSORON;
command(LCD_DISPLAYCONTROL | _displaycontrol);
}
void LiquidCrystal_Prusa::cursor() {
_displaycontrol |= LCD_CURSORON;
command(LCD_DISPLAYCONTROL | _displaycontrol);
}
// Turn on and off the blinking cursor
void LiquidCrystal_Prusa::noBlink() {
_displaycontrol &= ~LCD_BLINKON;
command(LCD_DISPLAYCONTROL | _displaycontrol);
}
void LiquidCrystal_Prusa::blink() {
_displaycontrol |= LCD_BLINKON;
command(LCD_DISPLAYCONTROL | _displaycontrol);
}
// These commands scroll the display without changing the RAM
void LiquidCrystal_Prusa::scrollDisplayLeft(void) {
command(LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVELEFT);
}
void LiquidCrystal_Prusa::scrollDisplayRight(void) {
command(LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVERIGHT);
}
// This is for text that flows Left to Right
void LiquidCrystal_Prusa::leftToRight(void) {
_displaymode |= LCD_ENTRYLEFT;
command(LCD_ENTRYMODESET | _displaymode);
}
// This is for text that flows Right to Left
void LiquidCrystal_Prusa::rightToLeft(void) {
_displaymode &= ~LCD_ENTRYLEFT;
command(LCD_ENTRYMODESET | _displaymode);
}
// This will 'right justify' text from the cursor
void LiquidCrystal_Prusa::autoscroll(void) {
_displaymode |= LCD_ENTRYSHIFTINCREMENT;
command(LCD_ENTRYMODESET | _displaymode);
}
// This will 'left justify' text from the cursor
void LiquidCrystal_Prusa::noAutoscroll(void) {
_displaymode &= ~LCD_ENTRYSHIFTINCREMENT;
command(LCD_ENTRYMODESET | _displaymode);
}
// Allows us to fill the first 8 CGRAM locations
// with custom characters
void LiquidCrystal_Prusa::createChar(uint8_t location, uint8_t charmap[]) {
location &= 0x7; // we only have 8 locations 0-7
command(LCD_SETCGRAMADDR | (location << 3));
for (int i=0; i<8; i++)
send(charmap[i], HIGH);
}
/*********** mid level commands, for sending data/cmds */
inline void LiquidCrystal_Prusa::command(uint8_t value) {
send(value, LOW);
}
inline size_t LiquidCrystal_Prusa::write(uint8_t value) {
if (value == '\n')
{
if (_currline > 3) _currline = -1;
setCursor(0, _currline + 1); // LF
return 1;
}
if (_escape[0] || (value == 0x1b))
return escape_write(value);
send(value, HIGH);
return 1; // assume sucess
}
//Supported VT100 escape codes:
//EraseScreen "\x1b[2J"
//CursorHome "\x1b[%d;%dH"
//CursorShow "\x1b[?25h"
//CursorHide "\x1b[?25l"
inline size_t LiquidCrystal_Prusa::escape_write(uint8_t chr)
{
#define escape_cnt (_escape[0]) //escape character counter
#define is_num_msk (_escape[1]) //numeric character bit mask
#define chr_is_num (is_num_msk & 0x01) //current character is numeric
#define e_2_is_num (is_num_msk & 0x04) //escape char 2 is numeric
#define e_3_is_num (is_num_msk & 0x08) //...
#define e_4_is_num (is_num_msk & 0x10)
#define e_5_is_num (is_num_msk & 0x20)
#define e_6_is_num (is_num_msk & 0x40)
#define e_7_is_num (is_num_msk & 0x80)
#define e2_num (_escape[2] - '0') //number from character 2
#define e3_num (_escape[3] - '0') //number from character 3
#define e23_num (10*e2_num+e3_num) //number from characters 2 and 3
#define e4_num (_escape[4] - '0') //number from character 4
#define e5_num (_escape[5] - '0') //number from character 5
#define e45_num (10*e4_num+e5_num) //number from characters 4 and 5
#define e6_num (_escape[6] - '0') //number from character 6
#define e56_num (10*e5_num+e6_num) //number from characters 5 and 6
if (escape_cnt > 1) // escape length > 1 = "\x1b["
{
_escape[escape_cnt] = chr; // store current char
if ((chr >= '0') && (chr <= '9')) // char is numeric
is_num_msk |= (1 | (1 << escape_cnt)); //set mask
else
is_num_msk &= ~1; //clear mask
}
switch (escape_cnt++)
{
case 0:
if (chr == 0x1b) return 1; // escape = "\x1b"
break;
case 1:
is_num_msk = 0x00; // reset 'is number' bit mask
if (chr == '[') return 1; // escape = "\x1b["
break;
case 2:
switch (chr)
{
case '2': return 1; // escape = "\x1b[2"
case '?': return 1; // escape = "\x1b[?"
default:
if (chr_is_num) return 1; // escape = "\x1b[%1d"
}
break;
case 3:
switch (_escape[2])
{
case '?': // escape = "\x1b[?"
if (chr == '2') return 1; // escape = "\x1b[?2"
break;
case '2':
if (chr == 'J') // escape = "\x1b[2J"
{ clear(); _currline = 0; break; } // EraseScreen
default:
if (e_2_is_num && // escape = "\x1b[%1d"
((chr == ';') || // escape = "\x1b[%1d;"
chr_is_num)) // escape = "\x1b[%2d"
return 1;
}
break;
case 4:
switch (_escape[2])
{
case '?': // "\x1b[?"
if ((_escape[3] == '2') && (chr == '5')) return 1; // escape = "\x1b[?25"
break;
default:
if (e_2_is_num) // escape = "\x1b[%1d"
{
if ((_escape[3] == ';') && chr_is_num) return 1; // escape = "\x1b[%1d;%1d"
else if (e_3_is_num && (chr == ';')) return 1; // escape = "\x1b[%2d;"
}
}
break;
case 5:
switch (_escape[2])
{
case '?':
if ((_escape[3] == '2') && (_escape[4] == '5')) // escape = "\x1b[?25"
switch (chr)
{
case 'h': // escape = "\x1b[?25h"
void cursor(); // CursorShow
break;
case 'l': // escape = "\x1b[?25l"
noCursor(); // CursorHide
break;
}
break;
default:
if (e_2_is_num) // escape = "\x1b[%1d"
{
if ((_escape[3] == ';') && e_4_is_num) // escape = "\x1b%1d;%1dH"
{
if (chr == 'H') // escape = "\x1b%1d;%1dH"
setCursor(e4_num, e2_num); // CursorHome
else if (chr_is_num)
return 1; // escape = "\x1b%1d;%2d"
}
else if (e_3_is_num && (_escape[4] == ';') && chr_is_num)
return 1; // escape = "\x1b%2d;%1d"
}
}
break;
case 6:
if (e_2_is_num) // escape = "\x1b[%1d"
{
if ((_escape[3] == ';') && e_4_is_num && e_5_is_num && (chr == 'H')) // escape = "\x1b%1d;%2dH"
setCursor(e45_num, e2_num); // CursorHome
else if (e_3_is_num && (_escape[4] == ';') && e_5_is_num) // escape = "\x1b%2d;%1d"
{
if (chr == 'H') // escape = "\x1b%2d;%1dH"
setCursor(e5_num, e23_num); // CursorHome
else if (chr_is_num) // "\x1b%2d;%2d"
return 1;
}
}
break;
case 7:
if (e_2_is_num && e_3_is_num && (_escape[4] == ';')) // "\x1b[%2d;"
if (e_5_is_num && e_6_is_num && (chr == 'H')) // "\x1b[%2d;%2dH"
setCursor(e56_num, e23_num); // CursorHome
break;
}
escape_cnt = 0; // reset escape
end:
return 1; // assume sucess
}
/************ low level data pushing commands **********/
// write either command or data, with automatic 4/8-bit selection
void LiquidCrystal_Prusa::send(uint8_t value, uint8_t mode) {
digitalWrite(_rs_pin, mode);
// if there is a RW pin indicated, set it low to Write
if (_rw_pin != 255) {
digitalWrite(_rw_pin, LOW);
}
if (_displayfunction & LCD_8BITMODE) {
write8bits(value);
} else {
write4bits(value>>4);
write4bits(value);
}
}
void LiquidCrystal_Prusa::pulseEnable(void) {
digitalWrite(_enable_pin, LOW);
delayMicroseconds(1);
digitalWrite(_enable_pin, HIGH);
delayMicroseconds(1); // enable pulse must be >450ns
digitalWrite(_enable_pin, LOW);
delayMicroseconds(100); // commands need > 37us to settle
}
void LiquidCrystal_Prusa::write4bits(uint8_t value) {
for (int i = 0; i < 4; i++) {
pinMode(_data_pins[i], OUTPUT);
digitalWrite(_data_pins[i], (value >> i) & 0x01);
}
pulseEnable();
}
void LiquidCrystal_Prusa::write8bits(uint8_t value) {
for (int i = 0; i < 8; i++) {
pinMode(_data_pins[i], OUTPUT);
digitalWrite(_data_pins[i], (value >> i) & 0x01);
}
pulseEnable();
}
void LiquidCrystal_Prusa::print(const char* s)
{
while (*s) write(*(s++));
}
void LiquidCrystal_Prusa::print(char c, int base)
{
print((long) c, base);
}
void LiquidCrystal_Prusa::print(unsigned char b, int base)
{
print((unsigned long) b, base);
}
void LiquidCrystal_Prusa::print(int n, int base)
{
print((long) n, base);
}
void LiquidCrystal_Prusa::print(unsigned int n, int base)
{
print((unsigned long) n, base);
}
void LiquidCrystal_Prusa::print(long n, int base)
{
if (base == 0) {
write(n);
} else if (base == 10) {
if (n < 0) {
print('-');
n = -n;
}
printNumber(n, 10);
} else {
printNumber(n, base);
}
}
void LiquidCrystal_Prusa::print(unsigned long n, int base)
{
if (base == 0) write(n);
else printNumber(n, base);
}
void LiquidCrystal_Prusa::print(double n, int digits)
{
printFloat(n, digits);
}
void LiquidCrystal_Prusa::println(void)
{
print('\r');
print('\n');
}
/*void LiquidCrystal_Prusa::println(const String &s)
{
print(s);
println();
}*/
void LiquidCrystal_Prusa::println(const char c[])
{
print(c);
println();
}
void LiquidCrystal_Prusa::println(char c, int base)
{
print(c, base);
println();
}
void LiquidCrystal_Prusa::println(unsigned char b, int base)
{
print(b, base);
println();
}
void LiquidCrystal_Prusa::println(int n, int base)
{
print(n, base);
println();
}
void LiquidCrystal_Prusa::println(unsigned int n, int base)
{
print(n, base);
println();
}
void LiquidCrystal_Prusa::println(long n, int base)
{
print(n, base);
println();
}
void LiquidCrystal_Prusa::println(unsigned long n, int base)
{
print(n, base);
println();
}
void LiquidCrystal_Prusa::println(double n, int digits)
{
print(n, digits);
println();
}
void LiquidCrystal_Prusa::printNumber(unsigned long n, uint8_t base)
{
unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars.
unsigned long i = 0;
if (n == 0) {
print('0');
return;
}
while (n > 0) {
buf[i++] = n % base;
n /= base;
}
for (; i > 0; i--)
print((char) (buf[i - 1] < 10 ?
'0' + buf[i - 1] :
'A' + buf[i - 1] - 10));
}
void LiquidCrystal_Prusa::printFloat(double number, uint8_t digits)
{
// Handle negative numbers
if (number < 0.0)
{
print('-');
number = -number;
}
// Round correctly so that print(1.999, 2) prints as "2.00"
double rounding = 0.5;
for (uint8_t i=0; i<digits; ++i)
rounding /= 10.0;
number += rounding;
// Extract the integer part of the number and print it
unsigned long int_part = (unsigned long)number;
double remainder = number - (double)int_part;
print(int_part);
// Print the decimal point, but only if there are digits beyond
if (digits > 0)
print(".");
// Extract digits from the remainder one at a time
while (digits-- > 0)
{
remainder *= 10.0;
int toPrint = int(remainder);
print(toPrint);
remainder -= toPrint;
}
}

View file

@ -1,142 +0,0 @@
#ifndef LiquidCrystal_Prusa_h
#define LiquidCrystal_Prusa_h
#include <inttypes.h>
#include <stddef.h>
//#include "Print.h"
// commands
#define LCD_CLEARDISPLAY 0x01
#define LCD_RETURNHOME 0x02
#define LCD_ENTRYMODESET 0x04
#define LCD_DISPLAYCONTROL 0x08
#define LCD_CURSORSHIFT 0x10
#define LCD_FUNCTIONSET 0x20
#define LCD_SETCGRAMADDR 0x40
#define LCD_SETDDRAMADDR 0x80
// flags for display entry mode
#define LCD_ENTRYRIGHT 0x00
#define LCD_ENTRYLEFT 0x02
#define LCD_ENTRYSHIFTINCREMENT 0x01
#define LCD_ENTRYSHIFTDECREMENT 0x00
// flags for display on/off control
#define LCD_DISPLAYON 0x04
#define LCD_DISPLAYOFF 0x00
#define LCD_CURSORON 0x02
#define LCD_CURSOROFF 0x00
#define LCD_BLINKON 0x01
#define LCD_BLINKOFF 0x00
// flags for display/cursor shift
#define LCD_DISPLAYMOVE 0x08
#define LCD_CURSORMOVE 0x00
#define LCD_MOVERIGHT 0x04
#define LCD_MOVELEFT 0x00
// flags for function set
#define LCD_8BITMODE 0x10
#define LCD_4BITMODE 0x00
#define LCD_2LINE 0x08
#define LCD_1LINE 0x00
#define LCD_5x10DOTS 0x04
#define LCD_5x8DOTS 0x00
class LiquidCrystal_Prusa/* : public Print */{
public:
LiquidCrystal_Prusa(uint8_t rs, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7);
LiquidCrystal_Prusa(uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7);
LiquidCrystal_Prusa(uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3);
LiquidCrystal_Prusa(uint8_t rs, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3);
void init(uint8_t fourbitmode, uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7);
void begin(uint8_t cols, uint8_t rows, uint8_t charsize = LCD_5x8DOTS);
void begin_noclear(uint8_t cols, uint8_t rows, uint8_t charsize = LCD_5x8DOTS);
void clear();
void home();
void noDisplay();
void display();
void noBlink();
void blink();
void noCursor();
void cursor();
void scrollDisplayLeft();
void scrollDisplayRight();
void leftToRight();
void rightToLeft();
void autoscroll();
void noAutoscroll();
void createChar(uint8_t, uint8_t[]);
void setCursor(uint8_t, uint8_t);
// virtual size_t write(uint8_t);
size_t write(uint8_t);
void command(uint8_t);
void print(const char*);
void print(char, int = 0);
void print(unsigned char, int = 0);
void print(int, int = 10);
void print(unsigned int, int = 10);
void print(long, int = 10);
void print(unsigned long, int = 10);
void print(double, int = 2);
// void println(const String &s);
void println(const char[]);
void println(char, int = 0);
void println(unsigned char, int = 0);
void println(int, int = 10);
void println(unsigned int, int = 10);
void println(long, int = 10);
void println(unsigned long, int = 10);
void println(double, int = 2);
void println(void);
void printNumber(unsigned long n, uint8_t base);
void printFloat(double number, uint8_t digits);
// using Print::write;
private:
void send(uint8_t, uint8_t);
void write4bits(uint8_t);
void write8bits(uint8_t);
void pulseEnable();
uint8_t _rs_pin; // LOW: command. HIGH: character.
uint8_t _rw_pin; // LOW: write to LCD. HIGH: read from LCD.
uint8_t _enable_pin; // activated by a HIGH pulse.
uint8_t _data_pins[8];
uint8_t _displayfunction;
uint8_t _displaycontrol;
uint8_t _displaymode;
uint8_t _initialized;
uint8_t _numlines,_currline;
uint8_t _escape[8];
size_t escape_write(uint8_t value);
};
#define ESC_2J "\x1b[2J"
#define ESC_25h "\x1b[?25h"
#define ESC_25l "\x1b[?25l"
#define ESC_H(c,r) "\x1b["#r";"#c"H"
#endif

View file

@ -62,8 +62,7 @@
#define MYSERIAL MSerial
#endif
extern FILE _lcdout;
#define lcdout (&_lcdout)
#include "lcd.h"
extern FILE _uartout;
#define uartout (&_uartout)
@ -456,7 +455,9 @@ void force_high_power_mode(bool start_high_power_section);
#endif //TMC2130
// G-codes
void gcode_G28(bool home_x, bool home_y, bool home_z, bool calib);
void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_y_value, bool home_z_axis, long home_z_value, bool calib, bool without_mbl);
void gcode_G28(bool home_x_axis, bool home_y_axis, bool home_z_axis);
bool gcode_M45(bool onlyZ, int8_t verbosity_level);
void gcode_M114();
void gcode_M701();

View file

@ -58,8 +58,10 @@
#endif
#include "printers.h"
#include "menu.h"
#include "ultralcd.h"
#include "Configuration_prusa.h"
#include "planner.h"
#include "stepper.h"
#include "temperature.h"
@ -167,7 +169,7 @@
// G92 - Set current position to coordinates given
// M Codes
// M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
// M0 - Unconditional stop - Wait for user to press a button on the LCD
// M1 - Same as M0
// M17 - Enable/Power all stepper motors
// M18 - Disable all stepper motors; same as M84
@ -431,13 +433,11 @@ int fanSpeed=0;
float retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE;
#endif
#ifdef ULTIPANEL
#ifdef PS_DEFAULT_OFF
bool powersupply = false;
#else
bool powersupply = true;
#endif
#endif
bool cancel_heatup = false ;
@ -716,7 +716,7 @@ void crashdet_detected(uint8_t mask)
}
lcd_update_enable(true);
lcd_implementation_clear();
lcd_clear();
lcd_update(2);
if (mask & X_AXIS_MASK)
@ -735,7 +735,7 @@ void crashdet_detected(uint8_t mask)
lcd_update_enable(true);
lcd_update(2);
lcd_setstatuspgm(_T(MSG_CRASH_DETECTED));
gcode_G28(true, true, false, false); //home X and Y
gcode_G28(true, true, false); //home X and Y
st_synchronize();
if (automatic_recovery_after_crash) {
@ -801,7 +801,7 @@ void failstats_reset_print()
int er_progress = 0;
void factory_reset(char level, bool quiet)
{
lcd_implementation_clear();
lcd_clear();
int cursor_pos = 0;
switch (level) {
@ -837,8 +837,8 @@ void factory_reset(char level, bool quiet)
// Level 2: Prepare for shipping
case 2:
//lcd_printPGM(PSTR("Factory RESET"));
//lcd_print_at_PGM(1,2,PSTR("Shipping prep"));
//lcd_puts_P(PSTR("Factory RESET"));
//lcd_puts_at_P(1,2,PSTR("Shipping prep"));
// Force language selection at the next boot up.
lang_reset();
@ -849,6 +849,16 @@ void factory_reset(char level, bool quiet)
farm_mode = false;
eeprom_update_byte((uint8_t*)EEPROM_FARM_MODE, farm_mode);
EEPROM_save_B(EEPROM_FARM_NUMBER, &farm_no);
eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, 0);
eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, 0);
eeprom_update_word((uint16_t *)EEPROM_CRASH_COUNT_X_TOT, 0);
eeprom_update_word((uint16_t *)EEPROM_CRASH_COUNT_Y_TOT, 0);
eeprom_update_word((uint16_t *)EEPROM_FERROR_COUNT_TOT, 0);
eeprom_update_word((uint16_t *)EEPROM_POWER_COUNT_TOT, 0);
fsensor_enable();
fautoload_set(true);
WRITE(BEEPER, HIGH);
_delay_ms(100);
@ -859,16 +869,17 @@ void factory_reset(char level, bool quiet)
// Level 3: erase everything, whole EEPROM will be set to 0xFF
case 3:
lcd_printPGM(PSTR("Factory RESET"));
lcd_print_at_PGM(1, 2, PSTR("ERASING all data"));
lcd_puts_P(PSTR("Factory RESET"));
lcd_puts_at_P(1, 2, PSTR("ERASING all data"));
WRITE(BEEPER, HIGH);
_delay_ms(100);
WRITE(BEEPER, LOW);
er_progress = 0;
lcd_print_at_PGM(3, 3, PSTR(" "));
lcd_implementation_print_at(3, 3, er_progress);
lcd_puts_at_P(3, 3, PSTR(" "));
lcd_set_cursor(3, 3);
lcd_print(er_progress);
// Erase EEPROM
for (int i = 0; i < 4096; i++) {
@ -876,9 +887,10 @@ void factory_reset(char level, bool quiet)
if (i % 41 == 0) {
er_progress++;
lcd_print_at_PGM(3, 3, PSTR(" "));
lcd_implementation_print_at(3, 3, er_progress);
lcd_printPGM(PSTR("%"));
lcd_puts_at_P(3, 3, PSTR(" "));
lcd_set_cursor(3, 3);
lcd_print(er_progress);
lcd_puts_P(PSTR("%"));
}
}
@ -895,16 +907,7 @@ void factory_reset(char level, bool quiet)
}
#include "LiquidCrystal_Prusa.h"
extern LiquidCrystal_Prusa lcd;
FILE _lcdout = {0};
int lcd_putchar(char c, FILE *stream)
{
lcd.write(c);
return 0;
}
FILE _uartout = {0};
@ -917,9 +920,9 @@ int uart_putchar(char c, FILE *stream)
void lcd_splash()
{
// lcd_print_at_PGM(0, 1, PSTR(" Original Prusa "));
// lcd_print_at_PGM(0, 2, PSTR(" 3D Printers "));
// lcd.print_P(PSTR("\x1b[1;3HOriginal Prusa\x1b[2;4H3D Printers"));
// lcd_puts_at_P(0, 1, PSTR(" Original Prusa "));
// lcd_puts_at_P(0, 2, PSTR(" 3D Printers "));
// lcd_puts_P(PSTR("\x1b[1;3HOriginal Prusa\x1b[2;4H3D Printers"));
// fputs_P(PSTR(ESC_2J ESC_H(1,1) "Original Prusa i3" ESC_H(3,2) "Prusa Research"), lcdout);
lcd_puts_P(PSTR(ESC_2J ESC_H(1,1) "Original Prusa i3" ESC_H(3,2) "Prusa Research"));
// lcd_printf_P(_N(ESC_2J "x:%.3f\ny:%.3f\nz:%.3f\ne:%.3f"), _x, _y, _z, _e);
@ -934,10 +937,10 @@ void factory_reset()
_delay_ms(1000);
if (!READ(BTN_ENC))
{
lcd_implementation_clear();
lcd_clear();
lcd_printPGM(PSTR("Factory RESET"));
lcd_puts_P(PSTR("Factory RESET"));
SET_OUTPUT(BEEPER);
@ -1007,15 +1010,15 @@ void show_fw_version_warnings() {
case(FW_VERSION_DEVEL):
case(FW_VERSION_DEBUG):
lcd_update_enable(false);
lcd_implementation_clear();
lcd_clear();
#if FW_DEV_VERSION == FW_VERSION_DEVEL
lcd_print_at_PGM(0, 0, PSTR("Development build !!"));
lcd_puts_at_P(0, 0, PSTR("Development build !!"));
#else
lcd_print_at_PGM(0, 0, PSTR("Debbugging build !!!"));
lcd_puts_at_P(0, 0, PSTR("Debbugging build !!!"));
#endif
lcd_print_at_PGM(0, 1, PSTR("May destroy printer!"));
lcd_print_at_PGM(0, 2, PSTR("ver ")); lcd_printPGM(PSTR(FW_VERSION_FULL));
lcd_print_at_PGM(0, 3, PSTR(FW_REPOSITORY));
lcd_puts_at_P(0, 1, PSTR("May destroy printer!"));
lcd_puts_at_P(0, 2, PSTR("ver ")); lcd_puts_P(PSTR(FW_VERSION_FULL));
lcd_puts_at_P(0, 3, PSTR(FW_REPOSITORY));
lcd_wait_for_click();
break;
// default: lcd_show_fullscreen_message_and_wait_P(_i("WARNING: This is an unofficial, unsupported build. Use at your own risk!")); break;////MSG_FW_VERSION_UNKNOWN c=20 r=8
@ -1143,17 +1146,17 @@ void list_sec_lang_from_external_flash()
// are initialized by the main() routine provided by the Arduino framework.
void setup()
{
#ifdef W25X20CL
// Enter an STK500 compatible Optiboot boot loader waiting for flashing the languages to an external flash memory.
optiboot_w25x20cl_enter();
#endif
lcd_init();
fdev_setup_stream(lcdout, lcd_putchar, NULL, _FDEV_SETUP_WRITE); //setup lcdout stream
ultralcd_init();
spi_init();
lcd_splash();
#ifdef W25X20CL
// Enter an STK500 compatible Optiboot boot loader waiting for flashing the languages to an external flash memory.
// optiboot_w25x20cl_enter();
#endif
#if (LANG_MODE != 0) //secondary language support
#ifdef W25X20CL
if (w25x20cl_init())
@ -1696,7 +1699,7 @@ void setup()
KEEPALIVE_STATE(IN_PROCESS);
#endif //DEBUG_DISABLE_STARTMSGS
lcd_update_enable(true);
lcd_implementation_clear();
lcd_clear();
lcd_update(2);
// Store the currently running firmware into an eeprom,
// so the next time the firmware gets updated, it will know from which version it has been updated.
@ -1810,8 +1813,8 @@ int serial_read_stream() {
setTargetHotend(0, 0);
setTargetBed(0);
lcd_implementation_clear();
lcd_printPGM(PSTR(" Upload in progress"));
lcd_clear();
lcd_puts_P(PSTR(" Upload in progress"));
// first wait for how many bytes we will receive
uint32_t bytesToReceive;
@ -2011,7 +2014,7 @@ void loop()
manage_heater();
isPrintPaused ? manage_inactivity(true) : manage_inactivity(false);
checkHitEndstops();
lcd_update();
lcd_update(0);
#ifdef PAT9125
fsensor_update();
#endif //PAT9125
@ -2269,8 +2272,8 @@ bool check_commands() {
bool calibrate_z_auto()
{
//lcd_display_message_fullscreen_P(_T(MSG_CALIBRATE_Z_AUTO));
lcd_implementation_clear();
lcd_print_at_PGM(0,1, _T(MSG_CALIBRATE_Z_AUTO));
lcd_clear();
lcd_puts_at_P(0,1, _T(MSG_CALIBRATE_Z_AUTO));
bool endstops_enabled = enable_endstops(true);
int axis_up_dir = -home_dir(Z_AXIS);
tmc2130_home_enter(Z_AXIS_MASK);
@ -2606,7 +2609,11 @@ void force_high_power_mode(bool start_high_power_section) {
}
#endif //TMC2130
void gcode_G28(bool home_x, bool home_y, bool home_z, bool calib) {
void gcode_G28(bool home_x_axis, bool home_y_axis, bool home_z_axis) {
gcode_G28(home_x_axis, 0, home_y_axis, 0, home_z_axis, 0, false, true);
}
void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_y_value, bool home_z_axis, long home_z_value, bool calib, bool without_mbl) {
st_synchronize();
#if 0
@ -2617,6 +2624,11 @@ void gcode_G28(bool home_x, bool home_y, bool home_z, bool calib) {
// Flag for the display update routine and to disable the print cancelation during homing.
homing_flag = true;
// Which axes should be homed?
bool home_x = home_x_axis;
bool home_y = home_y_axis;
bool home_z = home_z_axis;
// Either all X,Y,Z codes are present, or none of them.
bool home_all_axes = home_x == home_y && home_x == home_z;
if (home_all_axes)
@ -2725,11 +2737,11 @@ void gcode_G28(bool home_x, bool home_y, bool home_z, bool calib) {
#endif //TMC2130
if(code_seen(axis_codes[X_AXIS]) && code_value_long() != 0)
current_position[X_AXIS]=code_value()+add_homing[X_AXIS];
if(home_x_axis && home_x_value != 0)
current_position[X_AXIS]=home_x_value+add_homing[X_AXIS];
if(code_seen(axis_codes[Y_AXIS]) && code_value_long() != 0)
current_position[Y_AXIS]=code_value()+add_homing[Y_AXIS];
if(home_y_axis && home_y_value != 0)
current_position[Y_AXIS]=home_y_value+add_homing[Y_AXIS];
#if Z_HOME_DIR < 0 // If homing towards BED do Z last
#ifndef Z_SAFE_HOMING
@ -2824,8 +2836,8 @@ void gcode_G28(bool home_x, bool home_y, bool home_z, bool calib) {
#endif // Z_SAFE_HOMING
#endif // Z_HOME_DIR < 0
if(code_seen(axis_codes[Z_AXIS]) && code_value_long() != 0)
current_position[Z_AXIS]=code_value()+add_homing[Z_AXIS];
if(home_z_axis && home_z_value != 0)
current_position[Z_AXIS]=home_z_value+add_homing[Z_AXIS];
#ifdef ENABLE_AUTO_BED_LEVELING
if(home_z)
current_position[Z_AXIS] += zprobe_zoffset; //Add Z_Probe offset (the distance is negative)
@ -2857,7 +2869,7 @@ void gcode_G28(bool home_x, bool home_y, bool home_z, bool calib) {
world2machine_update_current();
#if (defined(MESH_BED_LEVELING) && !defined(MK1BP))
if (code_seen(axis_codes[X_AXIS]) || code_seen(axis_codes[Y_AXIS]) || code_seen('W') || code_seen(axis_codes[Z_AXIS]))
if (home_x_axis || home_y_axis || without_mbl || home_z_axis)
{
if (! home_z && mbl_was_active) {
// Re-enable the mesh bed leveling if only the X and Y axes were re-homed.
@ -2870,10 +2882,6 @@ void gcode_G28(bool home_x, bool home_y, bool home_z, bool calib) {
{
st_synchronize();
homing_flag = false;
// Push the commands to the front of the message queue in the reverse order!
// There shall be always enough space reserved for these commands.
enquecommand_front_P((PSTR("G80")));
//goto case_G80;
}
#endif
@ -2955,8 +2963,9 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
lcd_show_fullscreen_message_and_wait_P(_T(MSG_PAPER));
KEEPALIVE_STATE(IN_HANDLER);
lcd_display_message_fullscreen_P(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1));
lcd_implementation_print_at(0, 2, 1);
lcd_printPGM(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));
lcd_set_cursor(0, 2);
lcd_print(1);
lcd_puts_P(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));
}
// Move the print head close to the bed.
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
@ -3106,10 +3115,17 @@ void gcode_M701()
custom_message = true;
custom_message_type = 2;
lcd_setstatuspgm(_T(MSG_LOADING_FILAMENT));
current_position[E_AXIS] += 70;
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder); //fast sequence
lcd_setstatuspgm(_T(MSG_LOADING_FILAMENT));
current_position[E_AXIS] += 40;
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder); //fast sequence
st_synchronize();
if (current_position[Z_AXIS] < 20) current_position[Z_AXIS] += 30;
current_position[E_AXIS] += 30;
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder); //fast sequence
st_synchronize();
current_position[E_AXIS] += 25;
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 100 / 60, active_extruder); //slow sequence
st_synchronize();
@ -3190,6 +3206,13 @@ static void gcode_PRUSA_SN()
}
}
#ifdef BACKLASH_X
extern uint8_t st_backlash_x;
#endif //BACKLASH_X
#ifdef BACKLASH_Y
extern uint8_t st_backlash_y;
#endif //BACKLASH_Y
void process_commands()
{
if (!buflen) return; //empty command
@ -3245,18 +3268,77 @@ void process_commands()
}
else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("TMC_"), 4) == 0)
{
if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_WAVE_E"), 10) == 0)
if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_WAVE_"), 9) == 0)
{
uint8_t fac = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 14, NULL, 10);
tmc2130_set_wave(E_AXIS, 247, fac);
uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13);
axis = (axis == 'E')?3:(axis - 'X');
if (axis < 4)
{
uint8_t fac = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 14, NULL, 10);
tmc2130_set_wave(axis, 247, fac);
}
}
else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_STEP_E"), 10) == 0)
else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_STEP_"), 9) == 0)
{
uint8_t step = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 14, NULL, 10);
uint16_t res = tmc2130_get_res(E_AXIS);
tmc2130_goto_step(E_AXIS, step & (4*res - 1), 2, 1000, res);
uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13);
axis = (axis == 'E')?3:(axis - 'X');
if (axis < 4)
{
uint8_t step = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 14, NULL, 10);
uint16_t res = tmc2130_get_res(axis);
tmc2130_goto_step(axis, step & (4*res - 1), 2, 1000, res);
}
}
else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_CHOP_"), 9) == 0)
{
uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13);
axis = (axis == 'E')?3:(axis - 'X');
if (axis < 4)
{
uint8_t chop0 = tmc2130_chopper_config[axis].toff;
uint8_t chop1 = tmc2130_chopper_config[axis].hstr;
uint8_t chop2 = tmc2130_chopper_config[axis].hend;
uint8_t chop3 = tmc2130_chopper_config[axis].tbl;
char* str_end = 0;
if (CMDBUFFER_CURRENT_STRING[14])
{
chop0 = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 14, &str_end, 10) & 15;
if (str_end && *str_end)
{
chop1 = (uint8_t)strtol(str_end, &str_end, 10) & 7;
if (str_end && *str_end)
{
chop2 = (uint8_t)strtol(str_end, &str_end, 10) & 15;
if (str_end && *str_end)
chop3 = (uint8_t)strtol(str_end, &str_end, 10) & 3;
}
}
}
tmc2130_chopper_config[axis].toff = chop0;
tmc2130_chopper_config[axis].hstr = chop1 & 7;
tmc2130_chopper_config[axis].hend = chop2 & 15;
tmc2130_chopper_config[axis].tbl = chop3 & 3;
tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]);
//printf_P(_N("TMC_SET_CHOP_%c %hhd %hhd %hhd %hhd\n"), "xyze"[axis], chop0, chop1, chop2, chop3);
}
}
}
#ifdef BACKLASH_X
else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("BACKLASH_X"), 10) == 0)
{
uint8_t bl = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 10, NULL, 10);
st_backlash_x = bl;
printf_P(_N("st_backlash_x = %hhd\n"), st_backlash_x);
}
#endif //BACKLASH_X
#ifdef BACKLASH_Y
else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("BACKLASH_Y"), 10) == 0)
{
uint8_t bl = (uint8_t)strtol(CMDBUFFER_CURRENT_STRING + 10, NULL, 10);
st_backlash_y = bl;
printf_P(_N("st_backlash_y = %hhd\n"), st_backlash_y);
}
#endif //BACKLASH_Y
#endif //TMC2130
else if(code_seen("PRUSA")){
@ -3286,6 +3368,8 @@ void process_commands()
// careful!
if (farm_mode) {
#ifdef WATCHDOG
boot_app_magic = BOOT_APP_MAGIC;
boot_app_flags = BOOT_APP_FLG_RUN;
wdt_enable(WDTO_15MS);
cli();
while(1);
@ -3410,7 +3494,7 @@ void process_commands()
cnt++;
manage_heater();
manage_inactivity(true);
//lcd_update();
//lcd_update(0);
if(cnt==0)
{
#if BEEPER > 0
@ -3435,11 +3519,6 @@ void process_commands()
counterBeep++;
#else
#if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
lcd_buzz(1000/6,100);
#else
lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS,LCD_FEEDBACK_FREQUENCY_HZ);
#endif
#endif
}
}
@ -3576,7 +3655,7 @@ void process_commands()
while(millis() < codenum) {
manage_heater();
manage_inactivity();
lcd_update();
lcd_update(0);
}
break;
#ifdef FWRETRACT
@ -3598,16 +3677,26 @@ void process_commands()
#endif //FWRETRACT
case 28: //G28 Home all Axis one at a time
{
long home_x_value = 0;
long home_y_value = 0;
long home_z_value = 0;
// Which axes should be homed?
bool home_x = code_seen(axis_codes[X_AXIS]);
home_x_value = code_value_long();
bool home_y = code_seen(axis_codes[Y_AXIS]);
home_y_value = code_value_long();
bool home_z = code_seen(axis_codes[Z_AXIS]);
home_z_value = code_value_long();
bool without_mbl = code_seen('W');
// calibrate?
bool calib = code_seen('C');
gcode_G28(home_x, home_y, home_z, calib);
break;
gcode_G28(home_x, home_x_value, home_y, home_y_value, home_z, home_z_value, calib, without_mbl);
if ((home_x || home_y || without_mbl || home_z) == false) {
// Push the commands to the front of the message queue in the reverse order!
// There shall be always enough space reserved for these commands.
goto case_G80;
}
break;
}
#ifdef ENABLE_AUTO_BED_LEVELING
case 29: // G29 Detailed Z-Probe, probes the bed at 3 or more points.
@ -3847,7 +3936,7 @@ void process_commands()
current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
st_synchronize();
gcode_G28(false, false, true, false);
gcode_G28(false, false, true);
}
if ((current_temperature_pinda > 35) && (farm_mode == false)) {
@ -4586,7 +4675,6 @@ void process_commands()
} else
switch((int)code_value())
{
#ifdef ULTIPANEL
case 0: // M0 - Unconditional stop - Wait for user button press on LCD
case 1: // M1 - Conditional stop - Wait for user button press on LCD
@ -4622,18 +4710,16 @@ void process_commands()
while(millis() < codenum && !lcd_clicked()){
manage_heater();
manage_inactivity(true);
lcd_update();
lcd_update(0);
}
KEEPALIVE_STATE(IN_HANDLER);
lcd_ignore_click(false);
}else{
if (!lcd_detected())
break;
KEEPALIVE_STATE(PAUSED_FOR_USER);
while(!lcd_clicked()){
manage_heater();
manage_inactivity(true);
lcd_update();
lcd_update(0);
}
KEEPALIVE_STATE(IN_HANDLER);
}
@ -4643,7 +4729,6 @@ void process_commands()
LCD_MESSAGERPGM(_T(WELCOME_MSG));
}
break;
#endif
case 17:
LCD_MESSAGERPGM(_i("No move."));////MSG_NO_MOVE c=0 r=0
enable_x();
@ -4656,9 +4741,9 @@ void process_commands()
#ifdef SDSUPPORT
case 20: // M20 - list SD card
SERIAL_PROTOCOLLNRPGM(_i("Begin file list"));////MSG_BEGIN_FILE_LIST c=0 r=0
SERIAL_PROTOCOLLNRPGM(_N("Begin file list"));////MSG_BEGIN_FILE_LIST c=0 r=0
card.ls();
SERIAL_PROTOCOLLNRPGM(_i("End file list"));////MSG_END_FILE_LIST c=0 r=0
SERIAL_PROTOCOLLNRPGM(_N("End file list"));////MSG_END_FILE_LIST c=0 r=0
break;
case 21: // M21 - init SD card
@ -5365,7 +5450,7 @@ Sigma_Exit:
}
manage_heater();
manage_inactivity();
lcd_update();
lcd_update(0);
}
LCD_MESSAGERPGM(_T(MSG_BED_DONE));
KEEPALIVE_STATE(IN_HANDLER);
@ -5402,11 +5487,9 @@ Sigma_Exit:
WRITE(SUICIDE_PIN, HIGH);
#endif
#ifdef ULTIPANEL
powersupply = true;
LCD_MESSAGERPGM(_T(WELCOME_MSG));
lcd_update();
#endif
lcd_update(0);
break;
#endif
@ -5426,11 +5509,9 @@ Sigma_Exit:
SET_OUTPUT(PS_ON_PIN);
WRITE(PS_ON_PIN, PS_ON_ASLEEP);
#endif
#ifdef ULTIPANEL
powersupply = false;
LCD_MESSAGERPGM(CAT4(CUSTOM_MENDEL_NAME,PSTR(" "),MSG_OFF,PSTR(".")));
lcd_update();
#endif
lcd_update(0);
break;
case 82:
@ -5563,7 +5644,7 @@ Sigma_Exit:
enable_endstops(true) ;
break;
case 119: // M119
SERIAL_PROTOCOLRPGM(_i("Reporting endstop status"));////MSG_M119_REPORT c=0 r=0
SERIAL_PROTOCOLRPGM(_N("Reporting endstop status"));////MSG_M119_REPORT c=0 r=0
SERIAL_PROTOCOLLN("");
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
SERIAL_PROTOCOLRPGM(_n("x_min: "));////MSG_X_MIN c=0 r=0
@ -5890,7 +5971,7 @@ Sigma_Exit:
while(digitalRead(pin_number) != target){
manage_heater();
manage_inactivity();
lcd_update();
lcd_update(0);
}
}
}
@ -5948,10 +6029,6 @@ Sigma_Exit:
tone(BEEPER, beepS);
delay(beepP);
noTone(BEEPER);
#elif defined(ULTRALCD)
lcd_buzz(beepS, beepP);
#elif defined(LCD_USE_I2C_BUZZER)
lcd_buzz(beepP, beepS);
#endif
}
else
@ -6040,18 +6117,6 @@ Sigma_Exit:
#endif //chdk end if
}
break;
#ifdef DOGLCD
case 250: // M250 Set LCD contrast value: C<value> (value 0..63)
{
if (code_seen('C')) {
lcd_setcontrast( ((int)code_value())&63 );
}
SERIAL_PROTOCOLPGM("lcd contrast value: ");
SERIAL_PROTOCOL(lcd_contrast);
SERIAL_PROTOCOLLN("");
}
break;
#endif
#ifdef PREVENT_DANGEROUS_EXTRUDE
case 302: // allow cold extrudes, or set the minimum extrude temperature
{
@ -6278,11 +6343,6 @@ Sigma_Exit:
counterBeep++;
#else
#if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
lcd_buzz(1000 / 6, 100);
#else
lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ);
#endif
#endif
}
@ -6321,8 +6381,8 @@ Sigma_Exit:
}
else {
counterBeep = 20; //beeper will be inactive during waiting for nozzle preheat
lcd.setCursor(1, 4);
lcd.print(ftostr3(degHotend(active_extruder)));
lcd_set_cursor(1, 4);
lcd_print(ftostr3(degHotend(active_extruder)));
}
break;
@ -6680,7 +6740,7 @@ Sigma_Exit:
}
manage_heater();
manage_inactivity();
lcd_update();
lcd_update(0);
}
LCD_MESSAGERPGM(_T(MSG_OK));
@ -7586,13 +7646,13 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s
else
{
lcd_update_enable(false);
lcd_implementation_clear();
lcd.setCursor(0, 0);
lcd_printPGM(_T(MSG_ERROR));
lcd.setCursor(0, 2);
lcd_printPGM(_T(MSG_PREHEAT_NOZZLE));
lcd_clear();
lcd_set_cursor(0, 0);
lcd_puts_P(_T(MSG_ERROR));
lcd_set_cursor(0, 2);
lcd_puts_P(_T(MSG_PREHEAT_NOZZLE));
delay(2000);
lcd_implementation_clear();
lcd_clear();
lcd_update_enable(true);
}
@ -7724,7 +7784,7 @@ void kill(const char *full_screen_message, unsigned char id)
// FMC small patch to update the LCD before ending
sei(); // enable interrupts
for ( int i=5; i--; lcd_update())
for ( int i=5; i--; lcd_update(0))
{
delay(200);
}
@ -7899,7 +7959,7 @@ void delay_keep_alive(unsigned int ms)
manage_heater();
// Manage inactivity, but don't disable steppers on timeout.
manage_inactivity(true);
lcd_update();
lcd_update(0);
if (ms == 0)
break;
else if (ms >= 50) {
@ -7951,7 +8011,7 @@ void wait_for_heater(long codenum) {
}
manage_heater();
manage_inactivity();
lcd_update();
lcd_update(0);
#ifdef TEMP_RESIDENCY_TIME
/* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
or when current temp falls outside the hysteresis after target temp was reached */

View file

@ -1,29 +0,0 @@
/**
* @file
* @author Marek Bel
*/
#include "MenuStack.h"
/**
* @brief Push menu on stack
* @param menu
* @param position selected position in menu being pushed
*/
void MenuStack::push(menuFunc_t menu, int8_t position)
{
if (m_index >= max_depth) return;
m_stack[m_index].menu = menu;
m_stack[m_index].position = position;
++m_index;
}
/**
* @brief Pop menu from stack
* @return Record containing menu function pointer and previously selected line number
*/
MenuStack::Record MenuStack::pop()
{
if (m_index != 0) m_index--;
return m_stack[m_index];
}

View file

@ -1,34 +0,0 @@
/**
* @file
* @author Marek Bel
*/
#ifndef MENUSTACK_H
#define MENUSTACK_H
#include <stdint.h>
/** Pointer to function implementing menu.*/
typedef void (*menuFunc_t)();
/**
* @brief Stack implementation for navigating menu structure
*/
class MenuStack
{
public:
struct Record
{
menuFunc_t menu;
int8_t position;
};
MenuStack():m_stack(),m_index(0) {}
void push(menuFunc_t menu, int8_t position);
Record pop();
void reset(){m_index = 0;}
private:
static const int max_depth = 4;
Record m_stack[max_depth];
uint8_t m_index;
};
#endif /* FIRMWARE_MENUSTACK_H_ */

View file

@ -17,6 +17,7 @@
#define BOOT_APP_FLG_ERASE 0x01
#define BOOT_APP_FLG_COPY 0x02
#define BOOT_APP_FLG_FLASH 0x04
#define BOOT_APP_FLG_RUN 0x08
#define BOOT_APP_FLG_USER0 0x80

View file

@ -392,13 +392,13 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
if (file.open(curDir, fname, O_READ))
{
filesize = file.fileSize();
SERIAL_PROTOCOLRPGM(_i("File opened: "));////MSG_SD_FILE_OPENED c=0 r=0
SERIAL_PROTOCOLRPGM(_N("File opened: "));////MSG_SD_FILE_OPENED c=0 r=0
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLRPGM(_n(" Size: "));////MSG_SD_SIZE c=0 r=0
SERIAL_PROTOCOLLN(filesize);
sdpos = 0;
SERIAL_PROTOCOLLNRPGM(_i("File selected"));////MSG_SD_FILE_SELECTED c=0 r=0
SERIAL_PROTOCOLLNRPGM(_N("File selected"));////MSG_SD_FILE_SELECTED c=0 r=0
getfilename(0, fname);
lcd_setstatus(longFilename[0] ? longFilename : fname);
lcd_setstatus("SD-PRINTING ");
@ -421,7 +421,7 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
else
{
saving = true;
SERIAL_PROTOCOLRPGM(_i("Writing to file: "));////MSG_SD_WRITE_TO_FILE c=0 r=0
SERIAL_PROTOCOLRPGM(_N("Writing to file: "));////MSG_SD_WRITE_TO_FILE c=0 r=0
SERIAL_PROTOCOLLN(name);
lcd_setstatus(fname);
}
@ -513,7 +513,7 @@ void CardReader::getStatus()
if(sdprinting){
SERIAL_PROTOCOL(longFilename);
SERIAL_PROTOCOLPGM("\n");
SERIAL_PROTOCOLRPGM(_i("SD printing byte "));////MSG_SD_PRINTING_BYTE c=0 r=0
SERIAL_PROTOCOLRPGM(_N("SD printing byte "));////MSG_SD_PRINTING_BYTE c=0 r=0
SERIAL_PROTOCOL(sdpos);
SERIAL_PROTOCOLPGM("/");
SERIAL_PROTOCOLLN(filesize);
@ -757,11 +757,11 @@ void CardReader::presort() {
lcd_show_fullscreen_message_and_wait_P(_i("Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."));////MSG_FILE_CNT c=20 r=4
fileCnt = SDSORT_LIMIT;
}
lcd_implementation_clear();
lcd_clear();
#if !SDSORT_USES_RAM
lcd_set_progress();
#endif
lcd_print_at_PGM(0, 1, _i("Sorting files"));////MSG_SORTING c=20 r=1
lcd_puts_at_P(0, 1, _i("Sorting files"));////MSG_SORTING c=20 r=1
// Sort order is always needed. May be static or dynamic.
#if SDSORT_DYNAMIC_RAM
@ -889,7 +889,11 @@ void CardReader::presort() {
#if !SDSORT_USES_RAM //show progresss bar only if slow sorting method is used
int8_t percent = (counter * 100) / total;//((counter * 100) / pow((fileCnt-1),2));
for (int column = 0; column < 20; column++) {
if (column < (percent / 5)) lcd_implementation_print_at(column, 2, "\x01"); //simple progress bar
if (column < (percent / 5))
{
lcd_set_cursor(column, 2);
lcd_print('\x01'); //simple progress bar
}
}
counter++;
#endif
@ -964,11 +968,14 @@ void CardReader::presort() {
sort_count = fileCnt;
}
#if !SDSORT_USES_RAM //show progresss bar only if slow sorting method is used
for (int column = 0; column <= 19; column++) lcd_implementation_print_at(column, 2, "\x01"); //simple progress bar
for (int column = 0; column <= 19; column++)
{
lcd_set_cursor(column, 2);
lcd_print('\x01'); //simple progress bar
}
delay(300);
lcd_set_degree();
lcd_implementation_clear();
lcd_update(2);
lcd_clear();
#endif
lcd_update(2);
KEEPALIVE_STATE(NOT_BUSY);

View file

@ -476,6 +476,7 @@ void get_command()
SERIAL_ERROR_START;
SERIAL_ERRORRPGM(_n("No Line Number with checksum, Last Line: "));////MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM c=0 r=0
SERIAL_ERRORLN(gcode_LastN);
FlushSerialRequestResend();
serial_count = 0;
return;
}

View file

@ -8,6 +8,22 @@
#define ADC_OVRSAMPL 16 //oversampling multiplier
#define ADC_CALLBACK adc_ready //callback function ()
//SWI2C configuration
#define SWI2C
//#define SWI2C_SDA 20 //SDA on P3
//#define SWI2C_SCL 21 //SCL on P3
#define SWI2C_A8
#define SWI2C_DEL 20 //2us clock delay
#define SWI2C_TMO 2048 //2048 cycles timeout
//PAT9125 configuration
#define PAT9125_SWI2C
#define PAT9125_I2C_ADDR 0x75 //ID=LO
//#define PAT9125_I2C_ADDR 0x79 //ID=HI
//#define PAT9125_I2C_ADDR 0x73 //ID=NC
#define PAT9125_XRES 0
#define PAT9125_YRES 200
//SM4 configuration
#define SM4_DEFDELAY 500 //default step delay [us]

292
Firmware/conv2str.cpp Normal file
View file

@ -0,0 +1,292 @@
//conv2str.cpp - Float conversion utilities
#include "conv2str.h"
#include <stdlib.h>
// convert float to string with +123.4 format
char conv[8];
char *ftostr3(const float &x)
{
return itostr3((int)x);
}
char *itostr2(const uint8_t &x)
{
//sprintf(conv,"%5.1f",x);
int xx = x;
conv[0] = (xx / 10) % 10 + '0';
conv[1] = (xx) % 10 + '0';
conv[2] = 0;
return conv;
}
// Convert float to string with 123.4 format, dropping sign
char *ftostr31(const float &x)
{
int xx = x * 10;
conv[0] = (xx >= 0) ? '+' : '-';
xx = abs(xx);
conv[1] = (xx / 1000) % 10 + '0';
conv[2] = (xx / 100) % 10 + '0';
conv[3] = (xx / 10) % 10 + '0';
conv[4] = '.';
conv[5] = (xx) % 10 + '0';
conv[6] = 0;
return conv;
}
// Convert float to string with 123.4 format
char *ftostr31ns(const float &x)
{
int xx = x * 10;
//conv[0]=(xx>=0)?'+':'-';
xx = abs(xx);
conv[0] = (xx / 1000) % 10 + '0';
conv[1] = (xx / 100) % 10 + '0';
conv[2] = (xx / 10) % 10 + '0';
conv[3] = '.';
conv[4] = (xx) % 10 + '0';
conv[5] = 0;
return conv;
}
char *ftostr32(const float &x)
{
long xx = x * 100;
if (xx >= 0)
conv[0] = (xx / 10000) % 10 + '0';
else
conv[0] = '-';
xx = abs(xx);
conv[1] = (xx / 1000) % 10 + '0';
conv[2] = (xx / 100) % 10 + '0';
conv[3] = '.';
conv[4] = (xx / 10) % 10 + '0';
conv[5] = (xx) % 10 + '0';
conv[6] = 0;
return conv;
}
//// Convert float to rj string with 123.45 format
char *ftostr32ns(const float &x) {
long xx = abs(x);
conv[0] = xx >= 10000 ? (xx / 10000) % 10 + '0' : ' ';
conv[1] = xx >= 1000 ? (xx / 1000) % 10 + '0' : ' ';
conv[2] = xx >= 100 ? (xx / 100) % 10 + '0' : '0';
conv[3] = '.';
conv[4] = (xx / 10) % 10 + '0';
conv[5] = xx % 10 + '0';
return conv;
}
// Convert float to string with 1.234 format
char *ftostr43(const float &x, uint8_t offset)
{
const size_t maxOffset = sizeof(conv)/sizeof(conv[0]) - 6;
if (offset>maxOffset) offset = maxOffset;
long xx = x * 1000;
if (xx >= 0)
conv[offset] = (xx / 1000) % 10 + '0';
else
conv[offset] = '-';
xx = abs(xx);
conv[offset + 1] = '.';
conv[offset + 2] = (xx / 100) % 10 + '0';
conv[offset + 3] = (xx / 10) % 10 + '0';
conv[offset + 4] = (xx) % 10 + '0';
conv[offset + 5] = 0;
return conv;
}
//Float to string with 1.23 format
char *ftostr12ns(const float &x)
{
long xx = x * 100;
xx = abs(xx);
conv[0] = (xx / 100) % 10 + '0';
conv[1] = '.';
conv[2] = (xx / 10) % 10 + '0';
conv[3] = (xx) % 10 + '0';
conv[4] = 0;
return conv;
}
//Float to string with 1.234 format
char *ftostr13ns(const float &x)
{
long xx = x * 1000;
if (xx >= 0)
conv[0] = ' ';
else
conv[0] = '-';
xx = abs(xx);
conv[1] = (xx / 1000) % 10 + '0';
conv[2] = '.';
conv[3] = (xx / 100) % 10 + '0';
conv[4] = (xx / 10) % 10 + '0';
conv[5] = (xx) % 10 + '0';
conv[6] = 0;
return conv;
}
// convert float to space-padded string with -_23.4_ format
char *ftostr32sp(const float &x) {
long xx = abs(x * 100);
uint8_t dig;
if (x < 0) { // negative val = -_0
conv[0] = '-';
dig = (xx / 1000) % 10;
conv[1] = dig ? '0' + dig : ' ';
}
else { // positive val = __0
dig = (xx / 10000) % 10;
if (dig) {
conv[0] = '0' + dig;
conv[1] = '0' + (xx / 1000) % 10;
}
else {
conv[0] = ' ';
dig = (xx / 1000) % 10;
conv[1] = dig ? '0' + dig : ' ';
}
}
conv[2] = '0' + (xx / 100) % 10; // lsd always
dig = xx % 10;
if (dig) { // 2 decimal places
conv[5] = '0' + dig;
conv[4] = '0' + (xx / 10) % 10;
conv[3] = '.';
}
else { // 1 or 0 decimal place
dig = (xx / 10) % 10;
if (dig) {
conv[4] = '0' + dig;
conv[3] = '.';
}
else {
conv[3] = conv[4] = ' ';
}
conv[5] = ' ';
}
conv[6] = '\0';
return conv;
}
char *itostr31(const int &xx)
{
conv[0] = (xx >= 0) ? '+' : '-';
conv[1] = (xx / 1000) % 10 + '0';
conv[2] = (xx / 100) % 10 + '0';
conv[3] = (xx / 10) % 10 + '0';
conv[4] = '.';
conv[5] = (xx) % 10 + '0';
conv[6] = 0;
return conv;
}
// Convert int to rj string with 123 or -12 format
char *itostr3(const int &x)
{
int xx = x;
if (xx < 0) {
conv[0] = '-';
xx = -xx;
} else if (xx >= 100)
conv[0] = (xx / 100) % 10 + '0';
else
conv[0] = ' ';
if (xx >= 10)
conv[1] = (xx / 10) % 10 + '0';
else
conv[1] = ' ';
conv[2] = (xx) % 10 + '0';
conv[3] = 0;
return conv;
}
// Convert int to lj string with 123 format
char *itostr3left(const int &xx)
{
if (xx >= 100)
{
conv[0] = (xx / 100) % 10 + '0';
conv[1] = (xx / 10) % 10 + '0';
conv[2] = (xx) % 10 + '0';
conv[3] = 0;
}
else if (xx >= 10)
{
conv[0] = (xx / 10) % 10 + '0';
conv[1] = (xx) % 10 + '0';
conv[2] = 0;
}
else
{
conv[0] = (xx) % 10 + '0';
conv[1] = 0;
}
return conv;
}
// Convert int to rj string with 1234 format
char *itostr4(const int &xx) {
conv[0] = xx >= 1000 ? (xx / 1000) % 10 + '0' : ' ';
conv[1] = xx >= 100 ? (xx / 100) % 10 + '0' : ' ';
conv[2] = xx >= 10 ? (xx / 10) % 10 + '0' : ' ';
conv[3] = xx % 10 + '0';
conv[4] = 0;
return conv;
}
// Convert float to rj string with 12345 format
char *ftostr5(const float &x) {
long xx = abs(x);
conv[0] = xx >= 10000 ? (xx / 10000) % 10 + '0' : ' ';
conv[1] = xx >= 1000 ? (xx / 1000) % 10 + '0' : ' ';
conv[2] = xx >= 100 ? (xx / 100) % 10 + '0' : ' ';
conv[3] = xx >= 10 ? (xx / 10) % 10 + '0' : ' ';
conv[4] = xx % 10 + '0';
conv[5] = 0;
return conv;
}
// Convert float to string with +1234.5 format
char *ftostr51(const float &x)
{
long xx = x * 10;
conv[0] = (xx >= 0) ? '+' : '-';
xx = abs(xx);
conv[1] = (xx / 10000) % 10 + '0';
conv[2] = (xx / 1000) % 10 + '0';
conv[3] = (xx / 100) % 10 + '0';
conv[4] = (xx / 10) % 10 + '0';
conv[5] = '.';
conv[6] = (xx) % 10 + '0';
conv[7] = 0;
return conv;
}
// Convert float to string with +123.45 format
char *ftostr52(const float &x)
{
long xx = x * 100;
conv[0] = (xx >= 0) ? '+' : '-';
xx = abs(xx);
conv[1] = (xx / 10000) % 10 + '0';
conv[2] = (xx / 1000) % 10 + '0';
conv[3] = (xx / 100) % 10 + '0';
conv[4] = '.';
conv[5] = (xx / 10) % 10 + '0';
conv[6] = (xx) % 10 + '0';
conv[7] = 0;
return conv;
}

28
Firmware/conv2str.h Normal file
View file

@ -0,0 +1,28 @@
//conv2str.h - Float conversion utilities
#ifndef _CONV2STR_H
#define _CONV2STR_H
#include <inttypes.h>
char *itostr2(const uint8_t &x);
char *itostr31(const int &xx);
char *itostr3(const int &xx);
char *itostr3left(const int &xx);
char *itostr4(const int &xx);
char *ftostr3(const float &x);
char *ftostr31ns(const float &x); // float to string without sign character
char *ftostr31(const float &x);
char *ftostr32(const float &x);
char *ftostr32ns(const float &x);
char *ftostr43(const float &x, uint8_t offset = 0);
char *ftostr12ns(const float &x);
char *ftostr13ns(const float &x);
char *ftostr32sp(const float &x); // remove zero-padding from ftostr32
char *ftostr5(const float &x);
char *ftostr51(const float &x);
char *ftostr52(const float &x);
#endif //_CONV2STR_H

View file

@ -9,8 +9,6 @@
#include "fastio.h"
#include "cmdqueue.h"
//#include "LiquidCrystal_Prusa.h"
//extern LiquidCrystal_Prusa lcd;
#define FSENSOR_ERR_MAX 5 //filament sensor max error count
@ -86,6 +84,12 @@ void fsensor_disable()
FSensorStateMenu = 0;
}
void fautoload_set(bool State)
{
filament_autoload_enabled = State;
eeprom_update_byte((unsigned char *)EEPROM_FSENS_AUTOLOAD_ENABLED, filament_autoload_enabled);
}
void pciSetup(byte pin)
{
*digitalPinToPCMSK(pin) |= bit (digitalPinToPCMSKbit(pin)); // enable pin

View file

@ -15,6 +15,9 @@ extern void fsensor_unblock();
extern bool fsensor_enable();
extern void fsensor_disable();
extern bool filament_autoload_enabled;
extern void fautoload_set(bool State);
//update (perform M600 on filament runout)
extern void fsensor_update();

1083
Firmware/lcd.cpp Normal file

File diff suppressed because it is too large Load diff

224
Firmware/lcd.h Normal file
View file

@ -0,0 +1,224 @@
//lcd.h
#ifndef _LCD_H
#define _LCD_H
#include <inttypes.h>
#include <stdio.h>
extern FILE _lcdout;
#define lcdout (&_lcdout)
extern int lcd_putchar(char c, FILE *stream);
extern void lcd_init(void);
extern void lcd_refresh(void);
extern void lcd_refresh_noclear(void);
extern void lcd_clear(void);
extern void lcd_home(void);
/*extern void lcd_no_display(void);
extern void lcd_display(void);
extern void lcd_no_blink(void);
extern void lcd_blink(void);
extern void lcd_no_cursor(void);
extern void lcd_cursor(void);
extern void lcd_scrollDisplayLeft(void);
extern void lcd_scrollDisplayRight(void);
extern void lcd_leftToRight(void);
extern void lcd_rightToLeft(void);
extern void lcd_autoscroll(void);
extern void lcd_no_autoscroll(void);*/
extern void lcd_set_cursor(uint8_t col, uint8_t row);
extern void lcd_createChar_P(uint8_t, const uint8_t*);
extern int lcd_putc(int c);
extern int lcd_puts_P(const char* str);
extern int lcd_puts_at_P(uint8_t c, uint8_t r, const char* str);
extern int lcd_printf_P(const char* format, ...);
extern void lcd_printNumber(unsigned long n, uint8_t base);
extern void lcd_printFloat(double number, uint8_t digits);
extern void lcd_print(const char*);
extern void lcd_print(char, int = 0);
extern void lcd_print(unsigned char, int = 0);
extern void lcd_print(int, int = 10);
extern void lcd_print(unsigned int, int = 10);
extern void lcd_print(long, int = 10);
extern void lcd_print(unsigned long, int = 10);
extern void lcd_print(double, int = 2);
#define ESC_2J "\x1b[2J"
#define ESC_25h "\x1b[?25h"
#define ESC_25l "\x1b[?25l"
#define ESC_H(c,r) "\x1b["#r";"#c"H"
#define LCD_UPDATE_INTERVAL 100
#define LCD_TIMEOUT_TO_STATUS 30000
typedef void (*lcd_longpress_func_t)(void);
typedef void (*lcd_charsetup_func_t)(void);
typedef void (*lcd_lcdupdate_func_t)(void);
//Set to none-zero when the LCD needs to draw, decreased after every draw. Set to 2 in LCD routines so the LCD gets at least 1 full redraw (first redraw is partial)
extern uint8_t lcd_draw_update;
extern int32_t lcd_encoder;
extern uint8_t lcd_encoder_bits;
// lcd_encoder_diff is updated from interrupt context and added to lcd_encoder every LCD update
extern int8_t lcd_encoder_diff;
//the last checked lcd_buttons in a bit array.
extern uint8_t lcd_buttons;
extern uint8_t lcd_button_pressed;
extern uint8_t lcd_update_enabled;
extern uint32_t lcd_timeoutToStatus;
extern uint32_t lcd_next_update_millis;
extern uint8_t lcd_status_update_delay;
extern uint8_t lcd_long_press_active;
extern lcd_longpress_func_t lcd_longpress_func;
extern lcd_charsetup_func_t lcd_charsetup_func;
extern lcd_lcdupdate_func_t lcd_lcdupdate_func;
extern uint8_t lcd_clicked(void);
extern void lcd_beeper_quick_feedback(void);
//Cause an LCD refresh, and give the user visual or audible feedback that something has happened
extern void lcd_quick_feedback(void);
extern void lcd_update(uint8_t lcdDrawUpdateOverride);
extern void lcd_update_enable(uint8_t enabled);
extern void lcd_buttons_update(void);
/**
* Implementation of the LCD display routines for a Hitachi HD44780 display. These are common LCD character displays.
* When selecting the Russian language, a slightly different LCD implementation is used to handle UTF8 characters.
**/
////////////////////////////////////
// Setup button and encode mappings for each panel (into 'lcd_buttons' variable
//
// This is just to map common functions (across different panels) onto the same
// macro name. The mapping is independent of whether the button is directly connected or
// via a shift/i2c register.
#define BLEN_B 1
#define BLEN_A 0
#define EN_B (1<<BLEN_B) // The two encoder pins are connected through BTN_EN1 and BTN_EN2
#define EN_A (1<<BLEN_A)
#define BLEN_C 2
#define EN_C (1<<BLEN_C)
#define LCD_CLICKED (lcd_buttons&EN_C)
////////////////////////
// Setup Rotary Encoder Bit Values (for two pin encoders to indicate movement)
// These values are independent of which pins are used for EN_A and EN_B indications
// The rotary encoder part is also independent to the chipset used for the LCD
#define encrot0 0
#define encrot1 2
#define encrot2 3
#define encrot3 1
//Custom characters defined in the first 8 characters of the LCD
#define LCD_STR_BEDTEMP "\x00"
#define LCD_STR_DEGREE "\x01"
#define LCD_STR_THERMOMETER "\x02"
#define LCD_STR_UPLEVEL "\x03"
#define LCD_STR_REFRESH "\x04"
#define LCD_STR_FOLDER "\x05"
#define LCD_STR_FEEDRATE "\x06"
#define LCD_STR_CLOCK "\x07"
#define LCD_STR_ARROW_UP "\x0B"
#define LCD_STR_ARROW_DOWN "\x01"
#define LCD_STR_ARROW_RIGHT "\x7E" //from the default character set
extern void lcd_set_custom_characters(void);
extern void lcd_set_custom_characters_arrows(void);
extern void lcd_set_custom_characters_progress(void);
extern void lcd_set_custom_characters_nextpage(void);
extern void lcd_set_custom_characters_degree(void);
extern void lcd_drawedit(const char* pstr, char* value);
extern void lcd_drawedit_2(const char* pstr, char* value);
#endif //_LCD_H

274
Firmware/menu.cpp Normal file
View file

@ -0,0 +1,274 @@
//menu.cpp
#include "menu.h"
#include <stdio.h>
#include <string.h>
#include <stdarg.h>
#include <avr/pgmspace.h>
#include "lcd.h"
#include "Configuration.h"
#include "Marlin.h"
extern int32_t lcd_encoder;
menu_record_t menu_stack[MENU_DEPTH_MAX];
uint8_t menu_data[MENU_DATA_SIZE];
uint8_t menu_depth = 0;
uint8_t menu_line = 0;
uint8_t menu_item = 0;
uint8_t menu_row = 0;
uint8_t menu_top = 0;
uint8_t menu_clicked = 0;
menu_func_t menu_menu = 0;
void menu_goto(menu_func_t menu, const uint32_t encoder, const bool feedback, bool reset_menu_state)
{
asm("cli");
if (menu_menu != menu)
{
menu_menu = menu;
lcd_encoder = encoder;
asm("sei");
if (reset_menu_state)
{
// Resets the global shared C union.
// This ensures, that the menu entered will find out, that it shall initialize itself.
memset(&menu_data, 0, sizeof(menu_data));
}
if (feedback) lcd_quick_feedback();
}
else
asm("sei");
}
void menu_start(void)
{
if (lcd_encoder > 0x8000) lcd_encoder = 0;
if (lcd_encoder < 0) lcd_encoder = 0;
if (lcd_encoder < menu_top)
menu_top = lcd_encoder;
menu_line = menu_top;
menu_clicked = LCD_CLICKED;
}
void menu_end(void)
{
if (lcd_encoder >= menu_item)
lcd_encoder = menu_item - 1;
if (((uint8_t)lcd_encoder) >= menu_top + LCD_HEIGHT)
{
menu_top = lcd_encoder - LCD_HEIGHT + 1;
lcd_draw_update = 1;
menu_line = menu_top - 1;
menu_row = -1;
}
}
void menu_back(void)
{
if (menu_depth > 0) menu_goto(menu_stack[--menu_depth].menu, menu_stack[menu_depth].position, true, true);
}
void menu_back_if_clicked(void)
{
if (lcd_clicked())
menu_back();
}
void menu_back_if_clicked_fb(void)
{
if (lcd_clicked())
{
lcd_quick_feedback();
menu_back();
}
}
void menu_submenu(menu_func_t submenu)
{
if (menu_depth <= MENU_DEPTH_MAX)
{
menu_stack[menu_depth].menu = menu_menu;
menu_stack[menu_depth++].position = lcd_encoder;
menu_goto(submenu, 0, true, true);
}
}
uint8_t menu_item_ret(void)
{
lcd_beeper_quick_feedback();
lcd_draw_update = 2;
lcd_button_pressed = false;
return 1;
}
/*
int menu_item_printf_P(char type_char, const char* format, ...)
{
va_list args;
va_start(args, format);
int ret = 0;
lcd_set_cursor(0, menu_row);
if (lcd_encoder == menu_item)
lcd_print('>');
else
lcd_print(' ');
int cnt = vfprintf_P(lcdout, format, args);
for (int i = cnt; i < 18; i++)
lcd_print(' ');
lcd_print(type_char);
va_end(args);
return ret;
}
*/
int menu_draw_item_puts_P(char type_char, const char* str)
{
lcd_set_cursor(0, menu_row);
int cnt = lcd_printf_P(PSTR("%c%-18S%c"), (lcd_encoder == menu_item)?'>':' ', str, type_char);
return cnt;
}
/*
int menu_draw_item_puts_P_int16(char type_char, const char* str, int16_t val, )
{
lcd_set_cursor(0, menu_row);
int cnt = lcd_printf_P(PSTR("%c%-18S%c"), (lcd_encoder == menu_item)?'>':' ', str, type_char);
return cnt;
}
*/
void menu_item_dummy(void)
{
menu_item++;
}
uint8_t menu_item_text_P(const char* str)
{
if (menu_item == menu_line)
{
if (lcd_draw_update) menu_draw_item_puts_P(' ', str);
if (menu_clicked && (lcd_encoder == menu_item))
return menu_item_ret();
}
menu_item++;
return 0;
}
uint8_t menu_item_submenu_P(const char* str, menu_func_t submenu)
{
if (menu_item == menu_line)
{
if (lcd_draw_update) menu_draw_item_puts_P(LCD_STR_ARROW_RIGHT[0], str);
if (menu_clicked && (lcd_encoder == menu_item))
{
menu_submenu(submenu);
return menu_item_ret();
}
}
menu_item++;
return 0;
}
uint8_t menu_item_back_P(const char* str)
{
if (menu_item == menu_line)
{
if (lcd_draw_update) menu_draw_item_puts_P(LCD_STR_UPLEVEL[0], str);
if (menu_clicked && (lcd_encoder == menu_item))
{
menu_back();
return menu_item_ret();
}
}
menu_item++;
return 0;
}
uint8_t menu_item_function_P(const char* str, menu_func_t func)
{
if (menu_item == menu_line)
{
if (lcd_draw_update) menu_draw_item_puts_P(' ', str);
if (menu_clicked && (lcd_encoder == menu_item))
{
menu_clicked = false;
lcd_update_enabled = 0;
if (func) func();
lcd_update_enabled = 1;
return menu_item_ret();
}
}
menu_item++;
return 0;
}
uint8_t menu_item_gcode_P(const char* str, const char* str_gcode)
{
if (menu_item == menu_line)
{
if (lcd_draw_update) menu_draw_item_puts_P(' ', str);
if (menu_clicked && (lcd_encoder == menu_item))
{
if (str_gcode) enquecommand_P(str_gcode);
return menu_item_ret();
}
}
menu_item++;
return 0;
}
const char menu_fmt_int3[] PROGMEM = "%c%S:\x1b[%hhu;16H%3d";
#define _menu_data (*((menu_data_edit_t*)menu_data))
void _menu_edit_int3(void)
{
if (lcd_draw_update)
{
if (lcd_encoder < _menu_data.minEditValue) lcd_encoder = _menu_data.minEditValue;
if (lcd_encoder > _menu_data.maxEditValue) lcd_encoder = _menu_data.maxEditValue;
lcd_set_cursor(0, 1);
lcd_printf_P(menu_fmt_int3, ' ', _menu_data.editLabel, (uint8_t)1, (int)lcd_encoder);
}
if (LCD_CLICKED)
{
*((int*)(_menu_data.editValue)) = (int)lcd_encoder;
menu_back();
}
}
uint8_t menu_item_edit_int3(const char* str, int16_t* pval, int16_t min_val, int16_t max_val)
{
if (menu_item == menu_line)
{
if (lcd_draw_update)
{
lcd_set_cursor(0, menu_row);
lcd_printf_P(menu_fmt_int3, (lcd_encoder == menu_item)?'>':' ', str, menu_row, *pval);
}
if (menu_clicked && (lcd_encoder == menu_item))
{
menu_submenu(_menu_edit_int3);
_menu_data.editLabel = str;
_menu_data.editValue = pval;
_menu_data.minEditValue = min_val;
_menu_data.maxEditValue = max_val;
lcd_encoder = *pval;
return menu_item_ret();
}
}
menu_item++;
return 0;
}
#undef _menu_data

98
Firmware/menu.h Normal file
View file

@ -0,0 +1,98 @@
//menu.h
#ifndef _MENU_H
#define _MENU_H
#include <inttypes.h>
#define MENU_DEPTH_MAX 4
#define MENU_DATA_SIZE 32
//Function pointer to menu functions.
typedef void (*menu_func_t)(void);
typedef struct
{
menu_func_t menu;
uint8_t position;
} menu_record_t;
typedef struct
{
//Variables used when editing values.
const char* editLabel;
void* editValue;
int32_t minEditValue;
int32_t maxEditValue;
} menu_data_edit_t;
extern menu_record_t menu_stack[MENU_DEPTH_MAX];
extern uint8_t menu_data[MENU_DATA_SIZE];
extern uint8_t menu_depth;
extern uint8_t menu_line;
extern uint8_t menu_item;
extern uint8_t menu_row;
;
//scroll offset in the current menu
extern uint8_t menu_top;
extern uint8_t menu_clicked;
//function pointer to the currently active menu
extern menu_func_t menu_menu;
extern void menu_goto(menu_func_t menu, const uint32_t encoder, const bool feedback, bool reset_menu_state);
#define MENU_BEGIN() menu_start(); for(menu_row = 0; menu_row < LCD_HEIGHT; menu_row++, menu_line++) { menu_item = 0;
void menu_start(void);
#define MENU_END() menu_end(); }
extern void menu_end(void);
extern void menu_back(void);
extern void menu_back_if_clicked(void);
extern void menu_back_if_clicked_fb(void);
extern void menu_submenu(menu_func_t submenu);
extern uint8_t menu_item_ret(void);
//int menu_item_printf_P(char type_char, const char* format, ...);
extern int menu_draw_item_puts_P(char type_char, const char* str);
//int menu_draw_item_puts_P_int16(char type_char, const char* str, int16_t val, );
#define MENU_ITEM_DUMMY() menu_item_dummy()
extern void menu_item_dummy(void);
#define MENU_ITEM_TEXT_P(str) do { if (menu_item_text_P(str)) return; } while (0)
extern uint8_t menu_item_text_P(const char* str);
#define MENU_ITEM_SUBMENU_P(str, submenu) do { if (menu_item_submenu_P(str, submenu)) return; } while (0)
extern uint8_t menu_item_submenu_P(const char* str, menu_func_t submenu);
#define MENU_ITEM_BACK_P(str) do { if (menu_item_back_P(str)) return; } while (0)
extern uint8_t menu_item_back_P(const char* str);
#define MENU_ITEM_FUNCTION_P(str, func) do { if (menu_item_function_P(str, func)) return; } while (0)
extern uint8_t menu_item_function_P(const char* str, menu_func_t func);
#define MENU_ITEM_GCODE_P(str, str_gcode) do { if (menu_item_gcode_P(str, str_gcode)) return; } while (0)
extern uint8_t menu_item_gcode_P(const char* str, const char* str_gcode);
extern const char menu_fmt_int3[];
extern void _menu_edit_int3(void);
#define MENU_ITEM_EDIT_int3_P(str, pval, minval, maxval) do { if (menu_item_edit_int3(str, pval, minval, maxval)) return; } while (0)
//#define MENU_ITEM_EDIT_int3_P(str, pval, minval, maxval) MENU_ITEM_EDIT(int3, str, pval, minval, maxval)
extern uint8_t menu_item_edit_int3(const char* str, int16_t* pval, int16_t min_val, int16_t max_val);
#endif //_MENU_H

View file

@ -2204,12 +2204,13 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
// Don't let the manage_inactivity() function remove power from the motors.
refresh_cmd_timeout();
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
lcd_implementation_print_at(0, next_line, k + 1);
lcd_printPGM(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));
lcd_set_cursor(0, next_line);
lcd_print(k + 1);
lcd_puts_P(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));
if (iteration > 0) {
lcd_print_at_PGM(0, next_line + 1, _i("Iteration "));////MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION c=20 r=0
lcd_implementation_print(int(iteration + 1));
lcd_puts_at_P(0, next_line + 1, _i("Iteration "));////MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION c=20 r=0
lcd_print(int(iteration + 1));
}
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
float *pt = pts + k * 2;
@ -2478,8 +2479,8 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
refresh_cmd_timeout();
// Print the decrasing ID of the measurement point.
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
lcd_implementation_print_at(0, next_line, mesh_point+1);
lcd_printPGM(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));////MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14 r=0
lcd_print_at(0, next_line, mesh_point+1);
lcd_puts_P(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));////MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14 r=0
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
// Move up.
@ -2782,8 +2783,9 @@ bool sample_mesh_and_store_reference()
if (next_line > 3)
next_line = 3;
// display "point xx of yy"
lcd_implementation_print_at(0, next_line, 1);
lcd_printPGM(_T(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2));
lcd_set_cursor(0, next_line);
lcd_print(1);
lcd_puts_P(_T(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2));
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
// Sample Z heights for the mesh bed leveling.
@ -2828,8 +2830,9 @@ bool sample_mesh_and_store_reference()
go_to_current(homing_feedrate[X_AXIS]/60);
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
// display "point xx of yy"
lcd_implementation_print_at(0, next_line, mesh_point+1);
lcd_printPGM(_T(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2));
lcd_set_cursor(0, next_line);
lcd_print(mesh_point+1);
lcd_puts_P(_T(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2));
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
if (!find_bed_induction_sensor_point_z()) //Z crash or deviation > 50um
{
@ -2845,11 +2848,11 @@ bool sample_mesh_and_store_reference()
{
// Verify the span of the Z values.
float zmin = mbl.z_values[0][0];
float zmax = zmax;
float zmax = zmin;
for (int8_t j = 0; j < 3; ++ j)
for (int8_t i = 0; i < 3; ++ i) {
zmin = min(zmin, mbl.z_values[j][i]);
zmax = min(zmax, mbl.z_values[j][i]);
zmax = max(zmax, mbl.z_values[j][i]);
}
if (zmax - zmin > 3.f) {
// The span of the Z offsets is extreme. Give up.

160
Firmware/pat9125.cpp → Firmware/pat9125.c Executable file → Normal file
View file

@ -1,8 +1,30 @@
#include "uni_avr_rpi.h"
#ifdef PAT9125
//pat9125.c
#include "pat9125.h"
#include <avr/delay.h>
#include <avr/pgmspace.h>
#include "config.h"
#include <stdio.h>
//PAT9125 registers
#define PAT9125_PID1 0x00
#define PAT9125_PID2 0x01
#define PAT9125_MOTION 0x02
#define PAT9125_DELTA_XL 0x03
#define PAT9125_DELTA_YL 0x04
#define PAT9125_MODE 0x05
#define PAT9125_CONFIG 0x06
#define PAT9125_WP 0x09
#define PAT9125_SLEEP1 0x0a
#define PAT9125_SLEEP2 0x0b
#define PAT9125_RES_X 0x0d
#define PAT9125_RES_Y 0x0e
#define PAT9125_DELTA_XYH 0x12
#define PAT9125_SHUTTER 0x14
#define PAT9125_FRAME 0x17
#define PAT9125_ORIENTATION 0x19
#define PAT9125_BANK_SELECTION 0x7f
#ifdef PAT9125_SWSPI
#include "swspi.h"
@ -10,20 +32,18 @@
#ifdef PAT9125_SWI2C
#include "swi2c.h"
#endif //PAT9125_SWI2C
#ifdef PAT9125_HWI2C
#include <Wire.h>
#endif //PAT9125_HWI2C
unsigned char pat9125_PID1 = 0;
unsigned char pat9125_PID2 = 0;
int pat9125_x = 0;
int pat9125_y = 0;
unsigned char pat9125_b = 0;
unsigned char pat9125_s = 0;
uint8_t pat9125_PID1 = 0;
uint8_t pat9125_PID2 = 0;
int16_t pat9125_x = 0;
int16_t pat9125_y = 0;
uint8_t pat9125_b = 0;
uint8_t pat9125_s = 0;
// Init sequence, address & value.
const PROGMEM unsigned char pat9125_init_seq1[] = {
const PROGMEM uint8_t pat9125_init_seq1[] = {
// Disable write protect.
PAT9125_WP, 0x5a,
// Set the X resolution to zero to let the sensor know that it could safely ignore movement in the X axis.
@ -43,7 +63,7 @@ const PROGMEM unsigned char pat9125_init_seq1[] = {
};
// Init sequence, address & value.
const PROGMEM unsigned char pat9125_init_seq2[] = {
const PROGMEM uint8_t pat9125_init_seq2[] = {
// Magic sequence to enforce full frame rate of the sensor.
0x06, 0x028,
0x33, 0x0d0,
@ -74,22 +94,23 @@ const PROGMEM unsigned char pat9125_init_seq2[] = {
0x0ff
};
int pat9125_init()
uint8_t pat9125_rd_reg(uint8_t addr);
void pat9125_wr_reg(uint8_t addr, uint8_t data);
uint8_t pat9125_wr_reg_verify(uint8_t addr, uint8_t data);
uint8_t pat9125_init(void)
{
#ifdef PAT9125_SWSPI
swspi_init();
#endif //PAT9125_SWSPI
#ifdef PAT9125_SWI2C
swi2c_init(PAT9125_SWI2C_SDA, PAT9125_SWI2C_SCL, PAT9125_SWI2C_CFG);
swi2c_init();
#endif //PAT9125_SWI2C
#ifdef PAT9125_HWI2C
Wire.begin();
#endif //PAT9125_HWI2C
// Verify that the sensor responds with its correct product ID.
pat9125_PID1 = pat9125_rd_reg(PAT9125_PID1);
pat9125_PID2 = pat9125_rd_reg(PAT9125_PID2);
// pat9125_PID1 = 0x31;
// pat9125_PID2 = 0x91;
if ((pat9125_PID1 != 0x31) || (pat9125_PID2 != 0x91))
{
pat9125_PID1 = pat9125_rd_reg(PAT9125_PID1);
@ -97,6 +118,8 @@ int pat9125_init()
if ((pat9125_PID1 != 0x31) || (pat9125_PID2 != 0x91))
return 0;
}
#ifdef PAT9125_NEW_INIT
// Switch to bank0, not allowed to perform OTS_RegWriteRead.
pat9125_wr_reg(PAT9125_BANK_SELECTION, 0);
// Software reset (i.e. set bit7 to 1). It will reset to 0 automatically.
@ -104,11 +127,11 @@ int pat9125_init()
pat9125_wr_reg(PAT9125_CONFIG, 0x97);
// Wait until the sensor reboots.
// Delay 1ms.
delayMicroseconds(1000);
_delay_us(1000);
{
const unsigned char *ptr = pat9125_init_seq1;
const uint8_t *ptr = pat9125_init_seq1;
for (;;) {
const unsigned char addr = pgm_read_byte_near(ptr ++);
const uint8_t addr = pgm_read_byte_near(ptr ++);
if (addr == 0x0ff)
break;
if (! pat9125_wr_reg_verify(addr, pgm_read_byte_near(ptr ++)))
@ -117,13 +140,13 @@ int pat9125_init()
}
}
// Delay 10ms.
delayMicroseconds(10000);
_delay_ms(10);
// Switch to bank1, not allowed to perform OTS_RegWrite.
pat9125_wr_reg(PAT9125_BANK_SELECTION, 0x01);
{
const unsigned char *ptr = pat9125_init_seq2;
const uint8_t *ptr = pat9125_init_seq2;
for (;;) {
const unsigned char addr = pgm_read_byte_near(ptr ++);
const uint8_t addr = pgm_read_byte_near(ptr ++);
if (addr == 0x0ff)
break;
if (! pat9125_wr_reg_verify(addr, pgm_read_byte_near(ptr ++)))
@ -138,25 +161,28 @@ int pat9125_init()
pat9125_PID1 = pat9125_rd_reg(PAT9125_PID1);
pat9125_PID2 = pat9125_rd_reg(PAT9125_PID2);
#endif //PAT9125_NEW_INIT
pat9125_wr_reg(PAT9125_RES_X, 0);
pat9125_wr_reg(PAT9125_RES_Y, 200);
return 1;
}
int pat9125_update()
uint8_t pat9125_update(void)
{
if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91))
{
unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION);
uint8_t ucMotion = pat9125_rd_reg(PAT9125_MOTION);
pat9125_b = pat9125_rd_reg(PAT9125_FRAME);
pat9125_s = pat9125_rd_reg(PAT9125_SHUTTER);
if (pat9125_PID1 == 0xff) return 0;
if (ucMotion & 0x80)
{
unsigned char ucXL = pat9125_rd_reg(PAT9125_DELTA_XL);
unsigned char ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
unsigned char ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
uint8_t ucXL = pat9125_rd_reg(PAT9125_DELTA_XL);
uint8_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
uint8_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
if (pat9125_PID1 == 0xff) return 0;
int iDX = ucXL | ((ucXYH << 4) & 0xf00);
int iDY = ucYL | ((ucXYH << 8) & 0xf00);
int16_t iDX = ucXL | ((ucXYH << 4) & 0xf00);
int16_t iDY = ucYL | ((ucXYH << 8) & 0xf00);
if (iDX & 0x800) iDX -= 4096;
if (iDY & 0x800) iDY -= 4096;
pat9125_x += iDX;
@ -167,18 +193,18 @@ int pat9125_update()
return 0;
}
int pat9125_update_y()
uint8_t pat9125_update_y(void)
{
if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91))
{
unsigned char ucMotion = pat9125_rd_reg(PAT9125_MOTION);
uint8_t ucMotion = pat9125_rd_reg(PAT9125_MOTION);
if (pat9125_PID1 == 0xff) return 0;
if (ucMotion & 0x80)
{
unsigned char ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
unsigned char ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
uint8_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL);
uint8_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH);
if (pat9125_PID1 == 0xff) return 0;
int iDY = ucYL | ((ucXYH << 8) & 0xf00);
int16_t iDY = ucYL | ((ucXYH << 8) & 0xf00);
if (iDY & 0x800) iDY -= 4096;
pat9125_y -= iDY; //negative number, because direction switching does not work
}
@ -187,10 +213,26 @@ int pat9125_update_y()
return 0;
}
unsigned char pat9125_rd_reg(unsigned char addr)
uint8_t pat9125_update_y2(void)
{
// printf_P(PSTR("pat9125_rd_reg 0x%hhx "), addr);
unsigned char data = 0;
if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91))
{
uint8_t ucMotion = pat9125_rd_reg(PAT9125_MOTION);
if (pat9125_PID1 == 0xff) return 0; //NOACK error
if (ucMotion & 0x80)
{
int8_t dy = pat9125_rd_reg(PAT9125_DELTA_YL);
if (pat9125_PID1 == 0xff) return 0; //NOACK error
pat9125_y -= dy; //negative number, because direction switching does not work
}
return 1;
}
return 0;
}
uint8_t pat9125_rd_reg(uint8_t addr)
{
uint8_t data = 0;
#ifdef PAT9125_SWSPI
swspi_start();
swspi_tx(addr & 0x7f);
@ -198,30 +240,18 @@ unsigned char pat9125_rd_reg(unsigned char addr)
swspi_stop();
#endif //PAT9125_SWSPI
#ifdef PAT9125_SWI2C
int iret = swi2c_readByte_A8(PAT9125_I2C_ADDR, addr, &data);
if (!iret) //NO ACK error
if (!swi2c_readByte_A8(PAT9125_I2C_ADDR, addr, &data)) //NO ACK error
{
pat9125_PID1 = 0xff;
pat9125_PID2 = 0xff;
// printf_P(PSTR("ERR\n"));
return 0;
}
// printf_P(PSTR("0x%hhx OK\n"), data);
#endif //PAT9125_SWI2C
#ifdef PAT9125_HWI2C
Wire.beginTransmission(PAT9125_I2C_ADDR);
Wire.write(addr);
Wire.endTransmission();
if (Wire.requestFrom(PAT9125_I2C_ADDR, 1) == 1)
// if (Wire.available())
data = Wire.read();
#endif //PAT9125_HWI2C
return data;
}
void pat9125_wr_reg(unsigned char addr, unsigned char data)
void pat9125_wr_reg(uint8_t addr, uint8_t data)
{
// printf_P(PSTR("pat9125_wr_reg 0x%hhx 0x%hhx "), addr, data);
#ifdef PAT9125_SWSPI
swspi_start();
swspi_tx(addr | 0x80);
@ -229,29 +259,17 @@ void pat9125_wr_reg(unsigned char addr, unsigned char data)
swspi_stop();
#endif //PAT9125_SWSPI
#ifdef PAT9125_SWI2C
int iret = swi2c_writeByte_A8(PAT9125_I2C_ADDR, addr, &data);
if (!iret) //NO ACK error
if (!swi2c_writeByte_A8(PAT9125_I2C_ADDR, addr, &data)) //NO ACK error
{
pat9125_PID1 = 0xff;
pat9125_PID2 = 0xff;
// printf_P(PSTR("ERR\n"));
return;
}
// printf_P(PSTR("OK\n"));
#endif //PAT9125_SWI2C
#ifdef PAT9125_HWI2C
Wire.beginTransmission(PAT9125_I2C_ADDR);
Wire.write(addr);
Wire.write(data);
Wire.endTransmission();
#endif //PAT9125_HWI2C
}
bool pat9125_wr_reg_verify(unsigned char addr, unsigned char data)
uint8_t pat9125_wr_reg_verify(uint8_t addr, uint8_t data)
{
pat9125_wr_reg(addr, data);
return pat9125_rd_reg(addr) == data;
}
#endif //PAT9125

View file

@ -1,45 +1,31 @@
//pat9125.h
#ifndef PAT9125_H
#define PAT9125_H
//PAT9125 I2C
#define PAT9125_I2C_ADDR 0x75 //ID=LO
//#define PAT9125_I2C_ADDR 0x79 //ID=HI
//#define PAT9125_I2C_ADDR 0x73 //ID=NC
#include <inttypes.h>
//PAT9125 registers
#define PAT9125_PID1 0x00
#define PAT9125_PID2 0x01
#define PAT9125_MOTION 0x02
#define PAT9125_DELTA_XL 0x03
#define PAT9125_DELTA_YL 0x04
#define PAT9125_MODE 0x05
#define PAT9125_CONFIG 0x06
#define PAT9125_WP 0x09
#define PAT9125_SLEEP1 0x0a
#define PAT9125_SLEEP2 0x0b
#define PAT9125_RES_X 0x0d
#define PAT9125_RES_Y 0x0e
#define PAT9125_DELTA_XYH 0x12
#define PAT9125_SHUTTER 0x14
#define PAT9125_FRAME 0x17
#define PAT9125_ORIENTATION 0x19
#define PAT9125_BANK_SELECTION 0x7f
extern unsigned char pat9125_PID1;
extern unsigned char pat9125_PID2;
#if defined(__cplusplus)
extern "C" {
#endif //defined(__cplusplus)
extern int pat9125_x;
extern int pat9125_y;
extern unsigned char pat9125_b;
extern unsigned char pat9125_s;
extern int pat9125_init();
extern int pat9125_update();
extern int pat9125_update_y();
extern uint8_t pat9125_PID1;
extern uint8_t pat9125_PID2;
extern unsigned char pat9125_rd_reg(unsigned char addr);
extern void pat9125_wr_reg(unsigned char addr, unsigned char data);
extern bool pat9125_wr_reg_verify(unsigned char addr, unsigned char data);
extern int16_t pat9125_x;
extern int16_t pat9125_y;
extern uint8_t pat9125_b;
extern uint8_t pat9125_s;
extern uint8_t pat9125_init(void);
extern uint8_t pat9125_update(void);
extern uint8_t pat9125_update_y(void);
extern uint8_t pat9125_update_y2(void);
#if defined(__cplusplus)
}
#endif //defined(__cplusplus)
#endif //PAT9125_H

View file

@ -17,15 +17,11 @@
#define W25X20CL // external 256kB flash
#define SWI2C // enable software i2c
#define SWI2C_A8 // 8bit address functions
#define PAT9125_SWI2C
#define PAT9125_SWI2C_SDA 20 //SDA on P3
#define PAT9125_SWI2C_SCL 21 //SCL on P3
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
#define SWI2C_SDA 20 //SDA on P3
#define SWI2C_SCL 21 //SCL on P3
//#define PAT9125_HWI2C
#define X_TMC2130_CS 41
#define X_TMC2130_DIAG 64 // !!! changed from 40 (EINY03)
@ -99,11 +95,9 @@
#define KILL_PIN -1 // 80 with Smart Controller LCD
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
#ifdef ULTRA_LCD
//#define KILL_PIN 32
#ifdef NEWPANEL
//#define LCD_PWM_PIN -1//32 // lcd backlight brightnes pwm control pin
//#define LCD_PWM_MAX 0x0f // lcd pwm maximum value (0x07=64Hz, 0x0f=32Hz, 0x1f=16Hz)
@ -126,8 +120,6 @@
#define TACH_0 79 // !!! changed from 81 (EINY03)
#define TACH_1 80
#endif //NEWPANEL
#endif //ULTRA_LCD
// Support for an 8 bit logic analyzer, for example the Saleae.
// Channels 0-2 are fast, they could generate 2.667Mhz waveform with a software loop.

View file

@ -11,15 +11,10 @@
#define PINDA_THERMISTOR
#define SWI2C // enable software i2c
#define SWI2C_A8 // 8bit address functions
#define SWI2C_SDA 20 //SDA on P3
#define SWI2C_SCL 84 //PH2 on P3, sensor cable must be rewired
#define PAT9125_SWI2C
#define PAT9125_SWI2C_SDA 20 //SDA on P3
#define PAT9125_SWI2C_SCL 84 //PH2 on P3, sensor cable must be rewired
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
//#define PAT9125_HWI2C
#define X_STEP_PIN 37
#define X_DIR_PIN 48
@ -88,11 +83,9 @@
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
#define TACH_0 30 // noctua extruder fan
#ifdef ULTRA_LCD
//#define KILL_PIN 32
#ifdef NEWPANEL
#define BEEPER 78 // Beeper on AUX-4
#define LCD_PINS_RS 38
@ -110,8 +103,6 @@
#define SDCARDDETECT 72
#endif //NEWPANEL
#endif //ULTRA_LCD
// Support for an 8 bit logic analyzer, for example the Saleae.
// Channels 0-2 are fast, they could generate 2.667Mhz waveform with a software loop.

View file

@ -11,15 +11,10 @@
#define PINDA_THERMISTOR
#define SWI2C // enable software i2c
#define SWI2C_A8 // 8bit address functions
#define SWI2C_SDA 20 //SDA on P3
#define SWI2C_SCL 21 //SCL on P3
#define PAT9125_SWI2C
#define PAT9125_SWI2C_SDA 20 //SDA on P3
#define PAT9125_SWI2C_SCL 21 //SCL on P3
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
//#define PAT9125_HWI2C
#define X_STEP_PIN 37
#define X_DIR_PIN 48
@ -88,11 +83,9 @@
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
#define TACH_0 30 // noctua extruder fan
#ifdef ULTRA_LCD
//#define KILL_PIN 32
#ifdef NEWPANEL
#define BEEPER 84 // Beeper on AUX-4
#define LCD_PINS_RS 82
@ -110,8 +103,6 @@
#define SDCARDDETECT 15
#endif //NEWPANEL
#endif //ULTRA_LCD
// Support for an 8 bit logic analyzer, for example the Saleae.
// Channels 0-2 are fast, they could generate 2.667Mhz waveform with a software loop.

View file

@ -646,10 +646,10 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
manage_heater();
// Vojtech: Don't disable motors inside the planner!
manage_inactivity(false);
lcd_update();
lcd_update(0);
} while (block_buffer_tail == next_buffer_head);
if (waiting_inside_plan_buffer_line_print_aborted) {
// Inside the lcd_update() routine the print has been aborted.
// Inside the lcd_update(0) routine the print has been aborted.
// Cancel the print, do not plan the current line this routine is waiting on.
#ifdef PLANNER_DIAGNOSTICS
planner_update_queue_min_counter();
@ -954,6 +954,7 @@ Having the real displacement of the head, we can calculate the total movement le
{
current_speed[i] = delta_mm[i] * inverse_second;
#ifdef TMC2130
#ifdef FEEDRATE_LIMIT
float max_fr = max_feedrate[i];
if (i < 2) // X, Y
{
@ -970,6 +971,10 @@ Having the real displacement of the head, we can calculate the total movement le
}
if(fabs(current_speed[i]) > max_fr)
speed_factor = min(speed_factor, max_fr / fabs(current_speed[i]));
#else //FEEDRATE_LIMIT
if(fabs(current_speed[i]) > max_feedrate[i])
speed_factor = min(speed_factor, max_feedrate[i] / fabs(current_speed[i]));
#endif //FEEDRATE_LIMIT
#else //TMC2130
if(fabs(current_speed[i]) > max_feedrate[i])
speed_factor = min(speed_factor, max_feedrate[i] / fabs(current_speed[i]));
@ -1015,6 +1020,7 @@ Having the real displacement of the head, we can calculate the total movement le
if (block->steps_z.wide && (block->acceleration_st > axis_steps_per_sqr_second[Z_AXIS])) block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
if (block->steps_e.wide && (block->acceleration_st > axis_steps_per_sqr_second[E_AXIS])) block->acceleration_st = axis_steps_per_sqr_second[E_AXIS];
#else // SIMPLE_ACCEL_LIMIT
#ifdef ACCEL_LIMIT
if (tmc2130_mode == TMC2130_MODE_SILENT)
{
if ((block->steps_x.wide > block->step_event_count.wide / 2) || (block->steps_y.wide > block->step_event_count.wide / 2))
@ -1033,6 +1039,7 @@ Having the real displacement of the head, we can calculate the total movement le
block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
if(((float)block->acceleration_st * (float)block->steps_e.wide / (float)block->step_event_count.wide) > axis_steps_per_sqr_second[E_AXIS])
block->acceleration_st = axis_steps_per_sqr_second[E_AXIS];
#endif // ACCEL_LIMIT
#endif // SIMPLE_ACCEL_LIMIT
#else //TMC2130
// Limit acceleration per axis

View file

@ -407,12 +407,68 @@ ISR(TIMER1_COMPA_vect) {
}
}
uint8_t last_dir_bits = 0;
#ifdef BACKLASH_X
uint8_t st_backlash_x = 0;
#endif //BACKLASH_X
#ifdef BACKLASH_Y
uint8_t st_backlash_y = 0;
#endif //BACKLASH_Y
FORCE_INLINE void stepper_next_block()
{
// Anything in the buffer?
//WRITE_NC(LOGIC_ANALYZER_CH2, true);
current_block = plan_get_current_block();
if (current_block != NULL) {
#ifdef BACKLASH_X
if (current_block->steps_x.wide)
{ //X-axis movement
if ((current_block->direction_bits ^ last_dir_bits) & 1)
{
printf_P(PSTR("BL %d\n"), (current_block->direction_bits & 1)?st_backlash_x:-st_backlash_x);
if (current_block->direction_bits & 1)
WRITE_NC(X_DIR_PIN, INVERT_X_DIR);
else
WRITE_NC(X_DIR_PIN, !INVERT_X_DIR);
_delay_us(100);
for (uint8_t i = 0; i < st_backlash_x; i++)
{
WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
_delay_us(100);
WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
_delay_us(900);
}
}
last_dir_bits &= ~1;
last_dir_bits |= current_block->direction_bits & 1;
}
#endif
#ifdef BACKLASH_Y
if (current_block->steps_y.wide)
{ //Y-axis movement
if ((current_block->direction_bits ^ last_dir_bits) & 2)
{
printf_P(PSTR("BL %d\n"), (current_block->direction_bits & 2)?st_backlash_y:-st_backlash_y);
if (current_block->direction_bits & 2)
WRITE_NC(Y_DIR_PIN, INVERT_Y_DIR);
else
WRITE_NC(Y_DIR_PIN, !INVERT_Y_DIR);
_delay_us(100);
for (uint8_t i = 0; i < st_backlash_y; i++)
{
WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
_delay_us(100);
WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
_delay_us(900);
}
}
last_dir_bits &= ~2;
last_dir_bits |= current_block->direction_bits & 2;
}
#endif
#ifdef PAT9125
fsensor_counter = 0;
fsensor_st_block_begin(current_block);
@ -996,6 +1052,7 @@ FORCE_INLINE void isr() {
fsensor_st_block_chunk(current_block, fsensor_counter);
fsensor_counter = 0;
#endif //PAT9125
current_block = NULL;
plan_discard_current_block();
}
@ -1268,13 +1325,13 @@ void st_synchronize()
if (!tmc2130_update_sg())
{
manage_inactivity(true);
lcd_update();
lcd_update(0);
}
#else //TMC2130
manage_heater();
// Vojtech: Don't disable motors inside the planner!
manage_inactivity(true);
lcd_update();
lcd_update(0);
#endif //TMC2130
}
}

189
Firmware/swi2c.c Normal file
View file

@ -0,0 +1,189 @@
//swi2c.c
#include "swi2c.h"
#include <avr/io.h>
#include <avr/delay.h>
#include <avr/pgmspace.h>
#include "Configuration_prusa.h"
#include "pins.h"
#include "io_atmega2560.h"
#define SWI2C_RMSK 0x01 //read mask (bit0 = 1)
#define SWI2C_WMSK 0x00 //write mask (bit0 = 0)
#define SWI2C_ASHF 0x01 //address shift (<< 1)
#define SWI2C_DMSK 0x7f //device address mask
void __delay(void)
{
_delay_us(1.5);
}
void swi2c_init(void)
{
PIN_OUT(SWI2C_SDA);
PIN_OUT(SWI2C_SCL);
PIN_SET(SWI2C_SDA);
PIN_SET(SWI2C_SCL);
uint8_t i; for (i = 0; i < 100; i++)
__delay();
}
void swi2c_start(void)
{
PIN_CLR(SWI2C_SDA);
__delay();
PIN_CLR(SWI2C_SCL);
__delay();
}
void swi2c_stop(void)
{
PIN_SET(SWI2C_SCL);
__delay();
PIN_SET(SWI2C_SDA);
__delay();
}
void swi2c_ack(void)
{
PIN_CLR(SWI2C_SDA);
__delay();
PIN_SET(SWI2C_SCL);
__delay();
PIN_CLR(SWI2C_SCL);
__delay();
}
uint8_t swi2c_wait_ack()
{
PIN_INP(SWI2C_SDA);
__delay();
// PIN_SET(SWI2C_SDA);
__delay();
PIN_SET(SWI2C_SCL);
// __delay();
uint8_t ack = 0;
uint16_t ackto = SWI2C_TMO;
while (!(ack = (PIN_GET(SWI2C_SDA)?0:1)) && ackto--) __delay();
PIN_CLR(SWI2C_SCL);
__delay();
PIN_OUT(SWI2C_SDA);
__delay();
PIN_CLR(SWI2C_SDA);
__delay();
return ack;
}
uint8_t swi2c_read(void)
{
PIN_SET(SWI2C_SDA);
__delay();
PIN_INP(SWI2C_SDA);
uint8_t data = 0;
int8_t bit; for (bit = 7; bit >= 0; bit--)
{
PIN_SET(SWI2C_SCL);
__delay();
data |= (PIN_GET(SWI2C_SDA)?1:0) << bit;
PIN_CLR(SWI2C_SCL);
__delay();
}
PIN_OUT(SWI2C_SDA);
return data;
}
void swi2c_write(uint8_t data)
{
int8_t bit; for (bit = 7; bit >= 0; bit--)
{
if (data & (1 << bit)) PIN_SET(SWI2C_SDA);
else PIN_CLR(SWI2C_SDA);
__delay();
PIN_SET(SWI2C_SCL);
__delay();
PIN_CLR(SWI2C_SCL);
__delay();
}
}
uint8_t swi2c_check(uint8_t dev_addr)
{
swi2c_start();
swi2c_write((dev_addr & SWI2C_DMSK) << SWI2C_ASHF);
if (!swi2c_wait_ack()) { swi2c_stop(); return 0; }
swi2c_stop();
return 1;
}
#ifdef SWI2C_A8 //8bit address
uint8_t swi2c_readByte_A8(uint8_t dev_addr, uint8_t addr, uint8_t* pbyte)
{
swi2c_start();
swi2c_write(SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack()) { swi2c_stop(); return 0; }
swi2c_write(addr & 0xff);
if (!swi2c_wait_ack()) return 0;
swi2c_stop();
swi2c_start();
swi2c_write(SWI2C_RMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack()) return 0;
uint8_t byte = swi2c_read();
swi2c_stop();
if (pbyte) *pbyte = byte;
return 1;
}
uint8_t swi2c_writeByte_A8(uint8_t dev_addr, uint8_t addr, uint8_t* pbyte)
{
swi2c_start();
swi2c_write(SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack()) { swi2c_stop(); return 0; }
swi2c_write(addr & 0xff);
if (!swi2c_wait_ack()) return 0;
swi2c_write(*pbyte);
if (!swi2c_wait_ack()) return 0;
swi2c_stop();
return 1;
}
#endif //SWI2C_A8
#ifdef SWI2C_A16 //16bit address
uint8_t swi2c_readByte_A16(uint8_t dev_addr, unsigned short addr, uint8_t* pbyte)
{
swi2c_start();
swi2c_write(SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack()) { swi2c_stop(); return 0; }
swi2c_write(addr >> 8);
if (!swi2c_wait_ack()) return 0;
swi2c_write(addr & 0xff);
if (!swi2c_wait_ack()) return 0;
swi2c_stop();
swi2c_start();
swi2c_write(SWI2C_RMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack()) return 0;
uint8_t byte = swi2c_read();
swi2c_stop();
if (pbyte) *pbyte = byte;
return 1;
}
uint8_t swi2c_writeByte_A16(uint8_t dev_addr, unsigned short addr, uint8_t* pbyte)
{
swi2c_start();
swi2c_write(SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack()) { swi2c_stop(); return 0; }
swi2c_write(addr >> 8);
if (!swi2c_wait_ack()) return 0;
swi2c_write(addr & 0xff);
if (!swi2c_wait_ack()) return 0;
swi2c_write(*pbyte);
if (!swi2c_wait_ack()) return 0;
swi2c_stop();
return 1;
}
#endif //SWI2C_A16

View file

@ -1,209 +0,0 @@
#include "uni_avr_rpi.h"
#ifdef SWI2C
#include "swi2c.h"
#ifdef __AVR
unsigned char swi2c_sda = 20; // SDA pin
unsigned char swi2c_scl = 21; // SCL pin
#endif //__AVR
#ifdef __RPI
unsigned char swi2c_sda = 2; // SDA pin
unsigned char swi2c_scl = 3; // SCL pin
#endif //__RPI
unsigned char swi2c_cfg = 0xb1; // config
// bit0..3 = clock delay factor = 1 << 1 = 2 [us]
// bit4..7 = ack timeout factor = 1 << 11 = 2048 [cycles]
#define SWI2C_SDA swi2c_sda
#define SWI2C_SCL swi2c_scl
#define SWI2C_RMSK 0x01 //read mask (bit0 = 1)
#define SWI2C_WMSK 0x00 //write mask (bit0 = 0)
#define SWI2C_ASHF 0x01 //address shift (<< 1)
#define SWI2C_DMSK 0x7f //device address mask
void swi2c_init(unsigned char sda, unsigned char scl, unsigned char cfg)
{
swi2c_sda = sda;
swi2c_scl = scl;
swi2c_cfg = cfg;
GPIO_OUT(SWI2C_SDA);
GPIO_OUT(SWI2C_SCL);
GPIO_SET(SWI2C_SDA);
GPIO_SET(SWI2C_SCL);
DELAY(1000);
}
void swi2c_start(int delay)
{
GPIO_CLR(SWI2C_SDA);
DELAY(delay);
GPIO_CLR(SWI2C_SCL);
DELAY(delay);
}
void swi2c_stop(int delay)
{
GPIO_SET(SWI2C_SCL);
DELAY(delay);
GPIO_SET(SWI2C_SDA);
DELAY(delay);
}
void swi2c_ack(int delay)
{
GPIO_CLR(SWI2C_SDA);
DELAY(delay);
GPIO_SET(SWI2C_SCL);
DELAY(delay);
GPIO_CLR(SWI2C_SCL);
DELAY(delay);
}
int swi2c_wait_ack(int delay, int ackto)
{
GPIO_INP(SWI2C_SDA);
DELAY(delay);
// GPIO_SET(SWI2C_SDA);
DELAY(delay);
GPIO_SET(SWI2C_SCL);
// DELAY(delay);
int ack = 0;
while (!(ack = !GPIO_GET(SWI2C_SDA)) && ackto--) DELAY(delay);
GPIO_CLR(SWI2C_SCL);
DELAY(delay);
GPIO_OUT(SWI2C_SDA);
DELAY(delay);
GPIO_CLR(SWI2C_SDA);
DELAY(delay);
return ack;
}
unsigned char swi2c_read(int delay)
{
GPIO_SET(SWI2C_SDA);
DELAY(delay);
GPIO_INP(SWI2C_SDA);
unsigned char data = 0;
int bit; for (bit = 7; bit >= 0; bit--)
{
GPIO_SET(SWI2C_SCL);
DELAY(delay);
data |= GPIO_GET(SWI2C_SDA) << bit;
GPIO_CLR(SWI2C_SCL);
DELAY(delay);
}
GPIO_OUT(SWI2C_SDA);
return data;
}
void swi2c_write(int delay, unsigned char data)
{
int bit; for (bit = 7; bit >= 0; bit--)
{
if (data & (1 << bit)) GPIO_SET(SWI2C_SDA);
else GPIO_CLR(SWI2C_SDA);
DELAY(delay);
GPIO_SET(SWI2C_SCL);
DELAY(delay);
GPIO_CLR(SWI2C_SCL);
DELAY(delay);
}
}
int swi2c_check(unsigned char dev_addr)
{
int delay = 1 << (swi2c_cfg & 0xf);
int tmout = 1 << (swi2c_cfg >> 4);
swi2c_start(delay);
swi2c_write(delay, (dev_addr & SWI2C_DMSK) << SWI2C_ASHF);
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
swi2c_stop(delay);
return 1;
}
#ifdef SWI2C_A8 //8bit address
int swi2c_readByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte)
{
int delay = 1 << (swi2c_cfg & 0xf);
int tmout = 1 << (swi2c_cfg >> 4);
swi2c_start(delay);
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
swi2c_write(delay, addr & 0xff);
if (!swi2c_wait_ack(delay, tmout)) return 0;
swi2c_stop(delay);
swi2c_start(delay);
swi2c_write(delay, SWI2C_RMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack(delay, tmout)) return 0;
unsigned char byte = swi2c_read(delay);
swi2c_stop(delay);
if (pbyte) *pbyte = byte;
return 1;
}
int swi2c_writeByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte)
{
int delay = 1 << (swi2c_cfg & 0xf);
int tmout = 1 << (swi2c_cfg >> 4);
swi2c_start(delay);
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
swi2c_write(delay, addr & 0xff);
if (!swi2c_wait_ack(delay, tmout)) return 0;
swi2c_write(delay, *pbyte);
if (!swi2c_wait_ack(delay, tmout)) return 0;
swi2c_stop(delay);
return 1;
}
#endif //SWI2C_A8
#ifdef SWI2C_A16 //16bit address
int swi2c_readByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte)
{
int delay = 1 << (swi2c_cfg & 0xf);
int tmout = 1 << (swi2c_cfg >> 4);
swi2c_start(delay);
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
swi2c_write(delay, addr >> 8);
if (!swi2c_wait_ack(delay, tmout)) return 0;
swi2c_write(delay, addr & 0xff);
if (!swi2c_wait_ack(delay, tmout)) return 0;
swi2c_stop(delay);
swi2c_start(delay);
swi2c_write(delay, SWI2C_RMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack(delay, tmout)) return 0;
unsigned char byte = swi2c_read(delay);
swi2c_stop(delay);
if (pbyte) *pbyte = byte;
return 1;
}
int swi2c_writeByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte)
{
int delay = 1 << (swi2c_cfg & 0xf);
int tmout = 1 << (swi2c_cfg >> 4);
swi2c_start(delay);
swi2c_write(delay, SWI2C_WMSK | ((dev_addr & SWI2C_DMSK) << SWI2C_ASHF));
if (!swi2c_wait_ack(delay, tmout)) { swi2c_stop(delay); return 0; }
swi2c_write(delay, addr >> 8);
if (!swi2c_wait_ack(delay, tmout)) return 0;
swi2c_write(delay, addr & 0xff);
if (!swi2c_wait_ack(delay, tmout)) return 0;
swi2c_write(delay, *pbyte);
if (!swi2c_wait_ack(delay, tmout)) return 0;
swi2c_stop(delay);
return 1;
}
#endif //SWI2C_A16
#endif //SWI2C

View file

@ -1,22 +1,35 @@
//swi2c.h
#ifndef SWI2C_H
#define SWI2C_H
#include <inttypes.h>
#include "config.h"
#if defined(__cplusplus)
extern "C" {
#endif //defined(__cplusplus)
//initialize
extern void swi2c_init(unsigned char sda, unsigned char scl, unsigned char cfg);
extern void swi2c_init(void);
//check device address acknowledge
extern int swi2c_check(unsigned char dev_addr);
extern uint8_t swi2c_check(uint8_t dev_addr);
//read write functions - 8bit address (most i2c chips)
#ifdef SWI2C_A8
extern int swi2c_readByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte);
extern int swi2c_writeByte_A8(unsigned char dev_addr, unsigned char addr, unsigned char* pbyte);
extern uint8_t swi2c_readByte_A8(uint8_t dev_addr, uint8_t addr, uint8_t* pbyte);
extern uint8_t swi2c_writeByte_A8(uint8_t dev_addr, uint8_t addr, uint8_t* pbyte);
#endif //SWI2C_A8
//read write functions - 16bit address (e.g. serial eeprom AT24C256)
#ifdef SWI2C_A16
extern int swi2c_readByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte);
extern int swi2c_writeByte_A16(unsigned char dev_addr, unsigned short addr, unsigned char* pbyte);
extern uint8_t swi2c_readByte_A16(uint8_t dev_addr, uint16_t addr, uint8_t* pbyte);
extern uint8_t swi2c_writeByte_A16(uint8_t dev_addr, uint16_t addr, uint8_t* pbyte);
#endif //SWI2C_A16
#if defined(__cplusplus)
}
#endif //defined(__cplusplus)
#endif //SWI2C_H

View file

@ -403,7 +403,7 @@ unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
pid_cycle = 0;
return;
}
lcd_update();
lcd_update(0);
}
}
@ -1332,7 +1332,7 @@ void temp_runaway_stop(bool isPreheat, bool isBed)
disable_e1();
disable_e2();
manage_heater();
lcd_update();
lcd_update(0);
WRITE(BEEPER, HIGH);
delayMicroseconds(500);
WRITE(BEEPER, LOW);

View file

@ -3,13 +3,11 @@
#ifdef TMC2130
#include "tmc2130.h"
#include "LiquidCrystal_Prusa.h"
#include "ultralcd.h"
#include "language.h"
#include "spi.h"
extern LiquidCrystal_Prusa lcd;
#define TMC2130_GCONF_NORMAL 0x00000000 // spreadCycle
#define TMC2130_GCONF_SGSENS 0x00003180 // spreadCycle with stallguard (stall activates DIAG0 and DIAG1 [pushpull])
@ -62,6 +60,13 @@ uint8_t tmc2130_home_fsteps[2] = {48, 48};
uint8_t tmc2130_wave_fac[4] = {0, 0, 0, 0};
tmc2130_chopper_config_t tmc2130_chopper_config[4] = {
{TMC2130_TOFF_XYZ, 5, 1, 2, 0},
{TMC2130_TOFF_XYZ, 5, 1, 2, 0},
{TMC2130_TOFF_XYZ, 5, 1, 2, 0},
{TMC2130_TOFF_E, 5, 1, 2, 0}
};
bool tmc2130_sg_stop_on_crash = true;
uint8_t tmc2130_sg_diag_mask = 0x00;
uint8_t tmc2130_sg_crash = 0;
@ -407,9 +412,9 @@ void tmc2130_check_overtemp()
for (int i = 0; i < 4; i++)
{
tmc2130_sg_change = false;
lcd.setCursor(0 + i*4, 3);
lcd.print(itostr3(tmc2130_sg_cnt[i]));
lcd.print(' ');
lcd_set_cursor(0 + i*4, 3);
lcd_print(itostr3(tmc2130_sg_cnt[i]));
lcd_print(' ');
}
}
#endif //DEBUG_CRASHDET_COUNTERS
@ -418,13 +423,13 @@ void tmc2130_check_overtemp()
void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_t current_r)
{
uint8_t intpol = 1;
uint8_t toff = TMC2130_TOFF_XYZ; // toff = 3 (fchop = 27.778kHz)
uint8_t hstrt = 5; //initial 4, modified to 5
uint8_t hend = 1;
uint8_t toff = tmc2130_chopper_config[axis].toff; // toff = 3 (fchop = 27.778kHz)
uint8_t hstrt = tmc2130_chopper_config[axis].hstr; //initial 4, modified to 5
uint8_t hend = tmc2130_chopper_config[axis].hend; //original value = 1
uint8_t fd3 = 0;
uint8_t rndtf = 0; //random off time
uint8_t chm = 0; //spreadCycle
uint8_t tbl = 2; //blanking time
uint8_t tbl = tmc2130_chopper_config[axis].tbl; //blanking time, original value = 2
if (axis == E_AXIS)
{
#ifdef TMC2130_CNSTOFF_E
@ -434,9 +439,11 @@ void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_
hend = 0; //sine wave offset
chm = 1; // constant off time mod
#endif //TMC2130_CNSTOFF_E
toff = TMC2130_TOFF_E; // toff = 3-5
// toff = TMC2130_TOFF_E; // toff = 3-5
// rndtf = 1;
}
DBG(_n("tmc2130_setup_chopper(axis=%hhd, mres=%hhd, curh=%hhd, curr=%hhd\n"), axis, mres, current_h, current_r);
DBG(_n(" toff=%hhd, hstr=%hhd, hend=%hhd, tbl=%hhd\n"), toff, hstrt, hend, tbl);
if (current_r <= 31)
{
tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 1, 0, 0, 0, mres, intpol, 0, 0);
@ -444,7 +451,7 @@ void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_
}
else
{
tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, 0, 0, tbl, 0, 0, 0, 0, mres, intpol, 0, 0);
tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 0, 0, 0, 0, mres, intpol, 0, 0);
tmc2130_wr(axis, TMC2130_REG_IHOLD_IRUN, 0x000f0000 | (((current_r >> 1) & 0x1f) << 8) | ((current_h >> 1) & 0x1f));
}
}
@ -475,10 +482,7 @@ void tmc2130_print_currents()
void tmc2130_set_pwm_ampl(uint8_t axis, uint8_t pwm_ampl)
{
MYSERIAL.print("tmc2130_set_pwm_ampl ");
MYSERIAL.print((int)axis);
MYSERIAL.print(" ");
MYSERIAL.println((int)pwm_ampl);
DBG(_n("tmc2130_set_pwm_ampl(axis=%hhd, pwm_ampl=%hhd\n"), axis, pwm_ampl);
tmc2130_pwm_ampl[axis] = pwm_ampl;
if (((axis == 0) || (axis == 1)) && (tmc2130_mode == TMC2130_MODE_SILENT))
tmc2130_wr_PWMCONF(axis, tmc2130_pwm_ampl[axis], tmc2130_pwm_grad[axis], tmc2130_pwm_freq[axis], tmc2130_pwm_auto[axis], 0, 0);
@ -486,10 +490,7 @@ void tmc2130_set_pwm_ampl(uint8_t axis, uint8_t pwm_ampl)
void tmc2130_set_pwm_grad(uint8_t axis, uint8_t pwm_grad)
{
MYSERIAL.print("tmc2130_set_pwm_grad ");
MYSERIAL.print((int)axis);
MYSERIAL.print(" ");
MYSERIAL.println((int)pwm_grad);
DBG(_n("tmc2130_set_pwm_grad(axis=%hhd, pwm_grad=%hhd\n"), axis, pwm_grad);
tmc2130_pwm_grad[axis] = pwm_grad;
if (((axis == 0) || (axis == 1)) && (tmc2130_mode == TMC2130_MODE_SILENT))
tmc2130_wr_PWMCONF(axis, tmc2130_pwm_ampl[axis], tmc2130_pwm_grad[axis], tmc2130_pwm_freq[axis], tmc2130_pwm_auto[axis], 0, 0);
@ -865,7 +866,7 @@ void tmc2130_set_wave(uint8_t axis, uint8_t amp, uint8_t fac1000)
if (fac1000 < TMC2130_WAVE_FAC1000_MIN) fac1000 = 0;
if (fac1000 > TMC2130_WAVE_FAC1000_MAX) fac1000 = TMC2130_WAVE_FAC1000_MAX;
float fac = 0;
if (fac1000) fac = (float)((uint16_t)fac1000 + 1000) / 1000; //correction factor
if (fac1000) fac = ((float)((uint16_t)fac1000 + 1000) / 1000); //correction factor
printf_P(PSTR(" factor: %s\n"), ftostr43(fac));
uint8_t vA = 0; //value of currentA
uint8_t va = 0; //previous vA

View file

@ -36,6 +36,19 @@ extern uint8_t tmc2130_home_fsteps[2];
extern uint8_t tmc2130_wave_fac[4];
#pragma pack(push)
#pragma pack(1)
typedef struct
{
uint8_t toff:4;
uint8_t hstr:3;
uint8_t hend:4;
uint8_t tbl:2;
uint8_t res:3;
} tmc2130_chopper_config_t;
#pragma pack(pop)
extern tmc2130_chopper_config_t tmc2130_chopper_config[4];
//initialize tmc2130
extern void tmc2130_init();
@ -55,6 +68,7 @@ extern void tmc2130_sg_meassure_start(uint8_t axis);
//stop current stallguard meassuring and report result
extern uint16_t tmc2130_sg_meassure_stop();
extern void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_t current_r);
//set holding current for any axis (M911)
extern void tmc2130_set_current_h(uint8_t axis, uint8_t current);
@ -80,6 +94,7 @@ extern bool tmc2130_wait_standstill_xy(int timeout);
extern void tmc2130_eeprom_load_config();
extern void tmc2130_eeprom_save_config();
#pragma pack(push)
#pragma pack(1)
struct

File diff suppressed because it is too large Load diff

View file

@ -2,19 +2,20 @@
#define ULTRALCD_H
#include "Marlin.h"
#include "mesh_bed_calibration.h"
#include "lcd.h"
#include "conv2str.h"
extern int lcd_puts_P(const char* str);
extern int lcd_printf_P(const char* format, ...);
#ifdef ULTRA_LCD
extern void menu_lcd_longpress_func(void);
extern void menu_lcd_charsetup_func(void);
extern void menu_lcd_lcdupdate_func(void);
static void lcd_language_menu();
void lcd_update(uint8_t lcdDrawUpdateOverride = 0);
// Call with a false parameter to suppress the LCD update from various places like the planner or the temp control.
void lcd_update_enable(bool enable);
void lcd_init();
void ultralcd_init();
void lcd_setstatus(const char* message);
void lcd_setstatuspgm(const char* message);
void lcd_setalertstatuspgm(const char* message);
@ -37,7 +38,6 @@ extern int lcd_printf_P(const char* format, ...);
void lcd_confirm_print();
unsigned char lcd_choose_color();
//void lcd_mylang();
bool lcd_detected(void);
static void lcd_selftest_v();
extern bool lcd_selftest();
@ -76,15 +76,12 @@ extern int lcd_printf_P(const char* format, ...);
#ifndef TMC2130
extern bool lcd_calibrate_z_end_stop_manual(bool only_z);
#endif
// Show the result of the calibration process on the LCD screen.
extern void lcd_bed_calibration_show_result(BedSkewOffsetDetectionResultType result, uint8_t point_too_far_mask);
extern void lcd_bed_calibration_show_result(uint8_t result, uint8_t point_too_far_mask);
extern void lcd_diag_show_end_stops();
#ifdef DOGLCD
extern int lcd_contrast;
void lcd_setcontrast(uint8_t value);
#endif
static unsigned char blink = 0; // Variable for visualization of fan rotation in GLCD
@ -93,18 +90,7 @@ extern int lcd_printf_P(const char* format, ...);
#define LCD_MESSAGERPGM(x) lcd_setstatuspgm((x))
#define LCD_ALERTMESSAGERPGM(x) lcd_setalertstatuspgm((x))
#define LCD_UPDATE_INTERVAL 100
#define LCD_TIMEOUT_TO_STATUS 30000
#ifdef ULTIPANEL
void lcd_buttons_update();
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
#ifdef REPRAPWORLD_KEYPAD
extern volatile uint8_t buttons_reprapworld_keypad; // to store the keypad shift register values
#endif
#else
FORCE_INLINE void lcd_buttons_update() {}
#endif
// To be used in lcd_commands_type.
@ -142,102 +128,11 @@ extern int lcd_printf_P(const char* format, ...);
extern bool cancel_heatup;
extern bool isPrintPaused;
#ifdef FILAMENT_LCD_DISPLAY
extern unsigned long message_millis;
#endif
void lcd_buzz(long duration,uint16_t freq);
bool lcd_clicked();
void lcd_ignore_click(bool b=true);
void lcd_commands();
#ifdef NEWPANEL
#define EN_C (1<<BLEN_C)
#define EN_B (1<<BLEN_B)
#define EN_A (1<<BLEN_A)
#define LCD_CLICKED (buttons&EN_C)
#ifdef REPRAPWORLD_KEYPAD
#define EN_REPRAPWORLD_KEYPAD_F3 (1<<BLEN_REPRAPWORLD_KEYPAD_F3)
#define EN_REPRAPWORLD_KEYPAD_F2 (1<<BLEN_REPRAPWORLD_KEYPAD_F2)
#define EN_REPRAPWORLD_KEYPAD_F1 (1<<BLEN_REPRAPWORLD_KEYPAD_F1)
#define EN_REPRAPWORLD_KEYPAD_UP (1<<BLEN_REPRAPWORLD_KEYPAD_UP)
#define EN_REPRAPWORLD_KEYPAD_RIGHT (1<<BLEN_REPRAPWORLD_KEYPAD_RIGHT)
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (1<<BLEN_REPRAPWORLD_KEYPAD_MIDDLE)
#define EN_REPRAPWORLD_KEYPAD_DOWN (1<<BLEN_REPRAPWORLD_KEYPAD_DOWN)
#define EN_REPRAPWORLD_KEYPAD_LEFT (1<<BLEN_REPRAPWORLD_KEYPAD_LEFT)
#define LCD_CLICKED ((buttons&EN_C) || (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F1))
#define REPRAPWORLD_KEYPAD_MOVE_Z_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F2)
#define REPRAPWORLD_KEYPAD_MOVE_Z_DOWN (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F3)
#define REPRAPWORLD_KEYPAD_MOVE_X_LEFT (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_LEFT)
#define REPRAPWORLD_KEYPAD_MOVE_X_RIGHT (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_RIGHT)
#define REPRAPWORLD_KEYPAD_MOVE_Y_DOWN (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_DOWN)
#define REPRAPWORLD_KEYPAD_MOVE_Y_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_UP)
#define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_MIDDLE)
#endif //REPRAPWORLD_KEYPAD
#else
//atomic, do not change
#define B_LE (1<<BL_LE)
#define B_UP (1<<BL_UP)
#define B_MI (1<<BL_MI)
#define B_DW (1<<BL_DW)
#define B_RI (1<<BL_RI)
#define B_ST (1<<BL_ST)
#define EN_B (1<<BLEN_B)
#define EN_A (1<<BLEN_A)
#define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST))
#endif//NEWPANEL
#else //no LCD
FORCE_INLINE void
{}
FORCE_INLINE void lcd_init() {}
FORCE_INLINE void lcd_setstatus(const char* message) {}
FORCE_INLINE void lcd_buttons_update() {}
FORCE_INLINE void lcd_reset_alert_level() {}
FORCE_INLINE void lcd_buzz(long duration,uint16_t freq) {}
FORCE_INLINE bool lcd_detected(void) { return true; }
#define LCD_MESSAGEPGM(x)
#define LCD_ALERTMESSAGEPGM(x)
#endif //ULTRA_LCD
char *itostr2(const uint8_t &x);
char *itostr31(const int &xx);
char *itostr3(const int &xx);
char *itostr3left(const int &xx);
char *itostr4(const int &xx);
char *ftostr3(const float &x);
char *ftostr31ns(const float &x); // float to string without sign character
char *ftostr31(const float &x);
char *ftostr32(const float &x);
char *ftostr32ns(const float &x);
char *ftostr43(const float &x, uint8_t offset = 0);
char *ftostr12ns(const float &x);
char *ftostr13ns(const float &x);
char *ftostr32sp(const float &x); // remove zero-padding from ftostr32
char *ftostr5(const float &x);
char *ftostr51(const float &x);
char *ftostr52(const float &x);
extern void lcd_implementation_clear();
extern void lcd_printPGM(const char* str);
extern void lcd_print_at_PGM(uint8_t x, uint8_t y, const char* str);
extern void lcd_implementation_write(char c);
extern void lcd_implementation_print(const char *str);
extern void lcd_implementation_print(int8_t i);
extern void lcd_implementation_print_at(uint8_t x, uint8_t y, int8_t i);
extern void lcd_implementation_print(int i);
extern void lcd_implementation_print_at(uint8_t x, uint8_t y, int i);
extern void lcd_implementation_print(float f);
extern void lcd_implementation_print_at(uint8_t x, uint8_t y, const char *str);
void change_extr(int extr);

File diff suppressed because it is too large Load diff

View file

@ -290,10 +290,10 @@ bool show_upgrade_dialog_if_version_newer(const char *version_string)
if (upgrade) {
lcd_display_message_fullscreen_P(_i("New firmware version available:"));////MSG_NEW_FIRMWARE_AVAILABLE c=20 r=2
lcd_print_at_PGM(0, 2, PSTR(""));
lcd_puts_at_P(0, 2, PSTR(""));
for (const char *c = version_string; ! is_whitespace_or_nl_or_eol(*c); ++ c)
lcd_implementation_write(*c);
lcd_print_at_PGM(0, 3, _i("Please upgrade."));////MSG_NEW_FIRMWARE_PLEASE_UPGRADE c=20 r=0
lcd_putc(*c);
lcd_puts_at_P(0, 3, _i("Please upgrade."));////MSG_NEW_FIRMWARE_PLEASE_UPGRADE c=20 r=0
tone(BEEPER, 1000);
delay_keep_alive(50);
noTone(BEEPER);
@ -303,8 +303,8 @@ bool show_upgrade_dialog_if_version_newer(const char *version_string)
noTone(BEEPER);
lcd_wait_for_click();
lcd_update_enable(true);
lcd_implementation_clear();
lcd_update();
lcd_clear();
lcd_update(0);
}
// Succeeded.

View file

@ -136,7 +136,6 @@
//#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
//#define DEBUG_BLINK_ACTIVE
//#define DEBUG_DISABLE_FANCHECK //disable fan check (no ISR INT7, check disabled)
//#define DEBUG_DISABLE_FSENSORCHECK //disable fsensor check (no ISR INT7, check disabled)
//#define DEBUG_DUMP_TO_2ND_SERIAL //dump received characters to 2nd serial line

View file

@ -136,7 +136,6 @@
//#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
//#define DEBUG_BLINK_ACTIVE
//#define DEBUG_DISABLE_FANCHECK //disable fan check (no ISR INT7, check disabled)
//#define DEBUG_DISABLE_FSENSORCHECK //disable fsensor check (no ISR INT7, check disabled)
//#define DEBUG_DUMP_TO_2ND_SERIAL //dump received characters to 2nd serial line

View file

@ -96,15 +96,17 @@
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
//Silent mode limits
#define SILENT_MAX_ACCEL 960 // max axxeleration in silent mode in mm/s^2
#define SILENT_MAX_ACCEL_ST (100*SILENT_MAX_ACCEL) // max accel in steps/s^2
#define SILENT_MAX_FEEDRATE 172 //max feedrate in mm/s, because mode switched to normal for homming , this value limits also homing, it should be greater (172mm/s=9600mm/min>2700mm/min)
//#define SILENT_MAX_ACCEL 960 // max axxeleration in silent mode in mm/s^2
//#define SILENT_MAX_ACCEL_ST (100*SILENT_MAX_ACCEL) // max accel in steps/s^2
//#define SILENT_MAX_FEEDRATE 172 //max feedrate in mm/s, because mode switched to normal for homming , this value limits also homing, it should be greater (172mm/s=9600mm/min>2700mm/min)
//Normal mode limits
#define NORMAL_MAX_ACCEL 2500 // Y-axis max axxeleration in normal mode in mm/s^2
#define NORMAL_MAX_ACCEL_ST (100*NORMAL_MAX_ACCEL) // max accel in steps/s^2
#define NORMAL_MAX_FEEDRATE 200 //max feedrate in mm/s, because mode switched to normal for homming , this value limits also homing, it should be greater (172mm/s=9600mm/min>2700mm/min)
//#define NORMAL_MAX_ACCEL 2500 // Y-axis max axxeleration in normal mode in mm/s^2
//#define NORMAL_MAX_ACCEL_ST (100*NORMAL_MAX_ACCEL) // max accel in steps/s^2
//#define NORMAL_MAX_FEEDRATE 200 //max feedrate in mm/s, because mode switched to normal for homming , this value limits also homing, it should be greater (172mm/s=9600mm/min>2700mm/min)
//#define FEEDRATE_LIMIT //limitation method for normal/silent
//#define ACCEL_LIMIT //limitation method for normal/silent
//#define SIMPLE_ACCEL_LIMIT //new limitation method for normal/silent
//number of bytes from end of the file to start check
@ -135,6 +137,9 @@
// Filament sensor
#define PAT9125
// Backlash -
//#define BACKLASH_X
//#define BACKLASH_Y
// Disable some commands
#define _DISABLE_M42_M226
@ -172,7 +177,6 @@
//#define DEBUG_DISABLE_FORCE_SELFTEST //disable force selftest
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
//#define DEBUG_BLINK_ACTIVE
//#define DEBUG_DISABLE_FANCHECK //disable fan check (no ISR INT7, check disabled)
//#define DEBUG_DISABLE_FSENSORCHECK //disable fsensor check (no ISR INT7, check disabled)
#define DEBUG_DUMP_TO_2ND_SERIAL //dump received characters to 2nd serial line
@ -181,7 +185,6 @@
#define CMD_DIAGNOSTICS //Show cmd queue length on printer display
#endif /* DEBUG_BUILD */
//#define EXPERIMENTAL_FEATURES
#define TMC2130_LINEARITY_CORRECTION
#define TMC2130_LINEARITY_CORRECTION_XYZ
//#define TMC2130_VARIABLE_RESOLUTION