Styling adjustments (PR#2668 & PR#2670)

Keep "astyled" reformatting
This commit is contained in:
Scott Lahteine 2015-10-02 23:08:58 -07:00 committed by Richard Wackerbarth
parent b5fb7075b9
commit 0c7f7ebcfb
100 changed files with 10213 additions and 10618 deletions

View File

@ -74,10 +74,10 @@
#endif
#if ENABLED(MINIPANEL)
#define DOGLCD
#define ULTIPANEL
#define NEWPANEL
#define DEFAULT_LCD_CONTRAST 17
#define DOGLCD
#define ULTIPANEL
#define NEWPANEL
#define DEFAULT_LCD_CONTRAST 17
#endif
/**
@ -135,9 +135,9 @@
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
#if ENABLED(SAV_3DLCD)
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister
#define ULTIPANEL
#define NEWPANEL
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister
#define ULTIPANEL
#define NEWPANEL
#endif
#if ENABLED(ULTIPANEL)
@ -205,7 +205,7 @@
#endif
#if ENABLED(U8GLIB_SSD1306)
#undef HAS_LCD_CONTRAST
#endif
#endif
#endif
#else // CONFIGURATION_LCD
@ -285,13 +285,13 @@
#define SERVO_LEVELING (defined(AUTO_BED_LEVELING_FEATURE) && defined(Z_ENDSTOP_SERVO_NR))
/**
* Sled Options
*/
/**
* Sled Options
*/
#if ENABLED(Z_PROBE_SLED)
#define Z_SAFE_HOMING
#endif
/**
* MAX_STEP_FREQUENCY differs for TOSHIBA
*/

View File

@ -1,5 +1,5 @@
#define M100_FREE_MEMORY_DUMPER // Comment out to remove Dump sub-command
#define M100_FREE_MEMORY_CORRUPTOR // Comment out to remove Corrupt sub-command
#define M100_FREE_MEMORY_DUMPER // Comment out to remove Dump sub-command
#define M100_FREE_MEMORY_CORRUPTOR // Comment out to remove Corrupt sub-command
// M100 Free Memory Watcher
@ -7,14 +7,14 @@
// This code watches the free memory block between the bottom of the heap and the top of the stack.
// This memory block is initialized and watched via the M100 command.
//
// M100 I Initializes the free memory block and prints vitals statistics about the area
// M100 F Identifies how much of the free memory block remains free and unused. It also
// detects and reports any corruption within the free memory block that may have
// happened due to errant firmware.
// M100 D Does a hex display of the free memory block along with a flag for any errant
// data that does not match the expected value.
// M100 C x Corrupts x locations within the free memory block. This is useful to check the
// correctness of the M100 F and M100 D commands.
// M100 I Initializes the free memory block and prints vitals statistics about the area
// M100 F Identifies how much of the free memory block remains free and unused. It also
// detects and reports any corruption within the free memory block that may have
// happened due to errant firmware.
// M100 D Does a hex display of the free memory block along with a flag for any errant
// data that does not match the expected value.
// M100 C x Corrupts x locations within the free memory block. This is useful to check the
// correctness of the M100 F and M100 D commands.
//
// Initial version by Roxy-3DPrintBoard
//
@ -24,7 +24,7 @@
#include "Marlin.h"
#if ENABLED(M100_FREE_MEMORY_WATCHER)
extern void *__brkval;
extern void* __brkval;
extern size_t __heap_start, __heap_end, __flp;
@ -34,12 +34,12 @@ extern size_t __heap_start, __heap_end, __flp;
float code_value();
long code_value_long();
bool code_seen(char );
void serial_echopair_P(const char *, float );
void serial_echopair_P(const char *, double );
void serial_echopair_P(const char *, unsigned long );
void serial_echopair_P(const char *, int );
void serial_echopair_P(const char *, long );
bool code_seen(char);
void serial_echopair_P(const char*, float);
void serial_echopair_P(const char*, double);
void serial_echopair_P(const char*, unsigned long);
void serial_echopair_P(const char*, int);
void serial_echopair_P(const char*, long);
@ -48,188 +48,168 @@ void serial_echopair_P(const char *, long );
// Utility functions used by M100 to get its work done.
//
unsigned char *top_of_stack();
void prt_hex_nibble( unsigned int );
void prt_hex_byte(unsigned int );
void prt_hex_word(unsigned int );
int how_many_E5s_are_here( unsigned char *);
unsigned char* top_of_stack();
void prt_hex_nibble(unsigned int);
void prt_hex_byte(unsigned int);
void prt_hex_word(unsigned int);
int how_many_E5s_are_here(unsigned char*);
void gcode_M100()
{
static int m100_not_initialized=1;
unsigned char *sp, *ptr;
int i, j, n;
//
// M100 D dumps the free memory block from __brkval to the stack pointer.
// malloc() eats memory from the start of the block and the stack grows
// up from the bottom of the block. Solid 0xE5's indicate nothing has
// used that memory yet. There should not be anything but 0xE5's within
// the block of 0xE5's. If there is, that would indicate memory corruption
// probably caused by bad pointers. Any unexpected values will be flagged in
// the right hand column to help spotting them.
//
void gcode_M100() {
static int m100_not_initialized = 1;
unsigned char* sp, *ptr;
int i, j, n;
//
// M100 D dumps the free memory block from __brkval to the stack pointer.
// malloc() eats memory from the start of the block and the stack grows
// up from the bottom of the block. Solid 0xE5's indicate nothing has
// used that memory yet. There should not be anything but 0xE5's within
// the block of 0xE5's. If there is, that would indicate memory corruption
// probably caused by bad pointers. Any unexpected values will be flagged in
// the right hand column to help spotting them.
//
#if ENABLED(M100_FREE_MEMORY_DUMPER) // Disable to remove Dump sub-command
if ( code_seen('D') ) {
ptr = (unsigned char *) __brkval;
//
// We want to start and end the dump on a nice 16 byte boundry even though
// the values we are using are not 16 byte aligned.
//
SERIAL_ECHOPGM("\n__brkval : ");
prt_hex_word( (unsigned int) ptr );
ptr = (unsigned char *) ((unsigned long) ptr & 0xfff0);
sp = top_of_stack();
SERIAL_ECHOPGM("\nStack Pointer : ");
prt_hex_word( (unsigned int) sp );
SERIAL_ECHOPGM("\n");
sp = (unsigned char *) ((unsigned long) sp | 0x000f);
n = sp - ptr;
//
// This is the main loop of the Dump command.
//
while ( ptr < sp ) {
prt_hex_word( (unsigned int) ptr); // Print the address
SERIAL_ECHOPGM(":");
for(i=0; i<16; i++) { // and 16 data bytes
prt_hex_byte( *(ptr+i));
SERIAL_ECHOPGM(" ");
delay(2);
}
SERIAL_ECHO("|"); // now show where non 0xE5's are
for(i=0; i<16; i++) {
delay(2);
if ( *(ptr+i)==0xe5)
SERIAL_ECHOPGM(" ");
else
SERIAL_ECHOPGM("?");
}
SERIAL_ECHO("\n");
ptr += 16;
delay(2);
}
SERIAL_ECHOLNPGM("Done.\n");
return;
}
if (code_seen('D')) {
ptr = (unsigned char*) __brkval;
//
// We want to start and end the dump on a nice 16 byte boundry even though
// the values we are using are not 16 byte aligned.
//
SERIAL_ECHOPGM("\n__brkval : ");
prt_hex_word((unsigned int) ptr);
ptr = (unsigned char*)((unsigned long) ptr & 0xfff0);
sp = top_of_stack();
SERIAL_ECHOPGM("\nStack Pointer : ");
prt_hex_word((unsigned int) sp);
SERIAL_ECHOPGM("\n");
sp = (unsigned char*)((unsigned long) sp | 0x000f);
n = sp - ptr;
//
// This is the main loop of the Dump command.
//
while (ptr < sp) {
prt_hex_word((unsigned int) ptr); // Print the address
SERIAL_ECHOPGM(":");
for (i = 0; i < 16; i++) { // and 16 data bytes
prt_hex_byte(*(ptr + i));
SERIAL_ECHOPGM(" ");
delay(2);
}
SERIAL_ECHO("|"); // now show where non 0xE5's are
for (i = 0; i < 16; i++) {
delay(2);
if (*(ptr + i) == 0xe5)
SERIAL_ECHOPGM(" ");
else
SERIAL_ECHOPGM("?");
}
SERIAL_ECHO("\n");
ptr += 16;
delay(2);
}
SERIAL_ECHOLNPGM("Done.\n");
return;
}
#endif
//
// M100 F requests the code to return the number of free bytes in the memory pool along with
// other vital statistics that define the memory pool.
//
if ( code_seen('F') ) {
int max_addr = (int) __brkval;
int max_cnt = 0;
int block_cnt = 0;
ptr = (unsigned char *) __brkval;
sp = top_of_stack();
n = sp - ptr;
// Scan through the range looking for the biggest block of 0xE5's we can find
for(i=0; i<n; i++) {
if ( *(ptr+i) == (unsigned char) 0xe5) {
j = how_many_E5s_are_here( (unsigned char *) ptr+i );
if ( j>8) {
SERIAL_ECHOPAIR("Found ", j );
SERIAL_ECHOPGM(" bytes free at 0x");
prt_hex_word( (int) ptr+i );
SERIAL_ECHOPGM("\n");
i += j;
block_cnt++;
}
if ( j>max_cnt) { // We don't do anything with this information yet
max_cnt = j; // but we do know where the biggest free memory block is.
max_addr = (int) ptr+i;
}
}
}
if (block_cnt>1)
SERIAL_ECHOLNPGM("\nMemory Corruption detected in free memory area.\n");
SERIAL_ECHO("\nDone.\n");
return;
}
//
// M100 C x Corrupts x locations in the free memory pool and reports the locations of the corruption.
// This is useful to check the correctness of the M100 D and the M100 F commands.
//
//
// M100 F requests the code to return the number of free bytes in the memory pool along with
// other vital statistics that define the memory pool.
//
if (code_seen('F')) {
int max_addr = (int) __brkval;
int max_cnt = 0;
int block_cnt = 0;
ptr = (unsigned char*) __brkval;
sp = top_of_stack();
n = sp - ptr;
// Scan through the range looking for the biggest block of 0xE5's we can find
for (i = 0; i < n; i++) {
if (*(ptr + i) == (unsigned char) 0xe5) {
j = how_many_E5s_are_here((unsigned char*) ptr + i);
if (j > 8) {
SERIAL_ECHOPAIR("Found ", j);
SERIAL_ECHOPGM(" bytes free at 0x");
prt_hex_word((int) ptr + i);
SERIAL_ECHOPGM("\n");
i += j;
block_cnt++;
}
if (j > max_cnt) { // We don't do anything with this information yet
max_cnt = j; // but we do know where the biggest free memory block is.
max_addr = (int) ptr + i;
}
}
}
if (block_cnt > 1)
SERIAL_ECHOLNPGM("\nMemory Corruption detected in free memory area.\n");
SERIAL_ECHO("\nDone.\n");
return;
}
//
// M100 C x Corrupts x locations in the free memory pool and reports the locations of the corruption.
// This is useful to check the correctness of the M100 D and the M100 F commands.
//
#if ENABLED(M100_FREE_MEMORY_CORRUPTOR)
if ( code_seen('C') ) {
int x; // x gets the # of locations to corrupt within the memory pool
x = code_value();
SERIAL_ECHOLNPGM("Corrupting free memory block.\n");
ptr = (unsigned char *) __brkval;
SERIAL_ECHOPAIR("\n__brkval : ",(long) ptr );
ptr += 8;
sp = top_of_stack();
SERIAL_ECHOPAIR("\nStack Pointer : ",(long) sp );
SERIAL_ECHOLNPGM("\n");
n = sp - ptr - 64; // -64 just to keep us from finding interrupt activity that
// has altered the stack.
j = n / (x+1);
for(i=1; i<=x; i++) {
*(ptr+(i*j)) = i;
SERIAL_ECHO("\nCorrupting address: 0x");
prt_hex_word( (unsigned int) (ptr+(i*j)) );
}
SERIAL_ECHOLNPGM("\n");
return;
}
if (code_seen('C')) {
int x; // x gets the # of locations to corrupt within the memory pool
x = code_value();
SERIAL_ECHOLNPGM("Corrupting free memory block.\n");
ptr = (unsigned char*) __brkval;
SERIAL_ECHOPAIR("\n__brkval : ", (long) ptr);
ptr += 8;
sp = top_of_stack();
SERIAL_ECHOPAIR("\nStack Pointer : ", (long) sp);
SERIAL_ECHOLNPGM("\n");
n = sp - ptr - 64; // -64 just to keep us from finding interrupt activity that
// has altered the stack.
j = n / (x + 1);
for (i = 1; i <= x; i++) {
*(ptr + (i * j)) = i;
SERIAL_ECHO("\nCorrupting address: 0x");
prt_hex_word((unsigned int)(ptr + (i * j)));
}
SERIAL_ECHOLNPGM("\n");
return;
}
#endif
//
// M100 I Initializes the free memory pool so it can be watched and prints vital
// statistics that define the free memory pool.
//
if (m100_not_initialized || code_seen('I') ) { // If no sub-command is specified, the first time
SERIAL_ECHOLNPGM("Initializing free memory block.\n"); // this happens, it will Initialize.
ptr = (unsigned char *) __brkval; // Repeated M100 with no sub-command will not destroy the
SERIAL_ECHOPAIR("\n__brkval : ",(long) ptr ); // state of the initialized free memory pool.
ptr += 8;
sp = top_of_stack();
SERIAL_ECHOPAIR("\nStack Pointer : ",(long) sp );
SERIAL_ECHOLNPGM("\n");
n = sp - ptr - 64; // -64 just to keep us from finding interrupt activity that
// has altered the stack.
SERIAL_ECHO( n );
SERIAL_ECHOLNPGM(" bytes of memory initialized.\n");
for(i=0; i<n; i++)
*(ptr+i) = (unsigned char) 0xe5;
for(i=0; i<n; i++) {
if ( *(ptr+i) != (unsigned char) 0xe5 ) {
SERIAL_ECHOPAIR("? address : ", (unsigned long) ptr+i );
SERIAL_ECHOPAIR("=", *(ptr+i) );
SERIAL_ECHOLNPGM("\n");
}
}
m100_not_initialized = 0;
SERIAL_ECHOLNPGM("Done.\n");
return;
}
return;
//
// M100 I Initializes the free memory pool so it can be watched and prints vital
// statistics that define the free memory pool.
//
if (m100_not_initialized || code_seen('I')) { // If no sub-command is specified, the first time
SERIAL_ECHOLNPGM("Initializing free memory block.\n"); // this happens, it will Initialize.
ptr = (unsigned char*) __brkval; // Repeated M100 with no sub-command will not destroy the
SERIAL_ECHOPAIR("\n__brkval : ", (long) ptr); // state of the initialized free memory pool.
ptr += 8;
sp = top_of_stack();
SERIAL_ECHOPAIR("\nStack Pointer : ", (long) sp);
SERIAL_ECHOLNPGM("\n");
n = sp - ptr - 64; // -64 just to keep us from finding interrupt activity that
// has altered the stack.
SERIAL_ECHO(n);
SERIAL_ECHOLNPGM(" bytes of memory initialized.\n");
for (i = 0; i < n; i++)
*(ptr + i) = (unsigned char) 0xe5;
for (i = 0; i < n; i++) {
if (*(ptr + i) != (unsigned char) 0xe5) {
SERIAL_ECHOPAIR("? address : ", (unsigned long) ptr + i);
SERIAL_ECHOPAIR("=", *(ptr + i));
SERIAL_ECHOLNPGM("\n");
}
}
m100_not_initialized = 0;
SERIAL_ECHOLNPGM("Done.\n");
return;
}
return;
}
// top_of_stack() returns the location of a variable on its stack frame. The value returned is above
// the stack once the function returns to the caller.
unsigned char *top_of_stack() {
unsigned char* top_of_stack() {
unsigned char x;
return &x + 1; // x is pulled on return;
}
@ -238,39 +218,34 @@ unsigned char *top_of_stack() {
// 3 support routines to print hex numbers. We can print a nibble, byte and word
//
void prt_hex_nibble( unsigned int n )
{
if ( n <= 9 )
SERIAL_ECHO(n);
else
SERIAL_ECHO( (char) ('A'+n-10) );
delay(2);
void prt_hex_nibble(unsigned int n) {
if (n <= 9)
SERIAL_ECHO(n);
else
SERIAL_ECHO((char)('A' + n - 10));
delay(2);
}
void prt_hex_byte(unsigned int b)
{
prt_hex_nibble( ( b & 0xf0 ) >> 4 );
prt_hex_nibble( b & 0x0f );
void prt_hex_byte(unsigned int b) {
prt_hex_nibble((b & 0xf0) >> 4);
prt_hex_nibble(b & 0x0f);
}
void prt_hex_word(unsigned int w)
{
prt_hex_byte( ( w & 0xff00 ) >> 8 );
prt_hex_byte( w & 0x0ff );
void prt_hex_word(unsigned int w) {
prt_hex_byte((w & 0xff00) >> 8);
prt_hex_byte(w & 0x0ff);
}
// how_many_E5s_are_here() is a utility function to easily find out how many 0xE5's are
// at the specified location. Having this logic as a function simplifies the search code.
//
int how_many_E5s_are_here( unsigned char *p)
{
int n;
for(n=0; n<32000; n++) {
if ( *(p+n) != (unsigned char) 0xe5)
return n-1;
}
return -1;
int how_many_E5s_are_here(unsigned char* p) {
int n;
for (n = 0; n < 32000; n++) {
if (*(p + n) != (unsigned char) 0xe5)
return n - 1;
}
return -1;
}
#endif

View File

@ -92,15 +92,15 @@ extern const char echomagic[] PROGMEM;
#define SERIAL_ECHOPAIR(name,value) do{ serial_echopair_P(PSTR(name),(value)); }while(0)
void serial_echopair_P(const char *s_P, int v);
void serial_echopair_P(const char *s_P, long v);
void serial_echopair_P(const char *s_P, float v);
void serial_echopair_P(const char *s_P, double v);
void serial_echopair_P(const char *s_P, unsigned long v);
void serial_echopair_P(const char* s_P, int v);
void serial_echopair_P(const char* s_P, long v);
void serial_echopair_P(const char* s_P, float v);
void serial_echopair_P(const char* s_P, double v);
void serial_echopair_P(const char* s_P, unsigned long v);
// Things to write to serial from Program memory. Saves 400 to 2k of RAM.
FORCE_INLINE void serialprintPGM(const char *str) {
FORCE_INLINE void serialprintPGM(const char* str) {
char ch;
while ((ch = pgm_read_byte(str))) {
MYSERIAL.write(ch);
@ -112,7 +112,7 @@ void get_command();
void idle(); // the standard idle routine calls manage_inactivity(false)
void manage_inactivity(bool ignore_stepper_queue=false);
void manage_inactivity(bool ignore_stepper_queue = false);
#if ENABLED(DUAL_X_CARRIAGE) && HAS_X_ENABLE && HAS_X2_ENABLE
#define enable_x() do { X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); } while (0)
@ -194,9 +194,9 @@ void manage_inactivity(bool ignore_stepper_queue=false);
* A_AXIS and B_AXIS are used by COREXY printers
* X_HEAD and Y_HEAD is used for systems that don't have a 1:1 relationship between X_AXIS and X Head movement, like CoreXY bots.
*/
enum AxisEnum {X_AXIS=0, A_AXIS=0, Y_AXIS=1, B_AXIS=1, Z_AXIS=2, C_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5, Z_HEAD=5};
enum AxisEnum {X_AXIS = 0, A_AXIS = 0, Y_AXIS = 1, B_AXIS = 1, Z_AXIS = 2, C_AXIS = 2, E_AXIS = 3, X_HEAD = 4, Y_HEAD = 5, Z_HEAD = 5};
enum EndstopEnum {X_MIN=0, Y_MIN=1, Z_MIN=2, Z_MIN_PROBE=3, X_MAX=4, Y_MAX=5, Z_MAX=6, Z2_MIN=7, Z2_MAX=8};
enum EndstopEnum {X_MIN = 0, Y_MIN = 1, Z_MIN = 2, Z_MIN_PROBE = 3, X_MAX = 4, Y_MAX = 5, Z_MAX = 6, Z2_MIN = 7, Z2_MAX = 8};
void enable_all_steppers();
void disable_all_steppers();
@ -206,7 +206,7 @@ void ok_to_send();
void reset_bed_level();
void prepare_move();
void kill(const char *);
void kill(const char*);
void Stop();
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
@ -230,8 +230,8 @@ extern bool Running;
inline bool IsRunning() { return Running; }
inline bool IsStopped() { return !Running; }
bool enqueuecommand(const char *cmd); //put a single ASCII command at the end of the current buffer or return false when it is full
void enqueuecommands_P(const char *cmd); //put one or many ASCII commands at the end of the current buffer, read from flash
bool enqueuecommand(const char* cmd); //put a single ASCII command at the end of the current buffer or return false when it is full
void enqueuecommands_P(const char* cmd); //put one or many ASCII commands at the end of the current buffer, read from flash
void prepare_arc_move(char isclockwise);
void clamp_to_software_endstops(float target[3]);
@ -347,7 +347,7 @@ extern millis_t print_job_stop_ms;
extern uint8_t active_extruder;
#if ENABLED(DIGIPOT_I2C)
extern void digipot_i2c_set_current( int channel, float current );
extern void digipot_i2c_set_current(int channel, float current);
extern void digipot_i2c_init();
#endif

View File

@ -15,7 +15,7 @@
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
Modified 23 November 2006 by David A. Mellis
Modified 28 September 2010 by Mark Sproul
*/
@ -24,7 +24,7 @@
#include "MarlinSerial.h"
#ifndef USBCON
// this next line disables the entire HardwareSerial.cpp,
// this next line disables the entire HardwareSerial.cpp,
// this is so I can support Attiny series and any other chip without a UART
#if defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)
@ -74,7 +74,7 @@ void MarlinSerial::begin(long baud) {
useU2X = false;
}
#endif
if (useU2X) {
M_UCSRxA = BIT(M_U2Xx);
baud_setting = (F_CPU / 4 / baud - 1) / 2;
@ -95,14 +95,15 @@ void MarlinSerial::begin(long baud) {
void MarlinSerial::end() {
cbi(M_UCSRxB, M_RXENx);
cbi(M_UCSRxB, M_TXENx);
cbi(M_UCSRxB, M_RXCIEx);
cbi(M_UCSRxB, M_RXCIEx);
}
int MarlinSerial::peek(void) {
if (rx_buffer.head == rx_buffer.tail) {
return -1;
} else {
}
else {
return rx_buffer.buffer[rx_buffer.tail];
}
}
@ -162,7 +163,8 @@ void MarlinSerial::print(long n, int base) {
n = -n;
}
printNumber(n, 10);
} else {
}
else {
printNumber(n, base);
}
}
@ -178,10 +180,10 @@ void MarlinSerial::print(double n, int digits) {
void MarlinSerial::println(void) {
print('\r');
print('\n');
print('\n');
}
void MarlinSerial::println(const String &s) {
void MarlinSerial::println(const String& s) {
print(s);
println();
}
@ -229,13 +231,13 @@ void MarlinSerial::println(double n, int digits) {
// Private Methods /////////////////////////////////////////////////////////////
void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars.
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;
@ -243,23 +245,23 @@ void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
}
for (; i > 0; i--)
print((char) (buf[i - 1] < 10 ?
'0' + buf[i - 1] :
'A' + buf[i - 1] - 10));
print((char)(buf[i - 1] < 10 ?
'0' + buf[i - 1] :
'A' + buf[i - 1] - 10));
}
void MarlinSerial::printFloat(double number, uint8_t digits) {
// Handle negative numbers
if (number < 0.0) {
print('-');
number = -number;
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
@ -275,8 +277,8 @@ void MarlinSerial::printFloat(double number, uint8_t digits) {
remainder *= 10.0;
int toPrint = int(remainder);
print(toPrint);
remainder -= toPrint;
}
remainder -= toPrint;
}
}
// Preinstantiate Objects //////////////////////////////////////////////////////

View File

@ -29,9 +29,9 @@
// The presence of the UBRRH register is used to detect a UART.
#define UART_PRESENT(port) ((port == 0 && (defined(UBRRH) || defined(UBRR0H))) || \
(port == 1 && defined(UBRR1H)) || (port == 2 && defined(UBRR2H)) || \
(port == 3 && defined(UBRR3H)))
(port == 1 && defined(UBRR1H)) || (port == 2 && defined(UBRR2H)) || \
(port == 3 && defined(UBRR3H)))
// These are macros to build serial port register names for the selected SERIAL_PORT (C preprocessor
// requires two levels of indirection to expand macro values properly)
#define SERIAL_REGNAME(registerbase,number,suffix) SERIAL_REGNAME_INTERNAL(registerbase,number,suffix)
@ -41,15 +41,15 @@
#define SERIAL_REGNAME_INTERNAL(registerbase,number,suffix) registerbase##number##suffix
#endif
// Registers used by MarlinSerial class (these are expanded
// Registers used by MarlinSerial class (these are expanded
// depending on selected serial port
#define M_UCSRxA SERIAL_REGNAME(UCSR,SERIAL_PORT,A) // defines M_UCSRxA to be UCSRnA where n is the serial port number
#define M_UCSRxB SERIAL_REGNAME(UCSR,SERIAL_PORT,B)
#define M_RXENx SERIAL_REGNAME(RXEN,SERIAL_PORT,)
#define M_TXENx SERIAL_REGNAME(TXEN,SERIAL_PORT,)
#define M_RXCIEx SERIAL_REGNAME(RXCIE,SERIAL_PORT,)
#define M_UDREx SERIAL_REGNAME(UDRE,SERIAL_PORT,)
#define M_UDRx SERIAL_REGNAME(UDR,SERIAL_PORT,)
#define M_UCSRxB SERIAL_REGNAME(UCSR,SERIAL_PORT,B)
#define M_RXENx SERIAL_REGNAME(RXEN,SERIAL_PORT,)
#define M_TXENx SERIAL_REGNAME(TXEN,SERIAL_PORT,)
#define M_RXCIEx SERIAL_REGNAME(RXCIE,SERIAL_PORT,)
#define M_UDREx SERIAL_REGNAME(UDRE,SERIAL_PORT,)
#define M_UDRx SERIAL_REGNAME(UDR,SERIAL_PORT,)
#define M_UBRRxH SERIAL_REGNAME(UBRR,SERIAL_PORT,H)
#define M_UBRRxL SERIAL_REGNAME(UBRR,SERIAL_PORT,L)
#define M_RXCx SERIAL_REGNAME(RXC,SERIAL_PORT,)
@ -99,7 +99,6 @@ class MarlinSerial { //: public Stream
FORCE_INLINE void write(uint8_t c) {
while (!TEST(M_UCSRxA, M_UDREx))
;
M_UDRx = c;
}
@ -124,10 +123,10 @@ class MarlinSerial { //: public Stream
void printFloat(double, uint8_t);
public:
FORCE_INLINE void write(const char *str) { while (*str) write(*str++); }
FORCE_INLINE void write(const uint8_t *buffer, size_t size) { while (size--) write(*buffer++); }
FORCE_INLINE void print(const String &s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
FORCE_INLINE void print(const char *str) { write(str); }
FORCE_INLINE void write(const char* str) { while (*str) write(*str++); }
FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
FORCE_INLINE void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
FORCE_INLINE void print(const char* str) { write(str); }
void print(char, int = BYTE);
void print(unsigned char, int = BYTE);
@ -137,7 +136,7 @@ class MarlinSerial { //: public Stream
void print(unsigned long, int = DEC);
void print(double, int = 2);
void println(const String &s);
void println(const String& s);
void println(const char[]);
void println(char, int = BYTE);
void println(unsigned char, int = BYTE);

File diff suppressed because it is too large Load Diff

View File

@ -4,363 +4,363 @@
* Test configuration values for errors at compile-time.
*/
#ifndef SANITYCHECK_H
#define SANITYCHECK_H
#define SANITYCHECK_H
/**
* Dual Stepper Drivers
*/
#if ENABLED(Z_DUAL_STEPPER_DRIVERS) && ENABLED(Y_DUAL_STEPPER_DRIVERS)
#error You cannot have dual stepper drivers for both Y and Z.
/**
* Dual Stepper Drivers
*/
#if ENABLED(Z_DUAL_STEPPER_DRIVERS) && ENABLED(Y_DUAL_STEPPER_DRIVERS)
#error You cannot have dual stepper drivers for both Y and Z.
#endif
/**
* Progress Bar
*/
#if ENABLED(LCD_PROGRESS_BAR)
#if DISABLED(SDSUPPORT)
#error LCD_PROGRESS_BAR requires SDSUPPORT.
#endif
#if ENABLED(DOGLCD)
#error LCD_PROGRESS_BAR does not apply to graphical displays.
#endif
#if ENABLED(FILAMENT_LCD_DISPLAY)
#error LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both.
#endif
#endif
/**
* Babystepping
*/
#if ENABLED(BABYSTEPPING)
#if ENABLED(COREXY) && ENABLED(BABYSTEP_XY)
#error BABYSTEPPING only implemented for Z axis on CoreXY.
#endif
#if ENABLED(SCARA)
#error BABYSTEPPING is not implemented for SCARA yet.
#endif
#if ENABLED(DELTA) && ENABLED(BABYSTEP_XY)
#error BABYSTEPPING only implemented for Z axis on deltabots.
#endif
#endif
/**
* Filament Change with Extruder Runout Prevention
*/
#if ENABLED(FILAMENTCHANGEENABLE) && ENABLED(EXTRUDER_RUNOUT_PREVENT)
#error EXTRUDER_RUNOUT_PREVENT currently incompatible with FILAMENTCHANGE.
#endif
/**
* Options only for EXTRUDERS > 1
*/
#if EXTRUDERS > 1
#if EXTRUDERS > 4
#error The maximum number of EXTRUDERS in Marlin is 4.
#endif
/**
* Progress Bar
*/
#if ENABLED(LCD_PROGRESS_BAR)
#if DISABLED(SDSUPPORT)
#error LCD_PROGRESS_BAR requires SDSUPPORT.
#endif
#if ENABLED(DOGLCD)
#error LCD_PROGRESS_BAR does not apply to graphical displays.
#endif
#if ENABLED(FILAMENT_LCD_DISPLAY)
#error LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both.
#endif
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
#error EXTRUDERS must be 1 with TEMP_SENSOR_1_AS_REDUNDANT.
#endif
/**
* Babystepping
*/
#if ENABLED(BABYSTEPPING)
#if ENABLED(COREXY) && ENABLED(BABYSTEP_XY)
#error BABYSTEPPING only implemented for Z axis on CoreXY.
#endif
#if ENABLED(SCARA)
#error BABYSTEPPING is not implemented for SCARA yet.
#endif
#if ENABLED(DELTA) && ENABLED(BABYSTEP_XY)
#error BABYSTEPPING only implemented for Z axis on deltabots.
#endif
#if ENABLED(HEATERS_PARALLEL)
#error EXTRUDERS must be 1 with HEATERS_PARALLEL.
#endif
/**
* Filament Change with Extruder Runout Prevention
*/
#if ENABLED(FILAMENTCHANGEENABLE) && ENABLED(EXTRUDER_RUNOUT_PREVENT)
#error EXTRUDER_RUNOUT_PREVENT currently incompatible with FILAMENTCHANGE.
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
#error EXTRUDERS must be 1 with Y_DUAL_STEPPER_DRIVERS.
#endif
/**
* Options only for EXTRUDERS > 1
*/
#if EXTRUDERS > 1
#if EXTRUDERS > 4
#error The maximum number of EXTRUDERS in Marlin is 4.
#endif
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
#error EXTRUDERS must be 1 with TEMP_SENSOR_1_AS_REDUNDANT.
#endif
#if ENABLED(HEATERS_PARALLEL)
#error EXTRUDERS must be 1 with HEATERS_PARALLEL.
#endif
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
#error EXTRUDERS must be 1 with Y_DUAL_STEPPER_DRIVERS.
#endif
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
#error EXTRUDERS must be 1 with Z_DUAL_STEPPER_DRIVERS.
#endif
#endif // EXTRUDERS > 1
/**
* Limited number of servos
*/
#if NUM_SERVOS > 4
#error The maximum number of SERVOS in Marlin is 4.
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
#error EXTRUDERS must be 1 with Z_DUAL_STEPPER_DRIVERS.
#endif
#if defined(NUM_SERVOS) && NUM_SERVOS > 0
#if X_ENDSTOP_SERVO_NR >= 0 || Y_ENDSTOP_SERVO_NR >= 0 || Z_ENDSTOP_SERVO_NR >= 0
#if X_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error X_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#elif Y_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error Y_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#elif Z_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error Z_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#endif // EXTRUDERS > 1
/**
* Limited number of servos
*/
#if NUM_SERVOS > 4
#error The maximum number of SERVOS in Marlin is 4.
#endif
#if defined(NUM_SERVOS) && NUM_SERVOS > 0
#if X_ENDSTOP_SERVO_NR >= 0 || Y_ENDSTOP_SERVO_NR >= 0 || Z_ENDSTOP_SERVO_NR >= 0
#if X_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error X_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#elif Y_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error Y_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#elif Z_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error Z_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS.
#endif
#endif
#endif
/**
* Servo deactivation depends on servo endstops
*/
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_SERVO_ENDSTOPS
#error At least one of the ?_ENDSTOP_SERVO_NR is required for DEACTIVATE_SERVOS_AFTER_MOVE.
#endif
/**
* Required LCD language
*/
#if DISABLED(DOGLCD) && ENABLED(ULTRA_LCD) && DISABLED(DISPLAY_CHARSET_HD44780_JAPAN) && DISABLED(DISPLAY_CHARSET_HD44780_WESTERN) && DISABLED(DISPLAY_CHARSET_HD44780_CYRILLIC)
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN or DISPLAY_CHARSET_HD44780_CYRILLIC for your LCD controller.
#endif
/**
* Mesh Bed Leveling
*/
#if ENABLED(MESH_BED_LEVELING)
#if ENABLED(DELTA)
#error MESH_BED_LEVELING does not yet support DELTA printers.
#endif
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#error Select AUTO_BED_LEVELING_FEATURE or MESH_BED_LEVELING, not both.
#endif
#if MESH_NUM_X_POINTS > 7 || MESH_NUM_Y_POINTS > 7
#error MESH_NUM_X_POINTS and MESH_NUM_Y_POINTS need to be less than 8.
#endif
#endif
/**
* Auto Bed Leveling
*/
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
/**
* Require a Z min pin
*/
#if !PIN_EXISTS(Z_MIN)
#if !PIN_EXISTS(Z_MIN_PROBE) || (DISABLED(Z_MIN_PROBE_ENDSTOP) || ENABLED(DISABLE_Z_MIN_PROBE_ENDSTOP)) // It's possible for someone to set a pin for the Z probe, but not enable it.
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
#error You must have a Z_MIN or Z_PROBE endstop to enable Z_MIN_PROBE_REPEATABILITY_TEST.
#else
#error AUTO_BED_LEVELING_FEATURE requires a Z_MIN or Z_PROBE endstop. Z_MIN_PIN or Z_MIN_PROBE_PIN must point to a valid hardware pin.
#endif
#endif
#endif
/**
* Servo deactivation depends on servo endstops
* Require a Z probe pin if Z_MIN_PROBE_ENDSTOP is enabled.
*/
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_SERVO_ENDSTOPS
#error At least one of the ?_ENDSTOP_SERVO_NR is required for DEACTIVATE_SERVOS_AFTER_MOVE.
#endif
/**
* Required LCD language
*/
#if DISABLED(DOGLCD) && ENABLED(ULTRA_LCD) && DISABLED(DISPLAY_CHARSET_HD44780_JAPAN) && DISABLED(DISPLAY_CHARSET_HD44780_WESTERN) && DISABLED(DISPLAY_CHARSET_HD44780_CYRILLIC)
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN or DISPLAY_CHARSET_HD44780_CYRILLIC for your LCD controller.
#endif
/**
* Mesh Bed Leveling
*/
#if ENABLED(MESH_BED_LEVELING)
#if ENABLED(DELTA)
#error MESH_BED_LEVELING does not yet support DELTA printers.
#endif
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#error Select AUTO_BED_LEVELING_FEATURE or MESH_BED_LEVELING, not both.
#endif
#if MESH_NUM_X_POINTS > 7 || MESH_NUM_Y_POINTS > 7
#error MESH_NUM_X_POINTS and MESH_NUM_Y_POINTS need to be less than 8.
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
#if !PIN_EXISTS(Z_MIN_PROBE)
#error You must have a Z_MIN_PROBE_PIN defined in your pins_XXXX.h file if you enable Z_MIN_PROBE_ENDSTOP.
#endif
// Forcing Servo definitions can break some hall effect sensor setups. Leaving these here for further comment.
//#ifndef NUM_SERVOS
// #error You must have NUM_SERVOS defined and there must be at least 1 configured to use Z_MIN_PROBE_ENDSTOP.
//#endif
//#if defined(NUM_SERVOS) && NUM_SERVOS < 1
// #error You must have at least 1 servo defined for NUM_SERVOS to use Z_MIN_PROBE_ENDSTOP.
//#endif
//#if Z_ENDSTOP_SERVO_NR < 0
// #error You must have Z_ENDSTOP_SERVO_NR set to at least 0 or above to use Z_MIN_PROBE_ENDSTOP.
//#endif
//#ifndef SERVO_ENDSTOP_ANGLES
// #error You must have SERVO_ENDSTOP_ANGLES defined for Z Extend and Retract to use Z_MIN_PROBE_ENDSTOP.
//#endif
#endif
/**
* Auto Bed Leveling
* Check if Probe_Offset * Grid Points is greater than Probing Range
*/
#if ENABLED(AUTO_BED_LEVELING_GRID)
#ifndef DELTA_PROBABLE_RADIUS
// Be sure points are in the right order
#if LEFT_PROBE_BED_POSITION > RIGHT_PROBE_BED_POSITION
#error LEFT_PROBE_BED_POSITION must be less than RIGHT_PROBE_BED_POSITION.
#elif FRONT_PROBE_BED_POSITION > BACK_PROBE_BED_POSITION
#error FRONT_PROBE_BED_POSITION must be less than BACK_PROBE_BED_POSITION.
#endif
// Make sure probing points are reachable
#if LEFT_PROBE_BED_POSITION < MIN_PROBE_X
#error "The given LEFT_PROBE_BED_POSITION can't be reached by the Z probe."
#elif RIGHT_PROBE_BED_POSITION > MAX_PROBE_X
#error "The given RIGHT_PROBE_BED_POSITION can't be reached by the Z probe."
#elif FRONT_PROBE_BED_POSITION < MIN_PROBE_Y
#error "The given FRONT_PROBE_BED_POSITION can't be reached by the Z probe."
#elif BACK_PROBE_BED_POSITION > MAX_PROBE_Y
#error "The given BACK_PROBE_BED_POSITION can't be reached by the Z probe."
#endif
#endif
#else // !AUTO_BED_LEVELING_GRID
// Check the triangulation points
#if ABL_PROBE_PT_1_X < MIN_PROBE_X || ABL_PROBE_PT_1_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_1_X can't be reached by the Z probe."
#elif ABL_PROBE_PT_2_X < MIN_PROBE_X || ABL_PROBE_PT_2_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_2_X can't be reached by the Z probe."
#elif ABL_PROBE_PT_3_X < MIN_PROBE_X || ABL_PROBE_PT_3_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_3_X can't be reached by the Z probe."
#elif ABL_PROBE_PT_1_Y < MIN_PROBE_Y || ABL_PROBE_PT_1_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_1_Y can't be reached by the Z probe."
#elif ABL_PROBE_PT_2_Y < MIN_PROBE_Y || ABL_PROBE_PT_2_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_2_Y can't be reached by the Z probe."
#elif ABL_PROBE_PT_3_Y < MIN_PROBE_Y || ABL_PROBE_PT_3_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_3_Y can't be reached by the Z probe."
#endif
#endif // !AUTO_BED_LEVELING_GRID
#endif // AUTO_BED_LEVELING_FEATURE
/**
* ULTIPANEL encoder
*/
#if ENABLED(ULTIPANEL) && DISABLED(NEWPANEL) && DISABLED(SR_LCD_2W_NL) && !defined(SHIFT_CLK)
#error ULTIPANEL requires some kind of encoder.
#endif
/**
* Delta has limited bed leveling options
*/
#if ENABLED(DELTA)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
/**
* Require a Z min pin
*/
#if !PIN_EXISTS(Z_MIN)
#if !PIN_EXISTS(Z_MIN_PROBE) || (DISABLED(Z_MIN_PROBE_ENDSTOP) || ENABLED(DISABLE_Z_MIN_PROBE_ENDSTOP)) // It's possible for someone to set a pin for the Z probe, but not enable it.
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
#error You must have a Z_MIN or Z_PROBE endstop to enable Z_MIN_PROBE_REPEATABILITY_TEST.
#else
#error AUTO_BED_LEVELING_FEATURE requires a Z_MIN or Z_PROBE endstop. Z_MIN_PIN or Z_MIN_PROBE_PIN must point to a valid hardware pin.
#endif
#endif
#if DISABLED(AUTO_BED_LEVELING_GRID)
#error Only AUTO_BED_LEVELING_GRID is supported with DELTA.
#endif
/**
* Require a Z probe pin if Z_MIN_PROBE_ENDSTOP is enabled.
*/
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
#if !PIN_EXISTS(Z_MIN_PROBE)
#error You must have a Z_MIN_PROBE_PIN defined in your pins_XXXX.h file if you enable Z_MIN_PROBE_ENDSTOP.
#endif
// Forcing Servo definitions can break some hall effect sensor setups. Leaving these here for further comment.
// #ifndef NUM_SERVOS
// #error You must have NUM_SERVOS defined and there must be at least 1 configured to use Z_MIN_PROBE_ENDSTOP.
// #endif
// #if defined(NUM_SERVOS) && NUM_SERVOS < 1
// #error You must have at least 1 servo defined for NUM_SERVOS to use Z_MIN_PROBE_ENDSTOP.
// #endif
// #if Z_ENDSTOP_SERVO_NR < 0
// #error You must have Z_ENDSTOP_SERVO_NR set to at least 0 or above to use Z_MIN_PROBE_ENDSTOP.
// #endif
// #ifndef SERVO_ENDSTOP_ANGLES
// #error You must have SERVO_ENDSTOP_ANGLES defined for Z Extend and Retract to use Z_MIN_PROBE_ENDSTOP.
// #endif
#if ENABLED(Z_PROBE_SLED)
#error You cannot use Z_PROBE_SLED with DELTA.
#endif
/**
* Check if Probe_Offset * Grid Points is greater than Probing Range
*/
#if ENABLED(AUTO_BED_LEVELING_GRID)
#ifndef DELTA_PROBABLE_RADIUS
// Be sure points are in the right order
#if LEFT_PROBE_BED_POSITION > RIGHT_PROBE_BED_POSITION
#error LEFT_PROBE_BED_POSITION must be less than RIGHT_PROBE_BED_POSITION.
#elif FRONT_PROBE_BED_POSITION > BACK_PROBE_BED_POSITION
#error FRONT_PROBE_BED_POSITION must be less than BACK_PROBE_BED_POSITION.
#endif
// Make sure probing points are reachable
#if LEFT_PROBE_BED_POSITION < MIN_PROBE_X
#error "The given LEFT_PROBE_BED_POSITION can't be reached by the Z probe."
#elif RIGHT_PROBE_BED_POSITION > MAX_PROBE_X
#error "The given RIGHT_PROBE_BED_POSITION can't be reached by the Z probe."
#elif FRONT_PROBE_BED_POSITION < MIN_PROBE_Y
#error "The given FRONT_PROBE_BED_POSITION can't be reached by the Z probe."
#elif BACK_PROBE_BED_POSITION > MAX_PROBE_Y
#error "The given BACK_PROBE_BED_POSITION can't be reached by the Z probe."
#endif
#endif
#else // !AUTO_BED_LEVELING_GRID
// Check the triangulation points
#if ABL_PROBE_PT_1_X < MIN_PROBE_X || ABL_PROBE_PT_1_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_1_X can't be reached by the Z probe."
#elif ABL_PROBE_PT_2_X < MIN_PROBE_X || ABL_PROBE_PT_2_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_2_X can't be reached by the Z probe."
#elif ABL_PROBE_PT_3_X < MIN_PROBE_X || ABL_PROBE_PT_3_X > MAX_PROBE_X
#error "The given ABL_PROBE_PT_3_X can't be reached by the Z probe."
#elif ABL_PROBE_PT_1_Y < MIN_PROBE_Y || ABL_PROBE_PT_1_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_1_Y can't be reached by the Z probe."
#elif ABL_PROBE_PT_2_Y < MIN_PROBE_Y || ABL_PROBE_PT_2_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_2_Y can't be reached by the Z probe."
#elif ABL_PROBE_PT_3_Y < MIN_PROBE_Y || ABL_PROBE_PT_3_Y > MAX_PROBE_Y
#error "The given ABL_PROBE_PT_3_Y can't be reached by the Z probe."
#endif
#endif // !AUTO_BED_LEVELING_GRID
#endif // AUTO_BED_LEVELING_FEATURE
/**
* ULTIPANEL encoder
*/
#if ENABLED(ULTIPANEL) && DISABLED(NEWPANEL) && DISABLED(SR_LCD_2W_NL) && !defined(SHIFT_CLK)
#error ULTIPANEL requires some kind of encoder.
#endif
/**
* Delta has limited bed leveling options
*/
#if ENABLED(DELTA)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if DISABLED(AUTO_BED_LEVELING_GRID)
#error Only AUTO_BED_LEVELING_GRID is supported with DELTA.
#endif
#if ENABLED(Z_PROBE_SLED)
#error You cannot use Z_PROBE_SLED with DELTA.
#endif
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
#error Z_MIN_PROBE_REPEATABILITY_TEST is not supported with DELTA yet.
#endif
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
#error Z_MIN_PROBE_REPEATABILITY_TEST is not supported with DELTA yet.
#endif
#endif
/**
* Allen Key Z probe requires Auto Bed Leveling grid and Delta
*/
#if ENABLED(Z_PROBE_ALLEN_KEY) && !(ENABLED(AUTO_BED_LEVELING_GRID) && ENABLED(DELTA))
#error Invalid use of Z_PROBE_ALLEN_KEY.
#endif
#endif
/**
* Dual X Carriage requirements
*/
#if ENABLED(DUAL_X_CARRIAGE)
#if EXTRUDERS == 1 || ENABLED(COREXY) \
|| !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR \
|| !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \
|| !HAS_X_MAX
#error Missing or invalid definitions for DUAL_X_CARRIAGE mode.
#endif
#if X_HOME_DIR != -1 || X2_HOME_DIR != 1
#error Please use canonical x-carriage assignment.
#endif
#endif // DUAL_X_CARRIAGE
/**
* Allen Key Z probe requires Auto Bed Leveling grid and Delta
*/
#if ENABLED(Z_PROBE_ALLEN_KEY) && !(ENABLED(AUTO_BED_LEVELING_GRID) && ENABLED(DELTA))
#error Invalid use of Z_PROBE_ALLEN_KEY.
#endif
/**
* Make sure auto fan pins don't conflict with the fan pin
*/
#if HAS_AUTO_FAN && HAS_FAN
#if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
#error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN.
#elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
#error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN.
#elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
#error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN.
#elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
#error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN.
#endif
/**
* Dual X Carriage requirements
*/
#if ENABLED(DUAL_X_CARRIAGE)
#if EXTRUDERS == 1 || ENABLED(COREXY) \
|| !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR \
|| !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \
|| !HAS_X_MAX
#error Missing or invalid definitions for DUAL_X_CARRIAGE mode.
#endif
#if X_HOME_DIR != -1 || X2_HOME_DIR != 1
#error Please use canonical x-carriage assignment.
#endif
#endif // DUAL_X_CARRIAGE
#if HAS_FAN && CONTROLLERFAN_PIN == FAN_PIN
#error You cannot set CONTROLLERFAN_PIN equal to FAN_PIN.
/**
* Make sure auto fan pins don't conflict with the fan pin
*/
#if HAS_AUTO_FAN && HAS_FAN
#if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
#error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN.
#elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
#error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN.
#elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
#error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN.
#elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
#error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN.
#endif
#endif
/**
* Test Heater, Temp Sensor, and Extruder Pins; Sensor Type must also be set.
*/
#if EXTRUDERS > 3
#if !HAS_HEATER_3
#error HEATER_3_PIN not defined for this board.
#elif !PIN_EXISTS(TEMP_3)
#error TEMP_3_PIN not defined for this board.
#elif !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
#error E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board.
#elif TEMP_SENSOR_3 == 0
#error TEMP_SENSOR_3 is required with 4 EXTRUDERS.
#endif
#elif EXTRUDERS > 2
#if !HAS_HEATER_2
#error HEATER_2_PIN not defined for this board.
#elif !PIN_EXISTS(TEMP_2)
#error TEMP_2_PIN not defined for this board.
#elif !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
#error E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board.
#elif TEMP_SENSOR_2 == 0
#error TEMP_SENSOR_2 is required with 3 or more EXTRUDERS.
#endif
#elif EXTRUDERS > 1
#if !PIN_EXISTS(TEMP_1)
#error TEMP_1_PIN not defined for this board.
#elif !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
#error E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board.
#endif
#endif
#if HAS_FAN && CONTROLLERFAN_PIN == FAN_PIN
#error You cannot set CONTROLLERFAN_PIN equal to FAN_PIN.
#endif
#if EXTRUDERS > 1 || ENABLED(HEATERS_PARALLEL)
#if !HAS_HEATER_1
#error HEATER_1_PIN not defined for this board.
#endif
/**
* Test Heater, Temp Sensor, and Extruder Pins; Sensor Type must also be set.
*/
#if EXTRUDERS > 3
#if !HAS_HEATER_3
#error HEATER_3_PIN not defined for this board.
#elif !PIN_EXISTS(TEMP_3)
#error TEMP_3_PIN not defined for this board.
#elif !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
#error E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board.
#elif TEMP_SENSOR_3 == 0
#error TEMP_SENSOR_3 is required with 4 EXTRUDERS.
#endif
#elif EXTRUDERS > 2
#if !HAS_HEATER_2
#error HEATER_2_PIN not defined for this board.
#elif !PIN_EXISTS(TEMP_2)
#error TEMP_2_PIN not defined for this board.
#elif !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
#error E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board.
#elif TEMP_SENSOR_2 == 0
#error TEMP_SENSOR_2 is required with 3 or more EXTRUDERS.
#endif
#elif EXTRUDERS > 1
#if !PIN_EXISTS(TEMP_1)
#error TEMP_1_PIN not defined for this board.
#elif !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
#error E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board.
#endif
#endif
#if TEMP_SENSOR_1 == 0
#if EXTRUDERS > 1
#error TEMP_SENSOR_1 is required with 2 or more EXTRUDERS.
#elif ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
#error TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT.
#endif
#if EXTRUDERS > 1 || ENABLED(HEATERS_PARALLEL)
#if !HAS_HEATER_1
#error HEATER_1_PIN not defined for this board.
#endif
#endif
#if !HAS_HEATER_0
#error HEATER_0_PIN not defined for this board.
#elif !PIN_EXISTS(TEMP_0)
#error TEMP_0_PIN not defined for this board.
#elif !PIN_EXISTS(E0_STEP) || !PIN_EXISTS(E0_DIR) || !PIN_EXISTS(E0_ENABLE)
#error E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board.
#elif TEMP_SENSOR_0 == 0
#error TEMP_SENSOR_0 is required.
#if TEMP_SENSOR_1 == 0
#if EXTRUDERS > 1
#error TEMP_SENSOR_1 is required with 2 or more EXTRUDERS.
#elif ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
#error TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT.
#endif
#endif
/**
* Warnings for old configurations
*/
#if WATCH_TEMP_PERIOD > 500
#error WATCH_TEMP_PERIOD now uses seconds instead of milliseconds.
#elif DISABLED(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD))
#error Thermal Runaway Protection for hotends is now enabled with THERMAL_PROTECTION_HOTENDS.
#elif DISABLED(THERMAL_PROTECTION_BED) && defined(THERMAL_PROTECTION_BED_PERIOD)
#error Thermal Runaway Protection for the bed is now enabled with THERMAL_PROTECTION_BED.
#elif ENABLED(COREXZ) && ENABLED(Z_LATE_ENABLE)
#error "Z_LATE_ENABLE can't be used with COREXZ."
#elif defined(X_HOME_RETRACT_MM)
#error [XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM.
#elif defined(PROBE_SERVO_DEACTIVATION_DELAY)
#error PROBE_SERVO_DEACTIVATION_DELAY has been replaced with DEACTIVATE_SERVOS_AFTER_MOVE and SERVO_DEACTIVATION_DELAY.
#elif defined(BEEPER)
#error BEEPER is now BEEPER_PIN. Please update your pins definitions.
#elif defined(SDCARDDETECT)
#error SDCARDDETECT is now SD_DETECT_PIN. Please update your pins definitions.
#elif defined(SDCARDDETECTINVERTED)
#error SDCARDDETECTINVERTED is now SD_DETECT_INVERTED. Please update your configuration.
#elif defined(BTENABLED)
#error BTENABLED is now BLUETOOTH. Please update your configuration.
#elif defined(CUSTOM_MENDEL_NAME)
#error CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME. Please update your configuration.
#elif defined(HAS_AUTOMATIC_VERSIONING)
#error HAS_AUTOMATIC_VERSIONING deprecated - use USE_AUTOMATIC_VERSIONING instead
#elif defined(ENABLE_AUTO_BED_LEVELING)
#error ENABLE_AUTO_BED_LEVELING deprecated - use AUTO_BED_LEVELING_FEATURE instead
#endif
#if !HAS_HEATER_0
#error HEATER_0_PIN not defined for this board.
#elif !PIN_EXISTS(TEMP_0)
#error TEMP_0_PIN not defined for this board.
#elif !PIN_EXISTS(E0_STEP) || !PIN_EXISTS(E0_DIR) || !PIN_EXISTS(E0_ENABLE)
#error E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board.
#elif TEMP_SENSOR_0 == 0
#error TEMP_SENSOR_0 is required.
#endif
/**
* Warnings for old configurations
*/
#if WATCH_TEMP_PERIOD > 500
#error WATCH_TEMP_PERIOD now uses seconds instead of milliseconds.
#elif DISABLED(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD))
#error Thermal Runaway Protection for hotends is now enabled with THERMAL_PROTECTION_HOTENDS.
#elif DISABLED(THERMAL_PROTECTION_BED) && defined(THERMAL_PROTECTION_BED_PERIOD)
#error Thermal Runaway Protection for the bed is now enabled with THERMAL_PROTECTION_BED.
#elif ENABLED(COREXZ) && ENABLED(Z_LATE_ENABLE)
#error "Z_LATE_ENABLE can't be used with COREXZ."
#elif defined(X_HOME_RETRACT_MM)
#error [XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM.
#elif defined(PROBE_SERVO_DEACTIVATION_DELAY)
#error PROBE_SERVO_DEACTIVATION_DELAY has been replaced with DEACTIVATE_SERVOS_AFTER_MOVE and SERVO_DEACTIVATION_DELAY.
#elif defined(BEEPER)
#error BEEPER is now BEEPER_PIN. Please update your pins definitions.
#elif defined(SDCARDDETECT)
#error SDCARDDETECT is now SD_DETECT_PIN. Please update your pins definitions.
#elif defined(SDCARDDETECTINVERTED)
#error SDCARDDETECTINVERTED is now SD_DETECT_INVERTED. Please update your configuration.
#elif defined(BTENABLED)
#error BTENABLED is now BLUETOOTH. Please update your configuration.
#elif defined(CUSTOM_MENDEL_NAME)
#error CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME. Please update your configuration.
#elif defined(HAS_AUTOMATIC_VERSIONING)
#error HAS_AUTOMATIC_VERSIONING deprecated - use USE_AUTOMATIC_VERSIONING instead
#elif defined(ENABLE_AUTO_BED_LEVELING)
#error ENABLE_AUTO_BED_LEVELING deprecated - use AUTO_BED_LEVELING_FEATURE instead
#endif
#endif //SANITYCHECK_H

View File

@ -23,131 +23,129 @@
#include "Sd2Card.h"
//------------------------------------------------------------------------------
#if DISABLED(SOFTWARE_SPI)
// functions for hardware SPI
//------------------------------------------------------------------------------
// make sure SPCR rate is in expected bits
#if (SPR0 != 0 || SPR1 != 1)
#error unexpected SPCR bits
#endif
/**
* Initialize hardware SPI
* Set SCK rate to F_CPU/pow(2, 1 + spiRate) for spiRate [0,6]
*/
static void spiInit(uint8_t spiRate) {
// See avr processor documentation
SPCR = BIT(SPE) | BIT(MSTR) | (spiRate >> 1);
SPSR = spiRate & 1 || spiRate == 6 ? 0 : BIT(SPI2X);
}
//------------------------------------------------------------------------------
/** SPI receive a byte */
static uint8_t spiRec() {
SPDR = 0XFF;
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
return SPDR;
}
//------------------------------------------------------------------------------
/** SPI read data - only one call so force inline */
static inline __attribute__((always_inline))
void spiRead(uint8_t* buf, uint16_t nbyte) {
if (nbyte-- == 0) return;
SPDR = 0XFF;
for (uint16_t i = 0; i < nbyte; i++) {
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
buf[i] = SPDR;
// functions for hardware SPI
//------------------------------------------------------------------------------
// make sure SPCR rate is in expected bits
#if (SPR0 != 0 || SPR1 != 1)
#error unexpected SPCR bits
#endif
/**
* Initialize hardware SPI
* Set SCK rate to F_CPU/pow(2, 1 + spiRate) for spiRate [0,6]
*/
static void spiInit(uint8_t spiRate) {
// See avr processor documentation
SPCR = BIT(SPE) | BIT(MSTR) | (spiRate >> 1);
SPSR = spiRate & 1 || spiRate == 6 ? 0 : BIT(SPI2X);
}
//------------------------------------------------------------------------------
/** SPI receive a byte */
static uint8_t spiRec() {
SPDR = 0XFF;
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
return SPDR;
}
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
buf[nbyte] = SPDR;
}
//------------------------------------------------------------------------------
/** SPI send a byte */
static void spiSend(uint8_t b) {
SPDR = b;
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
}
//------------------------------------------------------------------------------
/** SPI send block - only one call so force inline */
static inline __attribute__((always_inline))
//------------------------------------------------------------------------------
/** SPI read data - only one call so force inline */
static inline __attribute__((always_inline))
void spiRead(uint8_t* buf, uint16_t nbyte) {
if (nbyte-- == 0) return;
SPDR = 0XFF;
for (uint16_t i = 0; i < nbyte; i++) {
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
buf[i] = SPDR;
SPDR = 0XFF;
}
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
buf[nbyte] = SPDR;
}
//------------------------------------------------------------------------------
/** SPI send a byte */
static void spiSend(uint8_t b) {
SPDR = b;
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
}
//------------------------------------------------------------------------------
/** SPI send block - only one call so force inline */
static inline __attribute__((always_inline))
void spiSendBlock(uint8_t token, const uint8_t* buf) {
SPDR = token;
for (uint16_t i = 0; i < 512; i += 2) {
SPDR = token;
for (uint16_t i = 0; i < 512; i += 2) {
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
SPDR = buf[i];
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
SPDR = buf[i + 1];
}
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
SPDR = buf[i];
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
SPDR = buf[i + 1];
}
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
}
//------------------------------------------------------------------------------
//------------------------------------------------------------------------------
#else // SOFTWARE_SPI
//------------------------------------------------------------------------------
/** nop to tune soft SPI timing */
#define nop asm volatile ("nop\n\t")
//------------------------------------------------------------------------------
/** Soft SPI receive byte */
static uint8_t spiRec() {
uint8_t data = 0;
// no interrupts during byte receive - about 8 us
cli();
// output pin high - like sending 0XFF
fastDigitalWrite(SPI_MOSI_PIN, HIGH);
//------------------------------------------------------------------------------
/** nop to tune soft SPI timing */
#define nop asm volatile ("nop\n\t")
//------------------------------------------------------------------------------
/** Soft SPI receive byte */
static uint8_t spiRec() {
uint8_t data = 0;
// no interrupts during byte receive - about 8 us
cli();
// output pin high - like sending 0XFF
fastDigitalWrite(SPI_MOSI_PIN, HIGH);
for (uint8_t i = 0; i < 8; i++) {
fastDigitalWrite(SPI_SCK_PIN, HIGH);
for (uint8_t i = 0; i < 8; i++) {
fastDigitalWrite(SPI_SCK_PIN, HIGH);
// adjust so SCK is nice
// adjust so SCK is nice
nop;
nop;
data <<= 1;
if (fastDigitalRead(SPI_MISO_PIN)) data |= 1;
fastDigitalWrite(SPI_SCK_PIN, LOW);
}
// enable interrupts
sei();
return data;
}
//------------------------------------------------------------------------------
/** Soft SPI read data */
static void spiRead(uint8_t* buf, uint16_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++)
buf[i] = spiRec();
}
//------------------------------------------------------------------------------
/** Soft SPI send byte */
static void spiSend(uint8_t data) {
// no interrupts during byte send - about 8 us
cli();
for (uint8_t i = 0; i < 8; i++) {
fastDigitalWrite(SPI_SCK_PIN, LOW);
fastDigitalWrite(SPI_MOSI_PIN, data & 0X80);
data <<= 1;
fastDigitalWrite(SPI_SCK_PIN, HIGH);
}
// hold SCK high for a few ns
nop;
nop;
nop;
nop;
data <<= 1;
if (fastDigitalRead(SPI_MISO_PIN)) data |= 1;
fastDigitalWrite(SPI_SCK_PIN, LOW);
// enable interrupts
sei();
}
// enable interrupts
sei();
return data;
}
//------------------------------------------------------------------------------
/** Soft SPI read data */
static void spiRead(uint8_t* buf, uint16_t nbyte) {
for (uint16_t i = 0; i < nbyte; i++) {
buf[i] = spiRec();
}
}
//------------------------------------------------------------------------------
/** Soft SPI send byte */
static void spiSend(uint8_t data) {
// no interrupts during byte send - about 8 us
cli();
for (uint8_t i = 0; i < 8; i++) {
fastDigitalWrite(SPI_SCK_PIN, LOW);
fastDigitalWrite(SPI_MOSI_PIN, data & 0X80);
data <<= 1;
fastDigitalWrite(SPI_SCK_PIN, HIGH);
}
// hold SCK high for a few ns
nop;
nop;
nop;
nop;
fastDigitalWrite(SPI_SCK_PIN, LOW);
// enable interrupts
sei();
}
//------------------------------------------------------------------------------
/** Soft SPI send block */
//------------------------------------------------------------------------------
/** Soft SPI send block */
void spiSendBlock(uint8_t token, const uint8_t* buf) {
spiSend(token);
for (uint16_t i = 0; i < 512; i++) {
spiSend(buf[i]);
spiSend(token);
for (uint16_t i = 0; i < 512; i++)
spiSend(buf[i]);
}
}
#endif // SOFTWARE_SPI
//------------------------------------------------------------------------------
// send command and return error code. Return zero for OK
@ -209,9 +207,9 @@ void Sd2Card::chipSelectHigh() {
}
//------------------------------------------------------------------------------
void Sd2Card::chipSelectLow() {
#if DISABLED(SOFTWARE_SPI)
spiInit(spiRate_);
#endif // SOFTWARE_SPI
#if DISABLED(SOFTWARE_SPI)
spiInit(spiRate_);
#endif // SOFTWARE_SPI
digitalWrite(chipSelectPin_, LOW);
}
//------------------------------------------------------------------------------
@ -246,10 +244,10 @@ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
lastBlock <<= 9;
}
if (cardCommand(CMD32, firstBlock)
|| cardCommand(CMD33, lastBlock)
|| cardCommand(CMD38, 0)) {
error(SD_CARD_ERROR_ERASE);
goto fail;
|| cardCommand(CMD33, lastBlock)
|| cardCommand(CMD38, 0)) {
error(SD_CARD_ERROR_ERASE);
goto fail;
}
if (!waitNotBusy(SD_ERASE_TIMEOUT)) {
error(SD_CARD_ERROR_ERASE_TIMEOUT);
@ -257,8 +255,7 @@ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
}
chipSelectHigh();
return true;
fail:
fail:
chipSelectHigh();
return false;
}
@ -297,17 +294,17 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
pinMode(SPI_MOSI_PIN, OUTPUT);
pinMode(SPI_SCK_PIN, OUTPUT);
#if DISABLED(SOFTWARE_SPI)
// SS must be in output mode even it is not chip select
pinMode(SS_PIN, OUTPUT);
// set SS high - may be chip select for another SPI device
#if SET_SPI_SS_HIGH
digitalWrite(SS_PIN, HIGH);
#endif // SET_SPI_SS_HIGH
// set SCK rate for initialization commands
spiRate_ = SPI_SD_INIT_RATE;
spiInit(spiRate_);
#endif // SOFTWARE_SPI
#if DISABLED(SOFTWARE_SPI)
// SS must be in output mode even it is not chip select
pinMode(SS_PIN, OUTPUT);
// set SS high - may be chip select for another SPI device
#if SET_SPI_SS_HIGH
digitalWrite(SS_PIN, HIGH);
#endif // SET_SPI_SS_HIGH
// set SCK rate for initialization commands
spiRate_ = SPI_SD_INIT_RATE;
spiInit(spiRate_);
#endif // SOFTWARE_SPI
// must supply min of 74 clock cycles with CS high.
for (uint8_t i = 0; i < 10; i++) spiSend(0XFF);
@ -322,7 +319,8 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
// check SD version
if ((cardCommand(CMD8, 0x1AA) & R1_ILLEGAL_COMMAND)) {
type(SD_CARD_TYPE_SD1);
} else {
}
else {
// only need last byte of r7 response
for (uint8_t i = 0; i < 4; i++) status_ = spiRec();
if (status_ != 0XAA) {
@ -353,13 +351,13 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
}
chipSelectHigh();
#if DISABLED(SOFTWARE_SPI)
return setSckRate(sckRateID);
#else // SOFTWARE_SPI
return true;
#endif // SOFTWARE_SPI
#if DISABLED(SOFTWARE_SPI)
return setSckRate(sckRateID);
#else // SOFTWARE_SPI
return true;
#endif // SOFTWARE_SPI
fail:
fail:
chipSelectHigh();
return false;
}
@ -376,28 +374,27 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
#if ENABLED(SD_CHECK_AND_RETRY)
uint8_t retryCnt = 3;
// use address if not SDHC card
if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9;
retry2:
if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
retry2:
retryCnt --;
if (cardCommand(CMD17, blockNumber)) {
error(SD_CARD_ERROR_CMD17);
if (retryCnt > 0) goto retry;
goto fail;
}
if (!readData(dst, 512))
{
if (!readData(dst, 512)) {
if (retryCnt > 0) goto retry;
goto fail;
}
return true;
retry:
chipSelectHigh();
cardCommand(CMD12, 0);//Try sending a stop command, but ignore the result.
errorCode_ = 0;
goto retry2;
retry:
chipSelectHigh();
cardCommand(CMD12, 0);//Try sending a stop command, but ignore the result.
errorCode_ = 0;
goto retry2;
#else
// use address if not SDHC card
if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9;
if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
if (cardCommand(CMD17, blockNumber)) {
error(SD_CARD_ERROR_CMD17);
goto fail;
@ -405,7 +402,7 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
return readData(dst, 512);
#endif
fail:
fail:
chipSelectHigh();
return false;
}
@ -417,7 +414,7 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool Sd2Card::readData(uint8_t *dst) {
bool Sd2Card::readData(uint8_t* dst) {
chipSelectLow();
return readData(dst, 512);
}
@ -488,10 +485,9 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
uint16_t calcCrc = CRC_CCITT(dst, count);
uint16_t recvCrc = spiRec() << 8;
recvCrc |= spiRec();
if (calcCrc != recvCrc)
{
error(SD_CARD_ERROR_CRC);
goto fail;
if (calcCrc != recvCrc) {
error(SD_CARD_ERROR_CRC);
goto fail;
}
}
#else
@ -501,8 +497,7 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
#endif
chipSelectHigh();
return true;
fail:
fail:
chipSelectHigh();
return false;
}
@ -515,8 +510,7 @@ bool Sd2Card::readRegister(uint8_t cmd, void* buf) {
goto fail;
}
return readData(dst, 16);
fail:
fail:
chipSelectHigh();
return false;
}
@ -532,15 +526,14 @@ bool Sd2Card::readRegister(uint8_t cmd, void* buf) {
* the value zero, false, is returned for failure.
*/
bool Sd2Card::readStart(uint32_t blockNumber) {
if (type()!= SD_CARD_TYPE_SDHC) blockNumber <<= 9;
if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
if (cardCommand(CMD18, blockNumber)) {
error(SD_CARD_ERROR_CMD18);
goto fail;
}
chipSelectHigh();
return true;
fail:
fail:
chipSelectHigh();
return false;
}
@ -558,8 +551,7 @@ bool Sd2Card::readStop() {
}
chipSelectHigh();
return true;
fail:
fail:
chipSelectHigh();
return false;
}
@ -592,8 +584,7 @@ bool Sd2Card::waitNotBusy(uint16_t timeoutMillis) {
if (((uint16_t)millis() - t0) >= timeoutMillis) goto fail;
}
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -626,8 +617,7 @@ bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) {
}
chipSelectHigh();
return true;
fail:
fail:
chipSelectHigh();
return false;
}
@ -644,8 +634,7 @@ bool Sd2Card::writeData(const uint8_t* src) {
if (!writeData(WRITE_MULTIPLE_TOKEN, src)) goto fail;
chipSelectHigh();
return true;
fail:
fail:
error(SD_CARD_ERROR_WRITE_MULTIPLE);
chipSelectHigh();
return false;
@ -664,8 +653,7 @@ bool Sd2Card::writeData(uint8_t token, const uint8_t* src) {
goto fail;
}
return true;
fail:
fail:
chipSelectHigh();
return false;
}
@ -695,8 +683,7 @@ bool Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) {
}
chipSelectHigh();
return true;
fail:
fail:
chipSelectHigh();
return false;
}
@ -713,8 +700,7 @@ bool Sd2Card::writeStop() {
if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
chipSelectHigh();
return true;
fail:
fail:
error(SD_CARD_ERROR_STOP_TRAN);
chipSelectHigh();
return false;

View File

@ -118,35 +118,35 @@ uint8_t const SD_CARD_TYPE_SDHC = 3;
*/
//------------------------------------------------------------------------------
#if MEGA_SOFT_SPI && (defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__))
#define SOFTWARE_SPI
#define SOFTWARE_SPI
#elif USE_SOFTWARE_SPI
#define SOFTWARE_SPI
#define SOFTWARE_SPI
#endif // MEGA_SOFT_SPI
//------------------------------------------------------------------------------
// SPI pin definitions - do not edit here - change in SdFatConfig.h
//
#if DISABLED(SOFTWARE_SPI)
// hardware pin defs
/** The default chip select pin for the SD card is SS. */
uint8_t const SD_CHIP_SELECT_PIN = SS_PIN;
// The following three pins must not be redefined for hardware SPI.
/** SPI Master Out Slave In pin */
uint8_t const SPI_MOSI_PIN = MOSI_PIN;
/** SPI Master In Slave Out pin */
uint8_t const SPI_MISO_PIN = MISO_PIN;
/** SPI Clock pin */
uint8_t const SPI_SCK_PIN = SCK_PIN;
// hardware pin defs
/** The default chip select pin for the SD card is SS. */
uint8_t const SD_CHIP_SELECT_PIN = SS_PIN;
// The following three pins must not be redefined for hardware SPI.
/** SPI Master Out Slave In pin */
uint8_t const SPI_MOSI_PIN = MOSI_PIN;
/** SPI Master In Slave Out pin */
uint8_t const SPI_MISO_PIN = MISO_PIN;
/** SPI Clock pin */
uint8_t const SPI_SCK_PIN = SCK_PIN;
#else // SOFTWARE_SPI
/** SPI chip select pin */
uint8_t const SD_CHIP_SELECT_PIN = SOFT_SPI_CS_PIN;
/** SPI Master Out Slave In pin */
uint8_t const SPI_MOSI_PIN = SOFT_SPI_MOSI_PIN;
/** SPI Master In Slave Out pin */
uint8_t const SPI_MISO_PIN = SOFT_SPI_MISO_PIN;
/** SPI Clock pin */
uint8_t const SPI_SCK_PIN = SOFT_SPI_SCK_PIN;
/** SPI chip select pin */
uint8_t const SD_CHIP_SELECT_PIN = SOFT_SPI_CS_PIN;
/** SPI Master Out Slave In pin */
uint8_t const SPI_MOSI_PIN = SOFT_SPI_MOSI_PIN;
/** SPI Master In Slave Out pin */
uint8_t const SPI_MISO_PIN = SOFT_SPI_MISO_PIN;
/** SPI Clock pin */
uint8_t const SPI_SCK_PIN = SOFT_SPI_SCK_PIN;
#endif // SOFTWARE_SPI
//------------------------------------------------------------------------------
/**
@ -178,12 +178,12 @@ class Sd2Card {
* \return true for success or false for failure.
*/
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
bool readBlock(uint32_t block, uint8_t* dst);
/**
* Read a card's CID register. The CID contains card identification
* information such as Manufacturer ID, Product name, Product serial
* number and Manufacturing date.
* number and Manufacturing date.
*
* \param[out] cid pointer to area for returned data.
*
@ -203,7 +203,7 @@ class Sd2Card {
bool readCSD(csd_t* csd) {
return readRegister(CMD9, csd);
}
bool readData(uint8_t *dst);
bool readData(uint8_t* dst);
bool readStart(uint32_t blockNumber);
bool readStop();
bool setSckRate(uint8_t sckRateID);

View File

@ -316,12 +316,12 @@ static const pin_map_t digitalPinMap[] = {
};
#elif defined(__AVR_ATmega1281__)
// Waspmote
// Two Wire (aka I2C) ports
uint8_t const SDA_PIN = 41;
uint8_t const SCL_PIN = 40;
#undef MOSI_PIN
#undef MISO_PIN
// SPI port
@ -329,59 +329,59 @@ uint8_t const SS_PIN = 16; // B0
uint8_t const MOSI_PIN = 11; // B2
uint8_t const MISO_PIN = 12; // B3
uint8_t const SCK_PIN = 10; // B1
static const pin_map_t digitalPinMap[] = {
{&DDRE, &PINE, &PORTE, 0}, // E0 0
{&DDRE, &PINE, &PORTE, 1}, // E1 1
{&DDRE, &PINE, &PORTE, 3}, // E3 2
{&DDRE, &PINE, &PORTE, 4}, // E4 3
{&DDRC, &PINC, &PORTC, 4}, // C4 4
{&DDRC, &PINC, &PORTC, 5}, // C5 5
{&DDRC, &PINC, &PORTC, 6}, // C6 6
{&DDRC, &PINC, &PORTC, 7}, // C7 7
{&DDRA, &PINA, &PORTA, 2}, // A2 8
{&DDRA, &PINA, &PORTA, 3}, // A3 9
{&DDRA, &PINA, &PORTA, 4}, // A4 10
{&DDRD, &PIND, &PORTD, 5}, // D5 11
{&DDRD, &PIND, &PORTD, 6}, // D6 12
{&DDRC, &PINC, &PORTC, 1}, // C1 13
{&DDRF, &PINF, &PORTF, 1}, // F1 14
{&DDRF, &PINF, &PORTF, 2}, // F2 15
{&DDRF, &PINF, &PORTF, 3}, // F3 16
{&DDRF, &PINF, &PORTF, 4}, // F4 17
{&DDRF, &PINF, &PORTF, 5}, // F5 18
{&DDRF, &PINF, &PORTF, 6}, // F6 19
{&DDRF, &PINF, &PORTF, 7}, // F7 20
{&DDRF, &PINF, &PORTF, 0}, // F0 21
{&DDRA, &PINA, &PORTA, 1}, // A1 22
{&DDRD, &PIND, &PORTD, 7}, // D7 23
{&DDRE, &PINE, &PORTE, 5}, // E5 24
{&DDRA, &PINA, &PORTA, 6}, // A6 25
{&DDRE, &PINE, &PORTE, 2}, // E2 26
{&DDRA, &PINA, &PORTA, 5}, // A5 27
{&DDRC, &PINC, &PORTC, 0}, // C0 28
{&DDRB, &PINB, &PORTB, 0}, // B0 29
{&DDRB, &PINB, &PORTB, 1}, // B1 30
{&DDRB, &PINB, &PORTB, 2}, // B2 31
{&DDRB, &PINB, &PORTB, 3}, // B3 32
{&DDRB, &PINB, &PORTB, 4}, // B4 33
{&DDRB, &PINB, &PORTB, 5}, // B5 34
{&DDRA, &PINA, &PORTA, 0}, // A0 35
{&DDRB, &PINB, &PORTB, 6}, // B6 36
{&DDRB, &PINB, &PORTB, 7}, // B7 37
{&DDRE, &PINE, &PORTE, 6}, // E6 38
{&DDRE, &PINE, &PORTE, 7}, // E7 39
{&DDRD, &PIND, &PORTD, 0}, // D0 40
{&DDRD, &PIND, &PORTD, 1}, // D1 41
{&DDRC, &PINC, &PORTC, 3}, // C3 42
{&DDRD, &PIND, &PORTD, 2}, // D2 43
{&DDRD, &PIND, &PORTD, 3}, // D3 44
{&DDRA, &PINA, &PORTA, 7}, // A7 45
{&DDRC, &PINC, &PORTC, 2}, // C2 46
{&DDRD, &PIND, &PORTD, 4}, // D4 47
{&DDRG, &PING, &PORTG, 2}, // G2 48
{&DDRG, &PING, &PORTG, 1}, // G1 49
{&DDRG, &PING, &PORTG, 0}, // G0 50
{&DDRE, &PINE, &PORTE, 0}, // E0 0
{&DDRE, &PINE, &PORTE, 1}, // E1 1
{&DDRE, &PINE, &PORTE, 3}, // E3 2
{&DDRE, &PINE, &PORTE, 4}, // E4 3
{&DDRC, &PINC, &PORTC, 4}, // C4 4
{&DDRC, &PINC, &PORTC, 5}, // C5 5
{&DDRC, &PINC, &PORTC, 6}, // C6 6
{&DDRC, &PINC, &PORTC, 7}, // C7 7
{&DDRA, &PINA, &PORTA, 2}, // A2 8
{&DDRA, &PINA, &PORTA, 3}, // A3 9
{&DDRA, &PINA, &PORTA, 4}, // A4 10
{&DDRD, &PIND, &PORTD, 5}, // D5 11
{&DDRD, &PIND, &PORTD, 6}, // D6 12
{&DDRC, &PINC, &PORTC, 1}, // C1 13
{&DDRF, &PINF, &PORTF, 1}, // F1 14
{&DDRF, &PINF, &PORTF, 2}, // F2 15
{&DDRF, &PINF, &PORTF, 3}, // F3 16
{&DDRF, &PINF, &PORTF, 4}, // F4 17
{&DDRF, &PINF, &PORTF, 5}, // F5 18
{&DDRF, &PINF, &PORTF, 6}, // F6 19
{&DDRF, &PINF, &PORTF, 7}, // F7 20
{&DDRF, &PINF, &PORTF, 0}, // F0 21
{&DDRA, &PINA, &PORTA, 1}, // A1 22
{&DDRD, &PIND, &PORTD, 7}, // D7 23
{&DDRE, &PINE, &PORTE, 5}, // E5 24
{&DDRA, &PINA, &PORTA, 6}, // A6 25
{&DDRE, &PINE, &PORTE, 2}, // E2 26
{&DDRA, &PINA, &PORTA, 5}, // A5 27
{&DDRC, &PINC, &PORTC, 0}, // C0 28
{&DDRB, &PINB, &PORTB, 0}, // B0 29
{&DDRB, &PINB, &PORTB, 1}, // B1 30
{&DDRB, &PINB, &PORTB, 2}, // B2 31
{&DDRB, &PINB, &PORTB, 3}, // B3 32
{&DDRB, &PINB, &PORTB, 4}, // B4 33
{&DDRB, &PINB, &PORTB, 5}, // B5 34
{&DDRA, &PINA, &PORTA, 0}, // A0 35
{&DDRB, &PINB, &PORTB, 6}, // B6 36
{&DDRB, &PINB, &PORTB, 7}, // B7 37
{&DDRE, &PINE, &PORTE, 6}, // E6 38
{&DDRE, &PINE, &PORTE, 7}, // E7 39
{&DDRD, &PIND, &PORTD, 0}, // D0 40
{&DDRD, &PIND, &PORTD, 1}, // D1 41
{&DDRC, &PINC, &PORTC, 3}, // C3 42
{&DDRD, &PIND, &PORTD, 2}, // D2 43
{&DDRD, &PIND, &PORTD, 3}, // D3 44
{&DDRA, &PINA, &PORTA, 7}, // A7 45
{&DDRC, &PINC, &PORTC, 2}, // C2 46
{&DDRD, &PIND, &PORTD, 4}, // D4 47
{&DDRG, &PING, &PORTG, 2}, // G2 48
{&DDRG, &PING, &PORTG, 1}, // G1 49
{&DDRG, &PING, &PORTG, 0}, // G0 50
};
#else // defined(__AVR_ATmega1280__)
#error unknown chip

View File

@ -48,7 +48,7 @@ bool SdBaseFile::addCluster() {
bool SdBaseFile::addDirCluster() {
uint32_t block;
// max folder size
if (fileSize_/sizeof(dir_t) >= 0XFFFF) goto fail;
if (fileSize_ / sizeof(dir_t) >= 0XFFFF) goto fail;
if (!addCluster()) goto fail;
if (!vol_->cacheFlush()) goto fail;
@ -68,8 +68,7 @@ bool SdBaseFile::addDirCluster() {
// Increase directory file size by cluster size
fileSize_ += 512UL << vol_->clusterSizeShift_;
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -78,8 +77,7 @@ bool SdBaseFile::addDirCluster() {
dir_t* SdBaseFile::cacheDirEntry(uint8_t action) {
if (!vol_->cacheRawBlock(dirBlock_, action)) goto fail;
return vol_->cache()->dir + dirIndex_;
fail:
fail:
return 0;
}
//------------------------------------------------------------------------------
@ -125,7 +123,7 @@ bool SdBaseFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) {
}
}
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -147,7 +145,7 @@ bool SdBaseFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) {
*
*/
bool SdBaseFile::createContiguous(SdBaseFile* dirFile,
const char* path, uint32_t size) {
const char* path, uint32_t size) {
uint32_t count;
// don't allow zero length file
if (size == 0) goto fail;
@ -167,8 +165,7 @@ bool SdBaseFile::createContiguous(SdBaseFile* dirFile,
flags_ |= F_FILE_DIR_DIRTY;
return sync();
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -191,8 +188,7 @@ bool SdBaseFile::dirEntry(dir_t* dir) {
// copy to caller's struct
memcpy(dir, p, sizeof(dir_t));
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -258,7 +254,8 @@ int16_t SdBaseFile::fgets(char* str, int16_t num, char* delim) {
str[n++] = ch;
if (!delim) {
if (ch == '\n') break;
} else {
}
else {
if (strchr(delim, ch)) break;
}
}
@ -318,11 +315,11 @@ void SdBaseFile::getpos(fpos_t* pos) {
void SdBaseFile::ls(uint8_t flags, uint8_t indent) {
rewind();
int8_t status;
while ((status = lsPrintNext( flags, indent))) {
while ((status = lsPrintNext(flags, indent))) {
if (status > 1 && (flags & LS_R)) {
uint16_t index = curPosition()/32 - 1;
uint16_t index = curPosition() / 32 - 1;
SdBaseFile s;
if (s.open(this, index, O_READ)) s.ls( flags, indent + 2);
if (s.open(this, index, O_READ)) s.ls(flags, indent + 2);
seekSet(32 * (index + 1));
}
}
@ -330,7 +327,7 @@ void SdBaseFile::ls(uint8_t flags, uint8_t indent) {
//------------------------------------------------------------------------------
// saves 32 bytes on stack for ls recursion
// return 0 - EOF, 1 - normal file, or 2 - directory
int8_t SdBaseFile::lsPrintNext( uint8_t flags, uint8_t indent) {
int8_t SdBaseFile::lsPrintNext(uint8_t flags, uint8_t indent) {
dir_t dir;
uint8_t w = 0;
@ -340,7 +337,7 @@ int8_t SdBaseFile::lsPrintNext( uint8_t flags, uint8_t indent) {
// skip deleted entry and entries for . and ..
if (dir.name[0] != DIR_NAME_DELETED && dir.name[0] != '.'
&& DIR_IS_FILE_OR_SUBDIR(&dir)) break;
&& DIR_IS_FILE_OR_SUBDIR(&dir)) break;
}
// indent for dir level
for (uint8_t i = 0; i < indent; i++) MYSERIAL.write(' ');
@ -365,9 +362,9 @@ int8_t SdBaseFile::lsPrintNext( uint8_t flags, uint8_t indent) {
// print modify date/time if requested
if (flags & LS_DATE) {
MYSERIAL.write(' ');
printFatDate( dir.lastWriteDate);
printFatDate(dir.lastWriteDate);
MYSERIAL.write(' ');
printFatTime( dir.lastWriteTime);
printFatTime(dir.lastWriteTime);
}
// print size if requested
if (!DIR_IS_SUBDIR(&dir) && (flags & LS_SIZE)) {
@ -392,7 +389,8 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) {
if (n == 10) goto fail; // only one dot allowed
n = 10; // max index for full 8.3 name
i = 8; // place for extension
} else {
}
else {
// illegal FAT characters
PGM_P p = PSTR("|<>^+=?/[];,*\"\\");
uint8_t b;
@ -400,14 +398,13 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) {
// check size and only allow ASCII printable characters
if (i > n || c < 0X21 || c > 0X7E)goto fail;
// only upper case allowed in 8.3 names - convert lower to upper
name[i++] = (c < 'a' || c > 'z') ? (c) : (c + ('A' - 'a'));
name[i++] = (c < 'a' || c > 'z') ? (c) : (c + ('A' - 'a'));
}
}
*ptr = str;
// must have a file name, extension is optional
return name[0] != ' ';
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -454,8 +451,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const char* path, bool pFlag) {
sub = parent != &dir1 ? &dir1 : &dir2;
}
return mkdir(parent, dname);
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -503,7 +499,8 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) {
if (parent->isRoot()) {
d.firstClusterLow = 0;
d.firstClusterHigh = 0;
} else {
}
else {
d.firstClusterLow = parent->firstCluster_ & 0XFFFF;
d.firstClusterHigh = parent->firstCluster_ >> 16;
}
@ -512,24 +509,23 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) {
// write first block
return vol_->cacheFlush();
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
/** Open a file in the current working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
*
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdBaseFile::open(const char* path, uint8_t oflag) {
return open(cwd_, path, oflag);
}
/** Open a file in the current working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
*
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdBaseFile::open(const char* path, uint8_t oflag) {
return open(cwd_, path, oflag);
}
//------------------------------------------------------------------------------
/** Open a file or directory by name.
*
@ -584,8 +580,8 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) {
bool SdBaseFile::open(SdBaseFile* dirFile, const char* path, uint8_t oflag) {
uint8_t dname[11];
SdBaseFile dir1, dir2;
SdBaseFile *parent = dirFile;
SdBaseFile *sub = &dir1;
SdBaseFile* parent = dirFile;
SdBaseFile* sub = &dir1;
if (!dirFile) goto fail;
@ -609,14 +605,13 @@ bool SdBaseFile::open(SdBaseFile* dirFile, const char* path, uint8_t oflag) {
sub = parent != &dir1 ? &dir1 : &dir2;
}
return open(parent, dname, oflag);
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
// open with filename in dname
bool SdBaseFile::open(SdBaseFile* dirFile,
const uint8_t dname[11], uint8_t oflag) {
const uint8_t dname[11], uint8_t oflag) {
bool emptyFound = false;
bool fileFound = false;
uint8_t index;
@ -641,7 +636,8 @@ bool SdBaseFile::open(SdBaseFile* dirFile,
}
// done if no entries follow
if (p->name[0] == DIR_NAME_FREE) break;
} else if (!memcmp(dname, p->name, 11)) {
}
else if (!memcmp(dname, p->name, 11)) {
fileFound = true;
break;
}
@ -649,14 +645,16 @@ bool SdBaseFile::open(SdBaseFile* dirFile,
if (fileFound) {
// don't open existing file if O_EXCL
if (oflag & O_EXCL) goto fail;
} else {
}
else {
// don't create unless O_CREAT and O_WRITE
if (!(oflag & O_CREAT) || !(oflag & O_WRITE)) goto fail;
if (emptyFound) {
index = dirIndex_;
p = cacheDirEntry(SdVolume::CACHE_FOR_WRITE);
if (!p) goto fail;
} else {
}
else {
if (dirFile->type_ == FAT_FILE_TYPE_ROOT_FIXED) goto fail;
// add and zero cluster for dirFile - first cluster is in cache for write
@ -674,7 +672,8 @@ bool SdBaseFile::open(SdBaseFile* dirFile,
if (dateTime_) {
// call user date/time function
dateTime_(&p->creationDate, &p->creationTime);
} else {
}
else {
// use default date/time
p->creationDate = FAT_DEFAULT_DATE;
p->creationTime = FAT_DEFAULT_TIME;
@ -688,8 +687,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile,
}
// open entry in cache
return openCachedEntry(index, oflag);
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -731,8 +729,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag) {
}
// open cached entry
return openCachedEntry(index & 0XF, oflag);
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -757,10 +754,12 @@ bool SdBaseFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) {
if (DIR_IS_FILE(p)) {
fileSize_ = p->fileSize;
type_ = FAT_FILE_TYPE_NORMAL;
} else if (DIR_IS_SUBDIR(p)) {
}
else if (DIR_IS_SUBDIR(p)) {
if (!vol_->chainSize(firstCluster_, &fileSize_)) goto fail;
type_ = FAT_FILE_TYPE_SUBDIR;
} else {
}
else {
goto fail;
}
// save open flags for read/write
@ -771,8 +770,7 @@ bool SdBaseFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) {
curPosition_ = 0;
if ((oflag & O_TRUNC) && !truncate(0)) return false;
return oflag & O_AT_END ? seekEnd(0) : true;
fail:
fail:
type_ = FAT_FILE_TYPE_CLOSED;
return false;
}
@ -818,8 +816,7 @@ bool SdBaseFile::openNext(SdBaseFile* dirFile, uint8_t oflag) {
return openCachedEntry(index, oflag);
}
}
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -862,8 +859,9 @@ bool SdBaseFile::openParent(SdBaseFile* dir) {
// '..' is pointer to first cluster of parent. open '../..' to find parent
if (p->firstClusterHigh == 0 && p->firstClusterLow == 0) {
if (!file.openRoot(dir->volume())) goto fail;
} else {
if (!file.openCachedEntry(1, O_READ)) goto fail;
}
else if (!file.openCachedEntry(1, O_READ)) {
goto fail;
}
// search for parent in '../..'
do {
@ -872,9 +870,8 @@ bool SdBaseFile::openParent(SdBaseFile* dir) {
c |= (uint32_t)entry.firstClusterHigh << 16;
} while (c != cluster);
// open parent
return open(&file, file.curPosition()/32 - 1, O_READ);
fail:
return open(&file, file.curPosition() / 32 - 1, O_READ);
fail:
return false;
}
//------------------------------------------------------------------------------
@ -895,11 +892,13 @@ bool SdBaseFile::openRoot(SdVolume* vol) {
type_ = FAT_FILE_TYPE_ROOT_FIXED;
firstCluster_ = 0;
fileSize_ = 32 * vol->rootDirEntryCount();
} else if (vol->fatType() == 32) {
}
else if (vol->fatType() == 32) {
type_ = FAT_FILE_TYPE_ROOT32;
firstCluster_ = vol->rootDirStart();
if (!vol->chainSize(firstCluster_, &fileSize_)) goto fail;
} else {
}
else {
// volume is not initialized, invalid, or FAT12 without support
return false;
}
@ -915,8 +914,7 @@ bool SdBaseFile::openRoot(SdVolume* vol) {
dirBlock_ = 0;
dirIndex_ = 0;
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -940,7 +938,7 @@ int SdBaseFile::peek() {
* \param[in] printSlash Print '/' after directory names if true.
*/
void SdBaseFile::printDirName(const dir_t& dir,
uint8_t width, bool printSlash) {
uint8_t width, bool printSlash) {
uint8_t w = 0;
for (uint8_t i = 0; i < 11; i++) {
if (dir.name[i] == ' ')continue;
@ -962,7 +960,7 @@ void SdBaseFile::printDirName(const dir_t& dir,
}
//------------------------------------------------------------------------------
// print uint8_t with width 2
static void print2u( uint8_t v) {
static void print2u(uint8_t v) {
if (v < 10) MYSERIAL.write('0');
MYSERIAL.print(v, DEC);
}
@ -985,9 +983,9 @@ static void print2u( uint8_t v) {
void SdBaseFile::printFatDate(uint16_t fatDate) {
MYSERIAL.print(FAT_YEAR(fatDate));
MYSERIAL.write('-');
print2u( FAT_MONTH(fatDate));
print2u(FAT_MONTH(fatDate));
MYSERIAL.write('-');
print2u( FAT_DAY(fatDate));
print2u(FAT_DAY(fatDate));
}
//------------------------------------------------------------------------------
@ -998,12 +996,12 @@ void SdBaseFile::printFatDate(uint16_t fatDate) {
* \param[in] pr Print stream for output.
* \param[in] fatTime The time field from a directory entry.
*/
void SdBaseFile::printFatTime( uint16_t fatTime) {
print2u( FAT_HOUR(fatTime));
void SdBaseFile::printFatTime(uint16_t fatTime) {
print2u(FAT_HOUR(fatTime));
MYSERIAL.write(':');
print2u( FAT_MINUTE(fatTime));
print2u(FAT_MINUTE(fatTime));
MYSERIAL.write(':');
print2u( FAT_SECOND(fatTime));
print2u(FAT_SECOND(fatTime));
}
//------------------------------------------------------------------------------
/** Print a file's name to Serial
@ -1060,14 +1058,16 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) {
offset = curPosition_ & 0X1FF; // offset in block
if (type_ == FAT_FILE_TYPE_ROOT_FIXED) {
block = vol_->rootDirStart() + (curPosition_ >> 9);
} else {
}
else {
uint8_t blockOfCluster = vol_->blockOfCluster(curPosition_);
if (offset == 0 && blockOfCluster == 0) {
// start of new cluster
if (curPosition_ == 0) {
// use first cluster in file
curCluster_ = firstCluster_;
} else {
}
else {
// get next cluster from FAT
if (!vol_->fatGet(curCluster_, &curCluster_)) goto fail;
}
@ -1082,7 +1082,8 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) {
// no buffering needed if n == 512
if (n == 512 && block != vol_->cacheBlockNumber()) {
if (!vol_->readBlock(block, dst)) goto fail;
} else {
}
else {
// read block to cache and copy data to caller
if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_READ)) goto fail;
uint8_t* src = vol_->cache()->data + offset;
@ -1093,8 +1094,7 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) {
toRead -= n;
}
return nbyte;
fail:
fail:
return -1;
}
@ -1113,7 +1113,7 @@ int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) {
int16_t n;
// if not a directory file or miss-positioned return an error
if (!isDir() || (0X1F & curPosition_)) return -1;
//If we have a longFilename buffer, mark it as invalid. If we find a long filename it will be filled automaticly.
if (longFilename != NULL) longFilename[0] = '\0';
@ -1131,15 +1131,15 @@ int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) {
// Fill the long filename if we have a long filename entry.
// Long filename entries are stored before the short filename.
if (longFilename != NULL && DIR_IS_LONG_NAME(dir)) {
vfat_t *VFAT = (vfat_t*)dir;
vfat_t* VFAT = (vfat_t*)dir;
// Sanity-check the VFAT entry. The first cluster is always set to zero. And the sequence number should be higher than 0
if (VFAT->firstClusterLow == 0 && (VFAT->sequenceNumber & 0x1F) > 0 && (VFAT->sequenceNumber & 0x1F) <= MAX_VFAT_ENTRIES) {
// TODO: Store the filename checksum to verify if a none-long filename aware system modified the file table.
n = ((VFAT->sequenceNumber & 0x1F) - 1) * FILENAME_LENGTH;
for (uint8_t i=0; i<FILENAME_LENGTH; i++)
longFilename[n+i] = (i < 5) ? VFAT->name1[i] : (i < 11) ? VFAT->name2[i-5] : VFAT->name3[i-11];
for (uint8_t i = 0; i < FILENAME_LENGTH; i++)
longFilename[n + i] = (i < 5) ? VFAT->name1[i] : (i < 11) ? VFAT->name2[i - 5] : VFAT->name3[i - 11];
// If this VFAT entry is the last one, add a NUL terminator at the end of the string
if (VFAT->sequenceNumber & 0x40) longFilename[n+FILENAME_LENGTH] = '\0';
if (VFAT->sequenceNumber & 0x40) longFilename[n + FILENAME_LENGTH] = '\0';
}
}
// Return if normal file or subdirectory
@ -1166,8 +1166,7 @@ dir_t* SdBaseFile::readDirCache() {
// return pointer to entry
return vol_->cache()->dir + i;
fail:
fail:
return 0;
}
//------------------------------------------------------------------------------
@ -1202,8 +1201,7 @@ bool SdBaseFile::remove() {
// write entry to SD
return vol_->cacheFlush();
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -1228,8 +1226,7 @@ bool SdBaseFile::remove(SdBaseFile* dirFile, const char* path) {
SdBaseFile file;
if (!file.open(dirFile, path, O_WRITE)) goto fail;
return file.remove();
fail:
fail:
// can't set iostate - static function
return false;
}
@ -1272,7 +1269,8 @@ bool SdBaseFile::rename(SdBaseFile* dirFile, const char* newPath) {
if (!file.open(dirFile, newPath, O_CREAT | O_EXCL | O_WRITE)) {
goto restore;
}
} else {
}
else {
// don't create missing path prefix components
if (!file.mkdir(dirFile, newPath, false)) {
goto restore;
@ -1311,14 +1309,14 @@ bool SdBaseFile::rename(SdBaseFile* dirFile, const char* newPath) {
}
return vol_->cacheFlush();
restore:
restore:
d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE);
if (!d) goto fail;
// restore entry
d->name[0] = entry.name[0];
vol_->cacheFlush();
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -1358,8 +1356,7 @@ bool SdBaseFile::rmdir() {
type_ = FAT_FILE_TYPE_NORMAL;
flags_ |= O_WRITE;
return remove();
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -1384,7 +1381,7 @@ bool SdBaseFile::rmRfStar() {
rewind();
while (curPosition_ < fileSize_) {
// remember position
index = curPosition_/32;
index = curPosition_ / 32;
dir_t* p = readDirCache();
if (!p) goto fail;
@ -1402,14 +1399,15 @@ bool SdBaseFile::rmRfStar() {
if (f.isSubDir()) {
// recursively delete
if (!f.rmRfStar()) goto fail;
} else {
}
else {
// ignore read-only
f.flags_ |= O_WRITE;
if (!f.remove()) goto fail;
}
// position to next entry if required
if (curPosition_ != (32*(index + 1))) {
if (!seekSet(32*(index + 1))) goto fail;
if (curPosition_ != (32 * (index + 1))) {
if (!seekSet(32 * (index + 1))) goto fail;
}
}
// don't try to delete root
@ -1417,8 +1415,7 @@ bool SdBaseFile::rmRfStar() {
if (!rmdir()) goto fail;
}
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -1465,7 +1462,8 @@ bool SdBaseFile::seekSet(uint32_t pos) {
if (nNew < nCur || curPosition_ == 0) {
// must follow chain from first cluster
curCluster_ = firstCluster_;
} else {
}
else {
// advance from curPosition
nNew -= nCur;
}
@ -1474,10 +1472,10 @@ bool SdBaseFile::seekSet(uint32_t pos) {
}
curPosition_ = pos;
done:
done:
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -1520,7 +1518,7 @@ bool SdBaseFile::sync() {
}
return vol_->cacheFlush();
fail:
fail:
writeError = true;
return false;
}
@ -1560,7 +1558,7 @@ bool SdBaseFile::timestamp(SdBaseFile* file) {
// write back entry
return vol_->cacheFlush();
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -1598,22 +1596,22 @@ bool SdBaseFile::timestamp(SdBaseFile* file) {
* the value zero, false, is returned for failure.
*/
bool SdBaseFile::timestamp(uint8_t flags, uint16_t year, uint8_t month,
uint8_t day, uint8_t hour, uint8_t minute, uint8_t second) {
uint8_t day, uint8_t hour, uint8_t minute, uint8_t second) {
uint16_t dirDate;
uint16_t dirTime;
dir_t* d;
if (!isOpen()
|| year < 1980
|| year > 2107
|| month < 1
|| month > 12
|| day < 1
|| day > 31
|| hour > 23
|| minute > 59
|| second > 59) {
goto fail;
|| year < 1980
|| year > 2107
|| month < 1
|| month > 12
|| day < 1
|| day > 31
|| hour > 23
|| minute > 59
|| second > 59) {
goto fail;
}
// update directory entry
if (!sync()) goto fail;
@ -1637,8 +1635,7 @@ bool SdBaseFile::timestamp(uint8_t flags, uint16_t year, uint8_t month,
d->lastWriteTime = dirTime;
}
return vol_->cacheFlush();
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -1674,7 +1671,8 @@ bool SdBaseFile::truncate(uint32_t length) {
// free all clusters
if (!vol_->freeChain(firstCluster_)) goto fail;
firstCluster_ = 0;
} else {
}
else {
uint32_t toFree;
if (!vol_->fatGet(curCluster_, &toFree)) goto fail;
@ -1696,7 +1694,7 @@ bool SdBaseFile::truncate(uint32_t length) {
// set file to correct position
return seekSet(newPos);
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -1739,16 +1737,19 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) {
if (firstCluster_ == 0) {
// allocate first cluster of file
if (!addCluster()) goto fail;
} else {
}
else {
curCluster_ = firstCluster_;
}
} else {
}
else {
uint32_t next;
if (!vol_->fatGet(curCluster_, &next)) goto fail;
if (vol_->isEOC(next)) {
// add cluster if at end of chain
if (!addCluster()) goto fail;
} else {
}
else {
curCluster_ = next;
}
}
@ -1768,13 +1769,15 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) {
vol_->cacheSetBlockNumber(0XFFFFFFFF, false);
}
if (!vol_->writeBlock(block, src)) goto fail;
} else {
}
else {
if (blockOffset == 0 && curPosition_ >= fileSize_) {
// start of new block don't need to read into cache
if (!vol_->cacheFlush()) goto fail;
// set cache dirty and SD address of block
vol_->cacheSetBlockNumber(block, true);
} else {
}
else {
// rewrite part of block
if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) goto fail;
}
@ -1789,7 +1792,8 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) {
// update fileSize and insure sync will update dir entry
fileSize_ = curPosition_;
flags_ |= F_FILE_DIR_DIRTY;
} else if (dateTime_ && nbyte) {
}
else if (dateTime_ && nbyte) {
// insure sync will update modified date and time
flags_ |= F_FILE_DIR_DIRTY;
}
@ -1799,7 +1803,7 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) {
}
return nbyte;
fail:
fail:
// return for write error
writeError = true;
return -1;
@ -1807,7 +1811,7 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) {
//------------------------------------------------------------------------------
// suppress cpplint warnings with NOLINT comment
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
void (*SdBaseFile::oldDateTime_)(uint16_t& date, uint16_t& time) = 0; // NOLINT
void (*SdBaseFile::oldDateTime_)(uint16_t& date, uint16_t& time) = 0; // NOLINT
#endif // ALLOW_DEPRECATED_FUNCTIONS

View File

@ -158,7 +158,7 @@ static inline uint8_t FAT_HOUR(uint16_t fatTime) {
* \return Extracted minute [0,59]
*/
static inline uint8_t FAT_MINUTE(uint16_t fatTime) {
return(fatTime >> 5) & 0X3F;
return (fatTime >> 5) & 0X3F;
}
/** second part of FAT directory time field
* Note second/2 is stored in packed time.
@ -168,7 +168,7 @@ static inline uint8_t FAT_MINUTE(uint16_t fatTime) {
* \return Extracted second [0,58]
*/
static inline uint8_t FAT_SECOND(uint16_t fatTime) {
return 2*(fatTime & 0X1F);
return 2 * (fatTime & 0X1F);
}
/** Default date for file timestamps is 1 Jan 2000 */
uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
@ -184,7 +184,7 @@ class SdBaseFile {
/** Create an instance. */
SdBaseFile() : writeError(false), type_(FAT_FILE_TYPE_CLOSED) {}
SdBaseFile(const char* path, uint8_t oflag);
~SdBaseFile() {if(isOpen()) close();}
~SdBaseFile() {if (isOpen()) close();}
/**
* writeError is set to true if an error occurs during a write().
* Set writeError to false before calling print() and/or write() and check
@ -205,7 +205,7 @@ class SdBaseFile {
bool close();
bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
bool createContiguous(SdBaseFile* dirFile,
const char* path, uint32_t size);
const char* path, uint32_t size);
/** \return The current cluster number for a file or directory. */
uint32_t curCluster() const {return curCluster_;}
/** \return The current position for a file or directory. */
@ -266,7 +266,7 @@ class SdBaseFile {
bool isRoot() const {
return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32;
}
void ls( uint8_t flags = 0, uint8_t indent = 0);
void ls(uint8_t flags = 0, uint8_t indent = 0);
bool mkdir(SdBaseFile* dir, const char* path, bool pFlag = true);
// alias for backward compactability
bool makeDir(SdBaseFile* dir, const char* path) {
@ -279,7 +279,7 @@ class SdBaseFile {
bool openRoot(SdVolume* vol);
int peek();
static void printFatDate(uint16_t fatDate);
static void printFatTime( uint16_t fatTime);
static void printFatTime(uint16_t fatTime);
bool printName();
int16_t read();
int16_t read(void* buf, uint16_t nbyte);
@ -309,7 +309,7 @@ class SdBaseFile {
bool sync();
bool timestamp(SdBaseFile* file);
bool timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day,
uint8_t hour, uint8_t minute, uint8_t second);
uint8_t hour, uint8_t minute, uint8_t second);
/** Type of file. You should use isFile() or isDir() instead of type()
* if possible.
*
@ -320,7 +320,7 @@ class SdBaseFile {
/** \return SdVolume that contains this file. */
SdVolume* volume() const {return vol_;}
int16_t write(const void* buf, uint16_t nbyte);
//------------------------------------------------------------------------------
//------------------------------------------------------------------------------
private:
// allow SdFat to set cwd_
friend class SdFat;
@ -352,18 +352,18 @@ class SdBaseFile {
bool addCluster();
bool addDirCluster();
dir_t* cacheDirEntry(uint8_t action);
int8_t lsPrintNext( uint8_t flags, uint8_t indent);
int8_t lsPrintNext(uint8_t flags, uint8_t indent);
static bool make83Name(const char* str, uint8_t* name, const char** ptr);
bool mkdir(SdBaseFile* parent, const uint8_t dname[11]);
bool open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag);
bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
dir_t* readDirCache();
//------------------------------------------------------------------------------
// to be deleted
static void printDirName( const dir_t& dir,
uint8_t width, bool printSlash);
//------------------------------------------------------------------------------
// Deprecated functions - suppress cpplint warnings with NOLINT comment
//------------------------------------------------------------------------------
// to be deleted
static void printDirName(const dir_t& dir,
uint8_t width, bool printSlash);
//------------------------------------------------------------------------------
// Deprecated functions - suppress cpplint warnings with NOLINT comment
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
public:
/** \deprecated Use:
@ -375,16 +375,16 @@ class SdBaseFile {
bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) { // NOLINT
return contiguousRange(&bgnBlock, &endBlock);
}
/** \deprecated Use:
* bool createContiguous(SdBaseFile* dirFile,
* const char* path, uint32_t size)
* \param[in] dirFile The directory where the file will be created.
* \param[in] path A path with a valid DOS 8.3 file name.
* \param[in] size The desired file size.
* \return true for success or false for failure.
*/
/** \deprecated Use:
* bool createContiguous(SdBaseFile* dirFile,
* const char* path, uint32_t size)
* \param[in] dirFile The directory where the file will be created.
* \param[in] path A path with a valid DOS 8.3 file name.
* \param[in] size The desired file size.
* \return true for success or false for failure.
*/
bool createContiguous(SdBaseFile& dirFile, // NOLINT
const char* path, uint32_t size) {
const char* path, uint32_t size) {
return createContiguous(&dirFile, path, size);
}
/** \deprecated Use:
@ -422,7 +422,7 @@ class SdBaseFile {
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, // NOLINT
const char* path, uint8_t oflag) {
const char* path, uint8_t oflag) {
return open(&dirFile, path, oflag);
}
/** \deprecated Do not use in new apps
@ -465,8 +465,8 @@ class SdBaseFile {
static bool remove(SdBaseFile& dirFile, const char* path) { // NOLINT
return remove(&dirFile, path);
}
//------------------------------------------------------------------------------
// rest are private
//------------------------------------------------------------------------------
// rest are private
private:
static void (*oldDateTime_)(uint16_t& date, uint16_t& time); // NOLINT
static void oldToNew(uint16_t* date, uint16_t* time) {

View File

@ -25,100 +25,100 @@
#if ENABLED(SDSUPPORT)
#ifndef SdFatConfig_h
#define SdFatConfig_h
#include <stdint.h>
//------------------------------------------------------------------------------
/**
* To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
*
* Using multiple cards costs 400 - 500 bytes of flash.
*
* Each card requires about 550 bytes of SRAM so use of a Mega is recommended.
*/
#define USE_MULTIPLE_CARDS 0
//------------------------------------------------------------------------------
/**
* Call flush for endl if ENDL_CALLS_FLUSH is nonzero
*
* The standard for iostreams is to call flush. This is very costly for
* SdFat. Each call to flush causes 2048 bytes of I/O to the SD.
*
* SdFat has a single 512 byte buffer for SD I/O so it must write the current
* data block to the SD, read the directory block from the SD, update the
* directory entry, write the directory block to the SD and read the data
* block back into the buffer.
*
* The SD flash memory controller is not designed for this many rewrites
* so performance may be reduced by more than a factor of 100.
*
* If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
* all data to be written to the SD.
*/
#define ENDL_CALLS_FLUSH 0
//------------------------------------------------------------------------------
/**
* Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
*/
#define ALLOW_DEPRECATED_FUNCTIONS 1
//------------------------------------------------------------------------------
/**
* Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
* FAT12 has not been well tested.
*/
#define FAT12_SUPPORT 0
//------------------------------------------------------------------------------
/**
* SPI init rate for SD initialization commands. Must be 5 (F_CPU/64)
* or 6 (F_CPU/128).
*/
#define SPI_SD_INIT_RATE 5
//------------------------------------------------------------------------------
/**
* Set the SS pin high for hardware SPI. If SS is chip select for another SPI
* device this will disable that device during the SD init phase.
*/
#define SET_SPI_SS_HIGH 1
//------------------------------------------------------------------------------
/**
* Define MEGA_SOFT_SPI nonzero to use software SPI on Mega Arduinos.
* Pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
*
* MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
* on Mega Arduinos. Software SPI works well with GPS Shield V1.1
* but many SD cards will fail with GPS Shield V1.0.
*/
#define MEGA_SOFT_SPI 0
//------------------------------------------------------------------------------
/**
* Set USE_SOFTWARE_SPI nonzero to always use software SPI.
*/
#define USE_SOFTWARE_SPI 0
// define software SPI pins so Mega can use unmodified 168/328 shields
/** Software SPI chip select pin for the SD */
uint8_t const SOFT_SPI_CS_PIN = 10;
/** Software SPI Master Out Slave In pin */
uint8_t const SOFT_SPI_MOSI_PIN = 11;
/** Software SPI Master In Slave Out pin */
uint8_t const SOFT_SPI_MISO_PIN = 12;
/** Software SPI Clock pin */
uint8_t const SOFT_SPI_SCK_PIN = 13;
//------------------------------------------------------------------------------
/**
* The __cxa_pure_virtual function is an error handler that is invoked when
* a pure virtual function is called.
*/
#define USE_CXA_PURE_VIRTUAL 1
#define SdFatConfig_h
#include <stdint.h>
//------------------------------------------------------------------------------
/**
* To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
*
* Using multiple cards costs 400 - 500 bytes of flash.
*
* Each card requires about 550 bytes of SRAM so use of a Mega is recommended.
*/
#define USE_MULTIPLE_CARDS 0
//------------------------------------------------------------------------------
/**
* Call flush for endl if ENDL_CALLS_FLUSH is nonzero
*
* The standard for iostreams is to call flush. This is very costly for
* SdFat. Each call to flush causes 2048 bytes of I/O to the SD.
*
* SdFat has a single 512 byte buffer for SD I/O so it must write the current
* data block to the SD, read the directory block from the SD, update the
* directory entry, write the directory block to the SD and read the data
* block back into the buffer.
*
* The SD flash memory controller is not designed for this many rewrites
* so performance may be reduced by more than a factor of 100.
*
* If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
* all data to be written to the SD.
*/
#define ENDL_CALLS_FLUSH 0
//------------------------------------------------------------------------------
/**
* Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
*/
#define ALLOW_DEPRECATED_FUNCTIONS 1
//------------------------------------------------------------------------------
/**
* Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
* FAT12 has not been well tested.
*/
#define FAT12_SUPPORT 0
//------------------------------------------------------------------------------
/**
* SPI init rate for SD initialization commands. Must be 5 (F_CPU/64)
* or 6 (F_CPU/128).
*/
#define SPI_SD_INIT_RATE 5
//------------------------------------------------------------------------------
/**
* Set the SS pin high for hardware SPI. If SS is chip select for another SPI
* device this will disable that device during the SD init phase.
*/
#define SET_SPI_SS_HIGH 1
//------------------------------------------------------------------------------
/**
* Define MEGA_SOFT_SPI nonzero to use software SPI on Mega Arduinos.
* Pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
*
* MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
* on Mega Arduinos. Software SPI works well with GPS Shield V1.1
* but many SD cards will fail with GPS Shield V1.0.
*/
#define MEGA_SOFT_SPI 0
//------------------------------------------------------------------------------
/**
* Set USE_SOFTWARE_SPI nonzero to always use software SPI.
*/
#define USE_SOFTWARE_SPI 0
// define software SPI pins so Mega can use unmodified 168/328 shields
/** Software SPI chip select pin for the SD */
uint8_t const SOFT_SPI_CS_PIN = 10;
/** Software SPI Master Out Slave In pin */
uint8_t const SOFT_SPI_MOSI_PIN = 11;
/** Software SPI Master In Slave Out pin */
uint8_t const SOFT_SPI_MISO_PIN = 12;
/** Software SPI Clock pin */
uint8_t const SOFT_SPI_SCK_PIN = 13;
//------------------------------------------------------------------------------
/**
* The __cxa_pure_virtual function is an error handler that is invoked when
* a pure virtual function is called.
*/
#define USE_CXA_PURE_VIRTUAL 1
/** Number of UTF-16 characters per entry */
#define FILENAME_LENGTH 13
/** Number of UTF-16 characters per entry */
#define FILENAME_LENGTH 13
/**
* Defines for long (vfat) filenames
*/
/** Number of VFAT entries used. Every entry has 13 UTF-16 characters */
#define MAX_VFAT_ENTRIES (2)
/** Total size of the buffer used to store the long filenames */
#define LONG_FILENAME_LENGTH (FILENAME_LENGTH*MAX_VFAT_ENTRIES+1)
/**
* Defines for long (vfat) filenames
*/
/** Number of VFAT entries used. Every entry has 13 UTF-16 characters */
#define MAX_VFAT_ENTRIES (2)
/** Total size of the buffer used to store the long filenames */
#define LONG_FILENAME_LENGTH (FILENAME_LENGTH*MAX_VFAT_ENTRIES+1)
#endif // SdFatConfig_h

View File

@ -55,9 +55,9 @@ struct partitionTable {
*/
uint8_t boot;
/**
* Head part of Cylinder-head-sector address of the first block in
* the partition. Legal values are 0-255. Only used in old PC BIOS.
*/
* Head part of Cylinder-head-sector address of the first block in
* the partition. Legal values are 0-255. Only used in old PC BIOS.
*/
uint8_t beginHead;
/**
* Sector part of Cylinder-head-sector address of the first block in
@ -337,10 +337,10 @@ struct fat32_boot {
* Bits 0-3 -- Zero-based number of active FAT.
* Only valid if mirroring is disabled.
* Bits 4-6 -- Reserved.
* Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs.
* -- 1 means only one FAT is active; it is the one referenced
* in bits 0-3.
* Bits 8-15 -- Reserved.
* Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs.
* -- 1 means only one FAT is active; it is the one referenced
* in bits 0-3.
* Bits 8-15 -- Reserved.
*/
uint16_t fat32Flags;
/**
@ -468,29 +468,29 @@ uint32_t const FAT32MASK = 0X0FFFFFFF;
* \brief FAT short directory entry
*
* Short means short 8.3 name, not the entry size.
*
* Date Format. A FAT directory entry date stamp is a 16-bit field that is
*
* Date Format. A FAT directory entry date stamp is a 16-bit field that is
* basically a date relative to the MS-DOS epoch of 01/01/1980. Here is the
* format (bit 0 is the LSB of the 16-bit word, bit 15 is the MSB of the
* format (bit 0 is the LSB of the 16-bit word, bit 15 is the MSB of the
* 16-bit word):
*
* Bits 9-15: Count of years from 1980, valid value range 0-127
*
* Bits 9-15: Count of years from 1980, valid value range 0-127
* inclusive (1980-2107).
*
*
* Bits 5-8: Month of year, 1 = January, valid value range 1-12 inclusive.
*
* Bits 0-4: Day of month, valid value range 1-31 inclusive.
*
* Time Format. A FAT directory entry time stamp is a 16-bit field that has
* a granularity of 2 seconds. Here is the format (bit 0 is the LSB of the
* a granularity of 2 seconds. Here is the format (bit 0 is the LSB of the
* 16-bit word, bit 15 is the MSB of the 16-bit word).
*
*
* Bits 11-15: Hours, valid value range 0-23 inclusive.
*
*
* Bits 5-10: Minutes, valid value range 0-59 inclusive.
*
*
* Bits 0-4: 2-second count, valid value range 0-29 inclusive (0 - 58 seconds).
*
*
* The valid time range is from Midnight 00:00:00 to 23:59:58.
*/
struct directoryEntry {
@ -548,7 +548,7 @@ struct directoryEntry {
*
* directoryVFATEntries are found in the same list as normal directoryEntry.
* But have the attribute field set to DIR_ATT_LONG_NAME.
*
*
* Long filenames are saved in multiple directoryVFATEntries.
* Each entry containing 13 UTF-16 characters.
*/

View File

@ -33,7 +33,7 @@ int SdFatUtil::FreeRam() {
return &top - reinterpret_cast<char*>(sbrk(0));
}
#else // __arm__
extern char *__brkval;
extern char* __brkval;
extern char __bss_end;
/** Amount of free RAM
* \return The number of free bytes.
@ -50,7 +50,7 @@ int SdFatUtil::FreeRam() {
* \param[in] pr Print object for output.
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::print_P( PGM_P str) {
void SdFatUtil::print_P(PGM_P str) {
for (uint8_t c; (c = pgm_read_byte(str)); str++) MYSERIAL.write(c);
}
//------------------------------------------------------------------------------
@ -59,8 +59,8 @@ void SdFatUtil::print_P( PGM_P str) {
* \param[in] pr Print object for output.
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::println_P( PGM_P str) {
print_P( str);
void SdFatUtil::println_P(PGM_P str) {
print_P(str);
MYSERIAL.println();
}
//------------------------------------------------------------------------------
@ -77,6 +77,6 @@ void SdFatUtil::SerialPrint_P(PGM_P str) {
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::SerialPrintln_P(PGM_P str) {
println_P( str);
println_P(str);
}
#endif

View File

@ -35,8 +35,8 @@
namespace SdFatUtil {
int FreeRam();
void print_P( PGM_P str);
void println_P( PGM_P str);
void print_P(PGM_P str);
void println_P(PGM_P str);
void SerialPrint_P(PGM_P str);
void SerialPrintln_P(PGM_P str);
}

View File

@ -55,15 +55,13 @@ int16_t SdFile::write(const void* buf, uint16_t nbyte) {
* Use writeError to check for errors.
*/
#if ARDUINO >= 100
size_t SdFile::write(uint8_t b)
{
size_t SdFile::write(uint8_t b) {
return SdBaseFile::write(&b, 1);
}
}
#else
void SdFile::write(uint8_t b)
{
void SdFile::write(uint8_t b) {
SdBaseFile::write(&b, 1);
}
}
#endif
//------------------------------------------------------------------------------
/** Write a string to a file. Used by the Arduino Print class.

View File

@ -38,11 +38,11 @@ class SdFile : public SdBaseFile, public Print {
SdFile() {}
SdFile(const char* name, uint8_t oflag);
#if ARDUINO >= 100
size_t write(uint8_t b);
size_t write(uint8_t b);
#else
void write(uint8_t b);
#endif
int16_t write(const void* buf, uint16_t nbyte);
void write(const char* str);
void write_P(PGM_P str);

View File

@ -118,13 +118,13 @@ typedef struct CID {
/** Manufacturing date month */
unsigned char mdt_month : 4;
/** Manufacturing date year low digit */
unsigned char mdt_year_low :4;
unsigned char mdt_year_low : 4;
// byte 15
/** not used always 1 */
unsigned char always1 : 1;
/** CRC7 checksum */
unsigned char crc : 7;
}cid_t;
} cid_t;
//------------------------------------------------------------------------------
/** CSD for version 1.00 cards */
typedef struct CSDV1 {
@ -146,7 +146,7 @@ typedef struct CSDV1 {
unsigned char c_size_high : 2;
unsigned char reserved2 : 2;
unsigned char dsr_imp : 1;
unsigned char read_blk_misalign :1;
unsigned char read_blk_misalign : 1;
unsigned char write_blk_misalign : 1;
unsigned char read_bl_partial : 1;
// byte 7
@ -154,7 +154,7 @@ typedef struct CSDV1 {
// byte 8
unsigned char vdd_r_curr_max : 3;
unsigned char vdd_r_curr_min : 3;
unsigned char c_size_low :2;
unsigned char c_size_low : 2;
// byte 9
unsigned char c_size_mult_high : 2;
unsigned char vdd_w_cur_max : 3;
@ -186,7 +186,7 @@ typedef struct CSDV1 {
// byte 15
unsigned char always1 : 1;
unsigned char crc : 7;
}csd1_t;
} csd1_t;
//------------------------------------------------------------------------------
/** CSD for version 2.00 cards */
typedef struct CSDV2 {
@ -212,7 +212,7 @@ typedef struct CSDV2 {
unsigned char reserved2 : 4;
unsigned char dsr_imp : 1;
/** fixed to 0 */
unsigned char read_blk_misalign :1;
unsigned char read_blk_misalign : 1;
/** fixed to 0 */
unsigned char write_blk_misalign : 1;
/** fixed to 0 - no partial read */
@ -268,7 +268,7 @@ typedef struct CSDV2 {
unsigned char always1 : 1;
/** checksum */
unsigned char crc : 7;
}csd2_t;
} csd2_t;
//------------------------------------------------------------------------------
/** union of old and new style CSD register */
union csd_t {

View File

@ -23,12 +23,12 @@
#include "SdVolume.h"
//------------------------------------------------------------------------------
#if !USE_MULTIPLE_CARDS
// raw block cache
uint32_t SdVolume::cacheBlockNumber_; // current block number
cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card
Sd2Card* SdVolume::sdCard_; // pointer to SD card object
bool SdVolume::cacheDirty_; // cacheFlush() will write block if true
uint32_t SdVolume::cacheMirrorBlock_; // mirror block for second FAT
// raw block cache
uint32_t SdVolume::cacheBlockNumber_; // current block number
cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card
Sd2Card* SdVolume::sdCard_; // pointer to SD card object
bool SdVolume::cacheDirty_; // cacheFlush() will write block if true
uint32_t SdVolume::cacheMirrorBlock_; // mirror block for second FAT
#endif // USE_MULTIPLE_CARDS
//------------------------------------------------------------------------------
// find a contiguous group of clusters
@ -50,7 +50,8 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
// don't save new start location
setStart = false;
} else {
}
else {
// start at likely place for free cluster
bgnCluster = allocSearchStart_;
@ -75,7 +76,8 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
if (f != 0) {
// cluster in use try next cluster as bgnCluster
bgnCluster = endCluster + 1;
} else if ((endCluster - bgnCluster + 1) == count) {
}
else if ((endCluster - bgnCluster + 1) == count) {
// done - found space
break;
}
@ -99,8 +101,7 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
if (setStart) allocSearchStart_ = bgnCluster + 1;
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -119,8 +120,7 @@ bool SdVolume::cacheFlush() {
cacheDirty_ = 0;
}
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -132,8 +132,7 @@ bool SdVolume::cacheRawBlock(uint32_t blockNumber, bool dirty) {
}
if (dirty) cacheDirty_ = true;
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -146,8 +145,7 @@ bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) {
} while (!isEOC(cluster));
*size = s;
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -173,9 +171,11 @@ bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
}
if (fatType_ == 16) {
lba = fatStartBlock_ + (cluster >> 8);
} else if (fatType_ == 32) {
}
else if (fatType_ == 32) {
lba = fatStartBlock_ + (cluster >> 7);
} else {
}
else {
goto fail;
}
if (lba != cacheBlockNumber_) {
@ -183,12 +183,12 @@ bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
}
if (fatType_ == 16) {
*value = cacheBuffer_.fat16[cluster & 0XFF];
} else {
}
else {
*value = cacheBuffer_.fat32[cluster & 0X7F] & FAT32MASK;
}
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -231,23 +231,25 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
}
if (fatType_ == 16) {
lba = fatStartBlock_ + (cluster >> 8);
} else if (fatType_ == 32) {
}
else if (fatType_ == 32) {
lba = fatStartBlock_ + (cluster >> 7);
} else {
}
else {
goto fail;
}
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail;
// store entry
if (fatType_ == 16) {
cacheBuffer_.fat16[cluster & 0XFF] = value;
} else {
}
else {
cacheBuffer_.fat32[cluster & 0X7F] = value;
}
// mirror second FAT
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -268,8 +270,7 @@ bool SdVolume::freeChain(uint32_t cluster) {
} while (!isEOC(cluster));
return true;
fail:
fail:
return false;
}
//------------------------------------------------------------------------------
@ -284,9 +285,11 @@ int32_t SdVolume::freeClusterCount() {
if (fatType_ == 16) {
n = 256;
} else if (fatType_ == 32) {
}
else if (fatType_ == 32) {
n = 128;
} else {
}
else {
// put FAT12 here
return -1;
}
@ -298,7 +301,8 @@ int32_t SdVolume::freeClusterCount() {
for (uint16_t i = 0; i < n; i++) {
if (cacheBuffer_.fat16[i] == 0) free++;
}
} else {
}
else {
for (uint16_t i = 0; i < n; i++) {
if (cacheBuffer_.fat32[i] == 0) free++;
}
@ -338,10 +342,10 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
if (part) {
if (part > 4)goto fail;
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail;
part_t* p = &cacheBuffer_.mbr.part[part-1];
if ((p->boot & 0X7F) !=0 ||
p->totalSectors < 100 ||
p->firstSector == 0) {
part_t* p = &cacheBuffer_.mbr.part[part - 1];
if ((p->boot & 0X7F) != 0 ||
p->totalSectors < 100 ||
p->firstSector == 0) {
// not a valid partition
goto fail;
}
@ -350,11 +354,11 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail;
fbs = &cacheBuffer_.fbs32;
if (fbs->bytesPerSector != 512 ||
fbs->fatCount == 0 ||
fbs->reservedSectorCount == 0 ||
fbs->sectorsPerCluster == 0) {
// not valid FAT volume
goto fail;
fbs->fatCount == 0 ||
fbs->reservedSectorCount == 0 ||
fbs->sectorsPerCluster == 0) {
// not valid FAT volume
goto fail;
}
fatCount_ = fbs->fatCount;
blocksPerCluster_ = fbs->sectorsPerCluster;
@ -365,7 +369,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
if (clusterSizeShift_++ > 7) goto fail;
}
blocksPerFat_ = fbs->sectorsPerFat16 ?
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
fatStartBlock_ = volumeStartBlock + fbs->reservedSectorCount;
@ -376,11 +380,12 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
rootDirStart_ = fatStartBlock_ + fbs->fatCount * blocksPerFat_;
// data start for FAT16 and FAT32
dataStartBlock_ = rootDirStart_ + ((32 * fbs->rootDirEntryCount + 511)/512);
dataStartBlock_ = rootDirStart_ + ((32 * fbs->rootDirEntryCount + 511) / 512);
// total blocks for FAT16 or FAT32
totalBlocks = fbs->totalSectors16 ?
fbs->totalSectors16 : fbs->totalSectors32;
fbs->totalSectors16 : fbs->totalSectors32;
// total data blocks
clusterCount_ = totalBlocks - (dataStartBlock_ - volumeStartBlock);
@ -391,15 +396,16 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
if (clusterCount_ < 4085) {
fatType_ = 12;
if (!FAT12_SUPPORT) goto fail;
} else if (clusterCount_ < 65525) {
}
else if (clusterCount_ < 65525) {
fatType_ = 16;
} else {
}
else {
rootDirStart_ = fbs->fat32RootCluster;
fatType_ = 32;
}
return true;
fail:
fail:
return false;
}
#endif

View File

@ -117,7 +117,7 @@ class SdVolume {
* \return true for success or false for failure
*/
bool dbgFat(uint32_t n, uint32_t* v) {return fatGet(n, v);}
//------------------------------------------------------------------------------
//------------------------------------------------------------------------------
private:
// Allow SdBaseFile access to SdVolume private data.
friend class SdBaseFile;
@ -154,12 +154,15 @@ class SdVolume {
//----------------------------------------------------------------------------
bool allocContiguous(uint32_t count, uint32_t* curCluster);
uint8_t blockOfCluster(uint32_t position) const {
return (position >> 9) & (blocksPerCluster_ - 1);}
return (position >> 9) & (blocksPerCluster_ - 1);
}
uint32_t clusterStartBlock(uint32_t cluster) const {
return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_);}
return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_);
}
uint32_t blockNumber(uint32_t cluster, uint32_t position) const {
return clusterStartBlock(cluster) + blockOfCluster(position);}
cache_t *cache() {return &cacheBuffer_;}
return clusterStartBlock(cluster) + blockOfCluster(position);
}
cache_t* cache() {return &cacheBuffer_;}
uint32_t cacheBlockNumber() {return cacheBlockNumber_;}
#if USE_MULTIPLE_CARDS
bool cacheFlush();
@ -187,11 +190,12 @@ class SdVolume {
return cluster >= FAT32EOC_MIN;
}
bool readBlock(uint32_t block, uint8_t* dst) {
return sdCard_->readBlock(block, dst);}
return sdCard_->readBlock(block, dst);
}
bool writeBlock(uint32_t block, const uint8_t* dst) {
return sdCard_->writeBlock(block, dst);
}
//------------------------------------------------------------------------------
//------------------------------------------------------------------------------
// Deprecated functions - suppress cpplint warnings with NOLINT comment
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
public:

View File

@ -9,7 +9,7 @@
#include "blinkm.h"
void SendColors(byte red, byte grn, byte blu) {
Wire.begin();
Wire.begin();
Wire.beginTransmission(0x09);
Wire.write('o'); //to disable ongoing script, only needs to be used once
Wire.write('n');

View File

@ -2,7 +2,7 @@
#define BUZZER_H
#if HAS_BUZZER
void buzz(long duration,uint16_t freq);
void buzz(long duration, uint16_t freq);
#endif
#endif //BUZZER_H

View File

@ -248,9 +248,8 @@ void CardReader::release() {
}
void CardReader::startFileprint() {
if (cardOK) {
if (cardOK)
sdprinting = true;
}
}
void CardReader::pauseSDPrint() {
@ -267,7 +266,7 @@ void CardReader::getAbsFilename(char *t) {
*t = '/'; t++; cnt++;
for (uint8_t i = 0; i < workDirDepth; i++) {
workDirParents[i].getFilename(t); //SDBaseFile.getfilename!
while(*t && cnt < MAXPATHNAMELENGTH) { t++; cnt++; } //crawl counter forward.
while (*t && cnt < MAXPATHNAMELENGTH) { t++; cnt++; } //crawl counter forward.
}
if (cnt < MAXPATHNAMELENGTH - FILENAME_LENGTH)
file.getFilename(t);
@ -279,34 +278,34 @@ void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/)
if (!cardOK) return;
if (file.isOpen()) { //replacing current file by new file, or subfile call
if (!replace_current) {
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
SERIAL_ERRORLN(SD_PROCEDURE_DEPTH);
kill(PSTR(MSG_KILLED));
return;
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
SERIAL_ERRORLN(SD_PROCEDURE_DEPTH);
kill(PSTR(MSG_KILLED));
return;
}
SERIAL_ECHO_START;
SERIAL_ECHOPGM("SUBROUTINE CALL target:\"");
SERIAL_ECHO(name);
SERIAL_ECHOPGM("\" parent:\"");
//store current filename and position
getAbsFilename(filenames[file_subcall_ctr]);
SERIAL_ECHO(filenames[file_subcall_ctr]);
SERIAL_ECHOPGM("\" pos");
SERIAL_ECHOLN(sdpos);
filespos[file_subcall_ctr] = sdpos;
file_subcall_ctr++;
}
SERIAL_ECHO_START;
SERIAL_ECHOPGM("SUBROUTINE CALL target:\"");
SERIAL_ECHO(name);
SERIAL_ECHOPGM("\" parent:\"");
//store current filename and position
getAbsFilename(filenames[file_subcall_ctr]);
SERIAL_ECHO(filenames[file_subcall_ctr]);
SERIAL_ECHOPGM("\" pos");
SERIAL_ECHOLN(sdpos);
filespos[file_subcall_ctr] = sdpos;
file_subcall_ctr++;
}
else {
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Now doing file: ");
SERIAL_ECHOLN(name);
}
file.close();
else {
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Now doing file: ");
SERIAL_ECHOLN(name);
}
file.close();
}
else { //opening fresh file
file_subcall_ctr = 0; //resetting procedure depth in case user cancels print while in procedure

View File

@ -38,7 +38,7 @@ public:
void getAbsFilename(char *t);
void ls();
void chdir(const char * relpath);
void chdir(const char *relpath);
void updir();
void setroot();

View File

@ -102,7 +102,7 @@
void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) {
uint8_t c;
while(size--) {
while (size--) {
eeprom_write_byte((unsigned char*)pos, *value);
c = eeprom_read_byte((unsigned char*)pos);
if (c != *value) {
@ -156,7 +156,7 @@ void Config_StoreSettings() {
uint8_t mesh_num_y = 3;
#if ENABLED(MESH_BED_LEVELING)
// Compile time test that sizeof(mbl.z_values) is as expected
typedef char c_assert[(sizeof(mbl.z_values) == MESH_NUM_X_POINTS*MESH_NUM_Y_POINTS*sizeof(dummy)) ? 1 : -1];
typedef char c_assert[(sizeof(mbl.z_values) == MESH_NUM_X_POINTS * MESH_NUM_Y_POINTS * sizeof(dummy)) ? 1 : -1];
mesh_num_x = MESH_NUM_X_POINTS;
mesh_num_y = MESH_NUM_Y_POINTS;
EEPROM_WRITE_VAR(i, mbl.active);
@ -169,7 +169,7 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, mesh_num_x);
EEPROM_WRITE_VAR(i, mesh_num_y);
dummy = 0.0f;
for (uint8_t q=0; q<mesh_num_x*mesh_num_y; q++) EEPROM_WRITE_VAR(i, dummy);
for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_WRITE_VAR(i, dummy);
#endif // MESH_BED_LEVELING
#if DISABLED(AUTO_BED_LEVELING_FEATURE)
@ -185,10 +185,10 @@ void Config_StoreSettings() {
#elif ENABLED(Z_DUAL_ENDSTOPS)
EEPROM_WRITE_VAR(i, z_endstop_adj); // 1 floats
dummy = 0.0f;
for (int q=5; q--;) EEPROM_WRITE_VAR(i, dummy);
for (int q = 5; q--;) EEPROM_WRITE_VAR(i, dummy);
#else
dummy = 0.0f;
for (int q=6; q--;) EEPROM_WRITE_VAR(i, dummy);
for (int q = 6; q--;) EEPROM_WRITE_VAR(i, dummy);
#endif
#if DISABLED(ULTIPANEL)
@ -579,7 +579,7 @@ void Config_ResetDefault() {
#endif
volumetric_enabled = false;
for (uint8_t q=0; q<COUNT(filament_size); q++)
for (uint8_t q = 0; q < COUNT(filament_size); q++)
filament_size[q] = DEFAULT_NOMINAL_FILAMENT_DIA;
calculate_volumetric_multipliers();
@ -686,8 +686,8 @@ void Config_PrintSettings(bool forReplay) {
SERIAL_ECHOPAIR(" X", (unsigned long)MESH_NUM_X_POINTS);
SERIAL_ECHOPAIR(" Y", (unsigned long)MESH_NUM_Y_POINTS);
SERIAL_EOL;
for (int y=0; y<MESH_NUM_Y_POINTS; y++) {
for (int x=0; x<MESH_NUM_X_POINTS; x++) {
for (int y = 0; y < MESH_NUM_Y_POINTS; y++) {
for (int x = 0; x < MESH_NUM_X_POINTS; x++) {
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M421 X", mbl.get_x(x));
SERIAL_ECHOPAIR(" Y", mbl.get_y(y));
@ -721,7 +721,7 @@ void Config_PrintSettings(bool forReplay) {
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M666 Z", z_endstop_adj);
SERIAL_EOL;
SERIAL_EOL;
#endif // DELTA
#if ENABLED(ULTIPANEL)
@ -810,7 +810,7 @@ void Config_PrintSettings(bool forReplay) {
#if EXTRUDERS > 1
SERIAL_ECHOPAIR(" W", retract_length_swap);
#endif
SERIAL_ECHOPAIR(" F", retract_feedrate*60);
SERIAL_ECHOPAIR(" F", retract_feedrate * 60);
SERIAL_ECHOPAIR(" Z", retract_zlift);
SERIAL_EOL;
CONFIG_ECHO_START;
@ -822,7 +822,7 @@ void Config_PrintSettings(bool forReplay) {
#if EXTRUDERS > 1
SERIAL_ECHOPAIR(" W", retract_recover_length_swap);
#endif
SERIAL_ECHOPAIR(" F", retract_recover_feedrate*60);
SERIAL_ECHOPAIR(" F", retract_recover_feedrate * 60);
SERIAL_EOL;
CONFIG_ECHO_START;
if (!forReplay) {

View File

@ -16,7 +16,7 @@
#endif
static byte current_to_wiper(float current) {
return byte(ceil(float((DIGIPOT_I2C_FACTOR*current))));
return byte(ceil(float((DIGIPOT_I2C_FACTOR * current))));
}
static void i2c_send(byte addr, byte a, byte b) {
@ -28,13 +28,13 @@ static void i2c_send(byte addr, byte a, byte b) {
// This is for the MCP4451 I2C based digipot
void digipot_i2c_set_current(int channel, float current) {
current = min( (float) max( current, 0.0f ), DIGIPOT_I2C_MAX_CURRENT);
current = min((float) max(current, 0.0f), DIGIPOT_I2C_MAX_CURRENT);
// these addresses are specific to Azteeg X3 Pro, can be set to others,
// In this case first digipot is at address A0=0, A1= 0, second one is at A0=0, A1= 1
byte addr = 0x2C; // channel 0-3
if (channel >= 4) {
addr = 0x2E; // channel 4-7
channel -= 4;
addr = 0x2E; // channel 4-7
channel -= 4;
}
// Initial setup
@ -50,9 +50,8 @@ void digipot_i2c_init() {
const float digipot_motor_current[] = DIGIPOT_I2C_MOTOR_CURRENTS;
Wire.begin();
// setup initial currents as defined in Configuration_adv.h
for(int i = 0; i < COUNT(digipot_motor_current); i++) {
for (int i = 0; i < COUNT(digipot_motor_current); i++)
digipot_i2c_set_current(i, digipot_motor_current[i]);
}
}
#endif //DIGIPOT_I2C

View File

@ -1,6 +1,6 @@
// BitMap for splashscreen
// Generated with: http://www.digole.com/tools/PicturetoC_Hex_converter.php
// Please note that using the high-res version takes 402Bytes of PROGMEM.
// Please note that using the high-res version takes 402Bytes of PROGMEM.
//#define START_BMPHIGH
#if ENABLED(SHOW_BOOTSCREEN)
@ -11,44 +11,44 @@
#define START_BMPBYTES 532 // START_BMPWIDTH * START_BMPHEIGHT / 8
const unsigned char start_bmp[START_BMPBYTES] PROGMEM = {
0x01,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff
,0x0f,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff
,0x1e,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x07,0xff,0xff
,0x38,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x03,0xff,0xff
,0x70,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xff,0xff
,0x60,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xff,0xff
,0x60,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7f,0xff
,0xc0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x78,0x00,0x00,0x3f,0xff
,0xc0,0x0f,0xc0,0xfc,0x00,0x00,0x00,0x00,0x00,0x78,0x18,0x00,0x1f,0xff
,0xc0,0x3f,0xe1,0xff,0x00,0x00,0x00,0x00,0x00,0x78,0x3c,0x00,0x0f,0xff
,0xc0,0x7f,0xf3,0xff,0x80,0x00,0x00,0x00,0x00,0x78,0x3c,0x00,0x07,0xff
,0xc0,0xff,0xff,0xff,0xc0,0x00,0x00,0x00,0x00,0x78,0x3c,0x00,0x03,0xff
,0xc1,0xf8,0x7f,0x87,0xe0,0x00,0x00,0x00,0x00,0x78,0x00,0x00,0x01,0xff
,0xc1,0xf0,0x3f,0x03,0xe0,0x00,0x00,0x00,0x00,0x78,0x00,0x00,0x00,0xff
,0xc1,0xe0,0x1e,0x01,0xe0,0x1f,0x00,0x03,0xe0,0x78,0x3c,0x03,0xf0,0x7f
,0xc1,0xe0,0x1e,0x01,0xe0,0x7f,0xc0,0x0f,0xf8,0x78,0x3c,0x07,0xfc,0x3f
,0xc1,0xe0,0x1e,0x01,0xe1,0xff,0xe0,0x1f,0xfc,0x78,0x3c,0x0f,0xfe,0x1f
,0xc1,0xe0,0x1e,0x01,0xe3,0xff,0xf0,0x3f,0xfe,0x78,0x3c,0x1f,0xfe,0x0f
,0xc1,0xe0,0x1e,0x01,0xe3,0xf3,0xf8,0x3f,0x3e,0x78,0x3c,0x3f,0x3f,0x07
,0xc1,0xe0,0x1e,0x01,0xe7,0xe0,0xfc,0x7c,0x1f,0x78,0x3c,0x3e,0x1f,0x07
,0xc1,0xe0,0x1e,0x01,0xe7,0xc0,0x7c,0x7c,0x0f,0x78,0x3c,0x3c,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe7,0x80,0x7c,0x78,0x0f,0x78,0x3c,0x3c,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe7,0x80,0x3c,0x78,0x00,0x78,0x3c,0x3c,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe7,0x80,0x3c,0x78,0x00,0x78,0x3c,0x3c,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe7,0x80,0x3c,0x78,0x00,0x78,0x3c,0x3c,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe7,0xc0,0x3c,0x78,0x00,0x78,0x3c,0x3c,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe3,0xe0,0x3c,0x78,0x00,0x7c,0x3c,0x3c,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe3,0xff,0x3f,0xf8,0x00,0x7f,0xbc,0x3c,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe1,0xff,0x3f,0xf8,0x00,0x3f,0xbf,0xfc,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe0,0xff,0x3f,0xf8,0x00,0x1f,0xbf,0xfc,0x0f,0x03
,0xc1,0xe0,0x1e,0x01,0xe0,0x7f,0x3f,0xf8,0x00,0x0f,0xbf,0xfc,0x0f,0x03
,0x60,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x07
,0x60,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x06
,0x70,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x0e
,0x38,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x1c
,0x1e,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x78
,0x0f,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xf0
,0x01,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0x80 };
0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFF, 0xFF,
0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF,
0x70, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF,
0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF,
0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF,
0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3F, 0xFF,
0xC0, 0x0F, 0xC0, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x18, 0x00, 0x1F, 0xFF,
0xC0, 0x3F, 0xE1, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x0F, 0xFF,
0xC0, 0x7F, 0xF3, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x07, 0xFF,
0xC0, 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x03, 0xFF,
0xC1, 0xF8, 0x7F, 0x87, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xFF,
0xC1, 0xF0, 0x3F, 0x03, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0xFF,
0xC1, 0xE0, 0x1E, 0x01, 0xE0, 0x1F, 0x00, 0x03, 0xE0, 0x78, 0x3C, 0x03, 0xF0, 0x7F,
0xC1, 0xE0, 0x1E, 0x01, 0xE0, 0x7F, 0xC0, 0x0F, 0xF8, 0x78, 0x3C, 0x07, 0xFC, 0x3F,
0xC1, 0xE0, 0x1E, 0x01, 0xE1, 0xFF, 0xE0, 0x1F, 0xFC, 0x78, 0x3C, 0x0F, 0xFE, 0x1F,
0xC1, 0xE0, 0x1E, 0x01, 0xE3, 0xFF, 0xF0, 0x3F, 0xFE, 0x78, 0x3C, 0x1F, 0xFE, 0x0F,
0xC1, 0xE0, 0x1E, 0x01, 0xE3, 0xF3, 0xF8, 0x3F, 0x3E, 0x78, 0x3C, 0x3F, 0x3F, 0x07,
0xC1, 0xE0, 0x1E, 0x01, 0xE7, 0xE0, 0xFC, 0x7C, 0x1F, 0x78, 0x3C, 0x3E, 0x1F, 0x07,
0xC1, 0xE0, 0x1E, 0x01, 0xE7, 0xC0, 0x7C, 0x7C, 0x0F, 0x78, 0x3C, 0x3C, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE7, 0x80, 0x7C, 0x78, 0x0F, 0x78, 0x3C, 0x3C, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE7, 0x80, 0x3C, 0x78, 0x00, 0x78, 0x3C, 0x3C, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE7, 0x80, 0x3C, 0x78, 0x00, 0x78, 0x3C, 0x3C, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE7, 0x80, 0x3C, 0x78, 0x00, 0x78, 0x3C, 0x3C, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE7, 0xC0, 0x3C, 0x78, 0x00, 0x78, 0x3C, 0x3C, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE3, 0xE0, 0x3C, 0x78, 0x00, 0x7C, 0x3C, 0x3C, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE3, 0xFF, 0x3F, 0xF8, 0x00, 0x7F, 0xBC, 0x3C, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE1, 0xFF, 0x3F, 0xF8, 0x00, 0x3F, 0xBF, 0xFC, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE0, 0xFF, 0x3F, 0xF8, 0x00, 0x1F, 0xBF, 0xFC, 0x0F, 0x03,
0xC1, 0xE0, 0x1E, 0x01, 0xE0, 0x7F, 0x3F, 0xF8, 0x00, 0x0F, 0xBF, 0xFC, 0x0F, 0x03,
0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07,
0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06,
0x70, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0E,
0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1C,
0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78,
0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0,
0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80 };
#else
#define START_BMPWIDTH 56
#define START_BMPHEIGHT 19
@ -56,184 +56,183 @@
#define START_BMPBYTES 133 // START_BMPWIDTH * START_BMPHEIGHT / 8
const unsigned char start_bmp[START_BMPBYTES] PROGMEM = {
0x1f,0xff,0xff,0xff,0xff,0xff,0xff
,0x60,0x00,0x00,0x00,0x00,0x01,0xff
,0x40,0x00,0x00,0x00,0x00,0x00,0xff
,0x80,0x00,0x00,0x00,0x00,0x00,0x7f
,0x83,0xcf,0x00,0x00,0x0c,0x30,0x3f
,0x87,0xff,0x80,0x00,0x0c,0x30,0x1f
,0x86,0x79,0x80,0x00,0x0c,0x00,0x0f
,0x8c,0x30,0xc7,0x83,0x8c,0x30,0xe7
,0x8c,0x30,0xcf,0xc7,0xcc,0x31,0xf3
,0x8c,0x30,0xdc,0xec,0xec,0x33,0xb9
,0x8c,0x30,0xd8,0x6c,0x6c,0x33,0x19
,0x8c,0x30,0xd0,0x6c,0x0c,0x33,0x19
,0x8c,0x30,0xd8,0x6c,0x0c,0x33,0x19
,0x8c,0x30,0xdc,0x6c,0x0e,0x3b,0x19
,0x8c,0x30,0xcf,0x7c,0x07,0x9f,0x19
,0x8c,0x30,0xc7,0x7c,0x03,0x8f,0x19
,0x40,0x00,0x00,0x00,0x00,0x00,0x02
,0x60,0x00,0x00,0x00,0x00,0x00,0x06
,0x1f,0xff,0xff,0xff,0xff,0xff,0xf8 };
0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0x60, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF,
0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF,
0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F,
0x83, 0xCF, 0x00, 0x00, 0x0C, 0x30, 0x3F,
0x87, 0xFF, 0x80, 0x00, 0x0C, 0x30, 0x1F,
0x86, 0x79, 0x80, 0x00, 0x0C, 0x00, 0x0F,
0x8C, 0x30, 0xC7, 0x83, 0x8C, 0x30, 0xE7,
0x8C, 0x30, 0xCF, 0xC7, 0xCC, 0x31, 0xF3,
0x8C, 0x30, 0xDC, 0xEC, 0xEC, 0x33, 0xB9,
0x8C, 0x30, 0xD8, 0x6C, 0x6C, 0x33, 0x19,
0x8C, 0x30, 0xD0, 0x6C, 0x0C, 0x33, 0x19,
0x8C, 0x30, 0xD8, 0x6C, 0x0C, 0x33, 0x19,
0x8C, 0x30, 0xDC, 0x6C, 0x0E, 0x3B, 0x19,
0x8C, 0x30, 0xCF, 0x7C, 0x07, 0x9F, 0x19,
0x8C, 0x30, 0xC7, 0x7C, 0x03, 0x8F, 0x19,
0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02,
0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06,
0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8 };
#endif
#endif
// Here comes a compile-time operation to match the extruder symbols
// Here comes a compile-time operation to match the extruder symbols
// on the info screen to the set number of extruders in configuration.h
//
// When only one extruder is selected, the "1" on the symbol will not
//
// When only one extruder is selected, the "1" on the symbol will not
// be displayed.
#if EXTRUDERS == 1
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x0E,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x4F,0x0F,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5F,0x0F,0xA0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5E,0x07,0xA0,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x5E,0x07,0xA0,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x5F,0x0F,0xA0,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x4F,0x0F,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x47,0x0E,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x63,0x0C,0x60,
0x3F,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x5E, 0x07, 0xA0,
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x5F, 0x0F, 0xA0,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x4F, 0x0F, 0x20,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x47, 0x0E, 0x20,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x63, 0x0C, 0x60,
0x3F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0xF8,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0xF0,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x60,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58,0x01,0xA0,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x58,0x01,0xA0,
0x7F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x40,0x60,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x40,0xF0,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x41,0xF8,0x20,
0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x61,0xF8,0x60,
0x3F,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x58, 0x01, 0xA0,
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x40, 0x60, 0x20,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x40, 0xF0, 0x20,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x41, 0xF8, 0x20,
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x61, 0xF8, 0x60,
0x3F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
};
#elif EXTRUDERS == 2
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x0E,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x4F,0x0F,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5F,0x0F,0xA0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5E,0x07,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x5E,0x07,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x5F,0x0F,0xA0,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x4F,0x0F,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x47,0x0E,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x63,0x0C,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
0x7F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
0xFB, 0xC0, 0x00, 0x79, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
0xF3, 0xC0, 0x00, 0x76, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
0xEB, 0xC0, 0x00, 0x7E, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
0x7B, 0x80, 0x00, 0x3D, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x5E, 0x07, 0xA0,
0x7B, 0x80, 0x00, 0x3B, 0xC0, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x5F, 0x0F, 0xA0,
0xFB, 0xC0, 0x00, 0x77, 0xE0, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x4F, 0x0F, 0x20,
0xFB, 0xC0, 0x00, 0x70, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x47, 0x0E, 0x20,
0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x63, 0x0C, 0x60,
0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0xF8,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0xF0,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x60,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58,0x01,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x00,0x00,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x58,0x01,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x00,0x00,0x01,0x04,0x10,0x00,0x40,0xF0,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x00,0x00,0x00,0x82,0x08,0x00,0x41,0xF8,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x00,0x00,0x00,0x41,0x04,0x00,0x61,0xF8,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x00,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
0x7F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
0xFB, 0xC0, 0x00, 0x79, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
0xF3, 0xC0, 0x00, 0x76, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
0xEB, 0xC0, 0x00, 0x7E, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
0x7B, 0x80, 0x00, 0x3D, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x58, 0x01, 0xA0,
0x7B, 0x80, 0x00, 0x3B, 0xC0, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x40, 0x60, 0x20,
0xFB, 0xC0, 0x00, 0x77, 0xE0, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x40, 0xF0, 0x20,
0xFB, 0xC0, 0x00, 0x70, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x41, 0xF8, 0x20,
0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x61, 0xF8, 0x60,
0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
};
#else
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x0E,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x4F,0x0F,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5F,0x0F,0xA0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5E,0x07,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x3F,0xC0,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x79,0xE0,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x76,0xE0,0x00,0x20,0x82,0x00,0x40,0xF0,0x20,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x7E,0xE0,0x00,0x41,0x04,0x00,0x40,0x60,0x20,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x39,0xC0,0x00,0x82,0x08,0x00,0x5E,0x07,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x3E,0xC0,0x01,0x04,0x10,0x00,0x5F,0x0F,0xA0,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x76,0xE0,0x01,0x04,0x10,0x00,0x4F,0x0F,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x79,0xE0,0x00,0x82,0x08,0x00,0x47,0x0E,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x7F,0xE0,0x00,0x41,0x04,0x00,0x63,0x0C,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x0F,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x06,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0xF8,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0xF0,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x60,0x20,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58,0x01,0xA0,
0x7F,0x80,0x00,0x3F,0xC0,0x00,0x3F,0xC0,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0xFB,0xC0,0x00,0x79,0xE0,0x00,0x79,0xE0,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xF3,0xC0,0x00,0x76,0xE0,0x00,0x76,0xE0,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0,
0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x7E,0xE0,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0,
0x7B,0x80,0x00,0x3D,0xC0,0x00,0x39,0xC0,0x00,0x82,0x08,0x00,0x58,0x01,0xA0,
0x7B,0x80,0x00,0x3B,0xC0,0x00,0x3E,0xC0,0x01,0x04,0x10,0x00,0x40,0x60,0x20,
0xFB,0xC0,0x00,0x77,0xE0,0x00,0x76,0xE0,0x01,0x04,0x10,0x00,0x40,0xF0,0x20,
0xFB,0xC0,0x00,0x70,0xE0,0x00,0x79,0xE0,0x00,0x82,0x08,0x00,0x41,0xF8,0x20,
0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x7F,0xE0,0x00,0x41,0x04,0x00,0x61,0xF8,0x60,
0x3F,0x00,0x00,0x1F,0x80,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x70,0x00,0xE0,
0x1E,0x00,0x00,0x0F,0x00,0x00,0x0F,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0,
0x0C,0x00,0x00,0x06,0x00,0x00,0x06,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00
};
#endif // Extruders
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
0x7F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x3F, 0xC0, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
0xFB, 0xC0, 0x00, 0x79, 0xE0, 0x00, 0x79, 0xE0, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
0xF3, 0xC0, 0x00, 0x76, 0xE0, 0x00, 0x76, 0xE0, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
0xEB, 0xC0, 0x00, 0x7E, 0xE0, 0x00, 0x7E, 0xE0, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
0x7B, 0x80, 0x00, 0x3D, 0xC0, 0x00, 0x39, 0xC0, 0x00, 0x82, 0x08, 0x00, 0x5E, 0x07, 0xA0,
0x7B, 0x80, 0x00, 0x3B, 0xC0, 0x00, 0x3E, 0xC0, 0x01, 0x04, 0x10, 0x00, 0x5F, 0x0F, 0xA0,
0xFB, 0xC0, 0x00, 0x77, 0xE0, 0x00, 0x76, 0xE0, 0x01, 0x04, 0x10, 0x00, 0x4F, 0x0F, 0x20,
0xFB, 0xC0, 0x00, 0x70, 0xE0, 0x00, 0x79, 0xE0, 0x00, 0x82, 0x08, 0x00, 0x47, 0x0E, 0x20,
0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x7F, 0xE0, 0x00, 0x41, 0x04, 0x00, 0x63, 0x0C, 0x60,
0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
};
#define STATUS_SCREENWIDTH 115 //Width in pixels
#define STATUS_SCREENHEIGHT 19 //Height in pixels
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
0x7F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x3F, 0xC0, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
0xFB, 0xC0, 0x00, 0x79, 0xE0, 0x00, 0x79, 0xE0, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
0xF3, 0xC0, 0x00, 0x76, 0xE0, 0x00, 0x76, 0xE0, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
0xEB, 0xC0, 0x00, 0x7E, 0xE0, 0x00, 0x7E, 0xE0, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
0x7B, 0x80, 0x00, 0x3D, 0xC0, 0x00, 0x39, 0xC0, 0x00, 0x82, 0x08, 0x00, 0x58, 0x01, 0xA0,
0x7B, 0x80, 0x00, 0x3B, 0xC0, 0x00, 0x3E, 0xC0, 0x01, 0x04, 0x10, 0x00, 0x40, 0x60, 0x20,
0xFB, 0xC0, 0x00, 0x77, 0xE0, 0x00, 0x76, 0xE0, 0x01, 0x04, 0x10, 0x00, 0x40, 0xF0, 0x20,
0xFB, 0xC0, 0x00, 0x70, 0xE0, 0x00, 0x79, 0xE0, 0x00, 0x82, 0x08, 0x00, 0x41, 0xF8, 0x20,
0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x7F, 0xE0, 0x00, 0x41, 0x04, 0x00, 0x61, 0xF8, 0x60,
0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
};
#endif // Extruders

View File

@ -11,147 +11,148 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t u8g_font_6x9[2300] U8G_SECTION(".progmem.u8g_font_6x9") = {
0,6,9,0,254,6,1,137,2,254,32,255,254,7,254,6,
254,0,0,0,6,0,7,1,6,6,6,2,0,128,128,128,
128,0,128,3,3,3,6,1,3,160,160,160,5,7,7,6,
0,255,80,80,248,80,248,80,80,5,9,9,6,0,254,32,
112,168,160,112,40,168,112,32,6,8,8,6,0,255,64,168,
72,16,32,72,84,8,5,7,7,6,0,255,96,144,144,96,
152,144,104,1,3,3,6,2,3,128,128,128,2,7,7,6,
2,255,64,128,128,128,128,128,64,2,7,7,6,2,255,128,
64,64,64,64,64,128,5,5,5,6,0,0,136,80,248,80,
136,5,5,5,6,0,0,32,32,248,32,32,2,4,4,6,
2,254,192,64,64,128,5,1,1,6,0,2,248,2,2,2,
6,2,0,192,192,4,6,6,6,1,0,16,16,32,64,128,
128,4,6,6,6,1,0,96,144,144,144,144,96,3,6,6,
6,1,0,64,192,64,64,64,224,4,6,6,6,1,0,96,
144,16,32,64,240,4,6,6,6,1,0,240,32,96,16,16,
224,5,6,6,6,0,0,16,48,80,144,248,16,4,6,6,
6,1,0,240,128,224,16,16,224,4,6,6,6,1,0,96,
128,224,144,144,96,4,6,6,6,1,0,240,16,16,32,64,
64,4,6,6,6,1,0,96,144,96,144,144,96,4,6,6,
6,1,0,96,144,144,112,16,96,2,5,5,6,2,0,192,
192,0,192,192,2,7,7,6,2,254,192,192,0,192,64,64,
128,5,5,5,6,0,0,24,96,128,96,24,5,3,3,6,
0,1,248,0,248,5,5,5,6,0,0,192,48,8,48,192,
4,7,7,6,1,0,96,144,16,96,64,0,64,5,6,6,
6,0,0,112,144,168,176,128,112,5,6,6,6,0,0,32,
80,136,248,136,136,5,6,6,6,0,0,240,136,240,136,136,
240,4,6,6,6,1,0,96,144,128,128,144,96,4,6,6,
6,1,0,224,144,144,144,144,224,4,6,6,6,1,0,240,
128,224,128,128,240,4,6,6,6,1,0,240,128,224,128,128,
128,4,6,6,6,1,0,96,144,128,176,144,96,4,6,6,
6,1,0,144,144,240,144,144,144,3,6,6,6,1,0,224,
64,64,64,64,224,5,6,6,6,0,0,56,16,16,16,144,
96,4,6,6,6,1,0,144,160,192,160,144,144,4,6,6,
6,1,0,128,128,128,128,128,240,5,6,6,6,0,0,136,
216,168,168,136,136,4,6,6,6,1,0,144,208,176,144,144,
144,5,6,6,6,0,0,112,136,136,136,136,112,4,6,6,
6,1,0,224,144,144,224,128,128,4,7,7,6,1,255,96,
144,144,208,176,96,16,4,6,6,6,1,0,224,144,144,224,
144,144,4,6,6,6,1,0,96,144,64,32,144,96,5,6,
6,6,0,0,248,32,32,32,32,32,4,6,6,6,1,0,
144,144,144,144,144,96,4,6,6,6,1,0,144,144,144,240,
96,96,5,6,6,6,0,0,136,136,168,168,216,136,5,6,
6,6,0,0,136,80,32,32,80,136,5,6,6,6,0,0,
136,136,80,32,32,32,4,6,6,6,1,0,240,16,32,64,
128,240,3,6,6,6,1,0,224,128,128,128,128,224,4,6,
6,6,1,0,128,128,64,32,16,16,3,6,6,6,1,0,
224,32,32,32,32,224,5,3,3,6,0,3,32,80,136,5,
1,1,6,0,254,248,2,2,2,6,2,4,128,64,4,4,
4,6,1,0,112,144,144,112,4,6,6,6,1,0,128,128,
224,144,144,224,4,4,4,6,1,0,112,128,128,112,4,6,
6,6,1,0,16,16,112,144,144,112,4,4,4,6,1,0,
96,176,192,112,4,6,6,6,1,0,32,80,64,224,64,64,
4,6,6,6,1,254,96,144,144,112,16,96,4,6,6,6,
1,0,128,128,224,144,144,144,3,6,6,6,1,0,64,0,
192,64,64,224,3,8,8,6,1,254,32,0,96,32,32,32,
160,64,4,6,6,6,1,0,128,128,160,192,160,144,3,6,
6,6,1,0,192,64,64,64,64,224,5,4,4,6,0,0,
208,168,168,136,4,4,4,6,1,0,224,144,144,144,4,4,
4,6,1,0,96,144,144,96,4,6,6,6,1,254,224,144,
144,224,128,128,4,6,6,6,1,254,112,144,144,112,16,16,
4,4,4,6,1,0,160,208,128,128,4,4,4,6,1,0,
112,192,48,224,4,6,6,6,1,0,64,64,224,64,80,32,
4,4,4,6,1,0,144,144,144,112,4,4,4,6,1,0,
144,144,96,96,5,4,4,6,0,0,136,168,168,80,4,4,
4,6,1,0,144,96,96,144,4,6,6,6,1,254,144,144,
144,112,144,96,4,4,4,6,1,0,240,32,64,240,3,7,
7,6,1,0,32,64,64,128,64,64,32,1,7,7,6,2,
255,128,128,128,128,128,128,128,3,7,7,6,1,0,128,64,
64,32,64,64,128,4,2,2,6,1,3,80,160,255,255,255,
255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,
255,255,255,255,255,255,255,255,255,255,255,255,255,255,0,0,
0,6,0,7,1,6,6,6,2,0,128,0,128,128,128,128,
4,6,6,6,1,255,32,112,160,160,112,32,5,7,7,6,
0,255,48,72,64,240,64,64,248,5,5,5,6,0,0,168,
80,136,80,168,5,6,6,6,0,0,136,80,248,32,248,32,
1,7,7,6,2,255,128,128,128,0,128,128,128,4,7,7,
6,1,255,112,128,96,144,96,16,224,3,1,1,6,1,5,
160,6,7,7,6,0,0,120,132,148,164,148,132,120,3,5,
5,6,1,1,96,160,96,0,224,5,5,5,6,0,0,40,
80,160,80,40,4,3,3,6,1,0,240,16,16,4,1,1,
6,1,2,240,6,7,7,6,0,0,120,132,180,164,164,132,
120,4,1,1,6,1,5,240,4,3,3,6,1,2,96,144,
96,5,7,7,6,0,255,32,32,248,32,32,0,248,3,5,
5,6,1,1,64,160,32,64,224,3,5,5,6,1,1,192,
32,64,32,192,2,2,2,6,2,4,64,128,4,5,5,6,
1,255,144,144,176,208,128,5,6,6,6,0,0,120,232,232,
104,40,40,1,1,1,6,2,2,128,2,2,2,6,2,254,
64,128,3,5,5,6,1,1,64,192,64,64,224,3,5,5,
6,1,1,64,160,64,0,224,5,5,5,6,0,0,160,80,
40,80,160,5,8,8,6,0,255,64,192,64,80,112,48,120,
16,5,8,8,6,0,255,64,192,64,80,104,8,16,56,5,
8,8,6,0,255,192,32,64,48,240,48,120,16,4,7,7,
6,1,0,32,0,32,96,128,144,96,5,7,7,6,0,0,
64,32,32,80,112,136,136,5,7,7,6,0,0,16,32,32,
80,112,136,136,5,7,7,6,0,0,32,80,32,80,112,136,
136,5,7,7,6,0,0,40,80,32,80,112,136,136,5,7,
7,6,0,0,80,0,32,80,112,136,136,5,7,7,6,0,
0,32,80,32,80,112,136,136,5,6,6,6,0,0,120,160,
240,160,160,184,4,8,8,6,1,254,96,144,128,128,144,96,
32,64,4,7,7,6,1,0,64,32,240,128,224,128,240,4,
7,7,6,1,0,32,64,240,128,224,128,240,4,7,7,6,
1,0,32,80,240,128,224,128,240,4,7,7,6,1,0,80,
0,240,128,224,128,240,3,7,7,6,1,0,128,64,224,64,
64,64,224,3,7,7,6,1,0,32,64,224,64,64,64,224,
3,7,7,6,1,0,64,160,224,64,64,64,224,3,7,7,
6,1,0,160,0,224,64,64,64,224,5,6,6,6,0,0,
112,72,232,72,72,112,4,7,7,6,1,0,80,160,144,208,
176,144,144,4,7,7,6,1,0,64,32,96,144,144,144,96,
4,7,7,6,1,0,32,64,96,144,144,144,96,4,7,7,
6,1,0,32,80,96,144,144,144,96,4,7,7,6,1,0,
80,160,96,144,144,144,96,4,7,7,6,1,0,80,0,96,
144,144,144,96,5,5,5,6,0,0,136,80,32,80,136,4,
8,8,6,1,255,16,112,176,176,208,208,224,128,4,7,7,
6,1,0,64,32,144,144,144,144,96,4,7,7,6,1,0,
32,64,144,144,144,144,96,4,7,7,6,1,0,32,80,144,
144,144,144,96,4,7,7,6,1,0,80,0,144,144,144,144,
96,5,7,7,6,0,0,16,32,136,80,32,32,32,4,6,
6,6,1,0,128,224,144,144,224,128,4,6,6,6,1,0,
96,144,160,160,144,160,4,7,7,6,1,0,64,32,0,112,
144,144,112,4,7,7,6,1,0,32,64,0,112,144,144,112,
4,7,7,6,1,0,32,80,0,112,144,144,112,4,7,7,
6,1,0,80,160,0,112,144,144,112,4,6,6,6,1,0,
80,0,112,144,144,112,4,7,7,6,1,0,32,80,32,112,
144,144,112,5,4,4,6,0,0,112,168,176,120,4,6,6,
6,1,254,112,128,128,112,32,64,4,7,7,6,1,0,64,
32,0,96,176,192,112,4,7,7,6,1,0,32,64,0,96,
176,192,112,4,7,7,6,1,0,32,80,0,96,176,192,112,
4,6,6,6,1,0,80,0,96,176,192,112,3,7,7,6,
1,0,128,64,0,192,64,64,224,3,7,7,6,1,0,32,
64,0,192,64,64,224,3,7,7,6,1,0,64,160,0,192,
64,64,224,3,6,6,6,1,0,160,0,192,64,64,224,4,
7,7,6,1,0,48,96,16,112,144,144,96,4,7,7,6,
1,0,80,160,0,224,144,144,144,4,7,7,6,1,0,64,
32,0,96,144,144,96,4,7,7,6,1,0,32,64,0,96,
144,144,96,4,7,7,6,1,0,32,80,0,96,144,144,96,
4,7,7,6,1,0,80,160,0,96,144,144,96,4,6,6,
6,1,0,80,0,96,144,144,96,5,5,5,6,0,0,32,
0,248,0,32,4,4,4,6,1,0,112,176,208,224,4,7,
7,6,1,0,64,32,0,144,144,144,112,4,7,7,6,1,
0,32,64,0,144,144,144,112,4,7,7,6,1,0,32,80,
0,144,144,144,112,4,6,6,6,1,0,80,0,144,144,144,
112,4,9,9,6,1,254,32,64,0,144,144,144,112,144,96,
4,8,8,6,1,254,128,128,224,144,144,224,128,128,4,8,
8,6,1,254,80,0,144,144,144,112,144,96};
0, 6, 9, 0, 254, 6, 1, 137, 2, 254, 32, 255, 254, 7, 254, 6,
254, 0, 0, 0, 6, 0, 7, 1, 6, 6, 6, 2, 0, 128, 128, 128,
128, 0, 128, 3, 3, 3, 6, 1, 3, 160, 160, 160, 5, 7, 7, 6,
0, 255, 80, 80, 248, 80, 248, 80, 80, 5, 9, 9, 6, 0, 254, 32,
112, 168, 160, 112, 40, 168, 112, 32, 6, 8, 8, 6, 0, 255, 64, 168,
72, 16, 32, 72, 84, 8, 5, 7, 7, 6, 0, 255, 96, 144, 144, 96,
152, 144, 104, 1, 3, 3, 6, 2, 3, 128, 128, 128, 2, 7, 7, 6,
2, 255, 64, 128, 128, 128, 128, 128, 64, 2, 7, 7, 6, 2, 255, 128,
64, 64, 64, 64, 64, 128, 5, 5, 5, 6, 0, 0, 136, 80, 248, 80,
136, 5, 5, 5, 6, 0, 0, 32, 32, 248, 32, 32, 2, 4, 4, 6,
2, 254, 192, 64, 64, 128, 5, 1, 1, 6, 0, 2, 248, 2, 2, 2,
6, 2, 0, 192, 192, 4, 6, 6, 6, 1, 0, 16, 16, 32, 64, 128,
128, 4, 6, 6, 6, 1, 0, 96, 144, 144, 144, 144, 96, 3, 6, 6,
6, 1, 0, 64, 192, 64, 64, 64, 224, 4, 6, 6, 6, 1, 0, 96,
144, 16, 32, 64, 240, 4, 6, 6, 6, 1, 0, 240, 32, 96, 16, 16,
224, 5, 6, 6, 6, 0, 0, 16, 48, 80, 144, 248, 16, 4, 6, 6,
6, 1, 0, 240, 128, 224, 16, 16, 224, 4, 6, 6, 6, 1, 0, 96,
128, 224, 144, 144, 96, 4, 6, 6, 6, 1, 0, 240, 16, 16, 32, 64,
64, 4, 6, 6, 6, 1, 0, 96, 144, 96, 144, 144, 96, 4, 6, 6,
6, 1, 0, 96, 144, 144, 112, 16, 96, 2, 5, 5, 6, 2, 0, 192,
192, 0, 192, 192, 2, 7, 7, 6, 2, 254, 192, 192, 0, 192, 64, 64,
128, 5, 5, 5, 6, 0, 0, 24, 96, 128, 96, 24, 5, 3, 3, 6,
0, 1, 248, 0, 248, 5, 5, 5, 6, 0, 0, 192, 48, 8, 48, 192,
4, 7, 7, 6, 1, 0, 96, 144, 16, 96, 64, 0, 64, 5, 6, 6,
6, 0, 0, 112, 144, 168, 176, 128, 112, 5, 6, 6, 6, 0, 0, 32,
80, 136, 248, 136, 136, 5, 6, 6, 6, 0, 0, 240, 136, 240, 136, 136,
240, 4, 6, 6, 6, 1, 0, 96, 144, 128, 128, 144, 96, 4, 6, 6,
6, 1, 0, 224, 144, 144, 144, 144, 224, 4, 6, 6, 6, 1, 0, 240,
128, 224, 128, 128, 240, 4, 6, 6, 6, 1, 0, 240, 128, 224, 128, 128,
128, 4, 6, 6, 6, 1, 0, 96, 144, 128, 176, 144, 96, 4, 6, 6,
6, 1, 0, 144, 144, 240, 144, 144, 144, 3, 6, 6, 6, 1, 0, 224,
64, 64, 64, 64, 224, 5, 6, 6, 6, 0, 0, 56, 16, 16, 16, 144,
96, 4, 6, 6, 6, 1, 0, 144, 160, 192, 160, 144, 144, 4, 6, 6,
6, 1, 0, 128, 128, 128, 128, 128, 240, 5, 6, 6, 6, 0, 0, 136,
216, 168, 168, 136, 136, 4, 6, 6, 6, 1, 0, 144, 208, 176, 144, 144,
144, 5, 6, 6, 6, 0, 0, 112, 136, 136, 136, 136, 112, 4, 6, 6,
6, 1, 0, 224, 144, 144, 224, 128, 128, 4, 7, 7, 6, 1, 255, 96,
144, 144, 208, 176, 96, 16, 4, 6, 6, 6, 1, 0, 224, 144, 144, 224,
144, 144, 4, 6, 6, 6, 1, 0, 96, 144, 64, 32, 144, 96, 5, 6,
6, 6, 0, 0, 248, 32, 32, 32, 32, 32, 4, 6, 6, 6, 1, 0,
144, 144, 144, 144, 144, 96, 4, 6, 6, 6, 1, 0, 144, 144, 144, 240,
96, 96, 5, 6, 6, 6, 0, 0, 136, 136, 168, 168, 216, 136, 5, 6,
6, 6, 0, 0, 136, 80, 32, 32, 80, 136, 5, 6, 6, 6, 0, 0,
136, 136, 80, 32, 32, 32, 4, 6, 6, 6, 1, 0, 240, 16, 32, 64,
128, 240, 3, 6, 6, 6, 1, 0, 224, 128, 128, 128, 128, 224, 4, 6,
6, 6, 1, 0, 128, 128, 64, 32, 16, 16, 3, 6, 6, 6, 1, 0,
224, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 3, 32, 80, 136, 5,
1, 1, 6, 0, 254, 248, 2, 2, 2, 6, 2, 4, 128, 64, 4, 4,
4, 6, 1, 0, 112, 144, 144, 112, 4, 6, 6, 6, 1, 0, 128, 128,
224, 144, 144, 224, 4, 4, 4, 6, 1, 0, 112, 128, 128, 112, 4, 6,
6, 6, 1, 0, 16, 16, 112, 144, 144, 112, 4, 4, 4, 6, 1, 0,
96, 176, 192, 112, 4, 6, 6, 6, 1, 0, 32, 80, 64, 224, 64, 64,
4, 6, 6, 6, 1, 254, 96, 144, 144, 112, 16, 96, 4, 6, 6, 6,
1, 0, 128, 128, 224, 144, 144, 144, 3, 6, 6, 6, 1, 0, 64, 0,
192, 64, 64, 224, 3, 8, 8, 6, 1, 254, 32, 0, 96, 32, 32, 32,
160, 64, 4, 6, 6, 6, 1, 0, 128, 128, 160, 192, 160, 144, 3, 6,
6, 6, 1, 0, 192, 64, 64, 64, 64, 224, 5, 4, 4, 6, 0, 0,
208, 168, 168, 136, 4, 4, 4, 6, 1, 0, 224, 144, 144, 144, 4, 4,
4, 6, 1, 0, 96, 144, 144, 96, 4, 6, 6, 6, 1, 254, 224, 144,
144, 224, 128, 128, 4, 6, 6, 6, 1, 254, 112, 144, 144, 112, 16, 16,
4, 4, 4, 6, 1, 0, 160, 208, 128, 128, 4, 4, 4, 6, 1, 0,
112, 192, 48, 224, 4, 6, 6, 6, 1, 0, 64, 64, 224, 64, 80, 32,
4, 4, 4, 6, 1, 0, 144, 144, 144, 112, 4, 4, 4, 6, 1, 0,
144, 144, 96, 96, 5, 4, 4, 6, 0, 0, 136, 168, 168, 80, 4, 4,
4, 6, 1, 0, 144, 96, 96, 144, 4, 6, 6, 6, 1, 254, 144, 144,
144, 112, 144, 96, 4, 4, 4, 6, 1, 0, 240, 32, 64, 240, 3, 7,
7, 6, 1, 0, 32, 64, 64, 128, 64, 64, 32, 1, 7, 7, 6, 2,
255, 128, 128, 128, 128, 128, 128, 128, 3, 7, 7, 6, 1, 0, 128, 64,
64, 32, 64, 64, 128, 4, 2, 2, 6, 1, 3, 80, 160, 255, 255, 255,
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255,
255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 255, 0, 0,
0, 6, 0, 7, 1, 6, 6, 6, 2, 0, 128, 0, 128, 128, 128, 128,
4, 6, 6, 6, 1, 255, 32, 112, 160, 160, 112, 32, 5, 7, 7, 6,
0, 255, 48, 72, 64, 240, 64, 64, 248, 5, 5, 5, 6, 0, 0, 168,
80, 136, 80, 168, 5, 6, 6, 6, 0, 0, 136, 80, 248, 32, 248, 32,
1, 7, 7, 6, 2, 255, 128, 128, 128, 0, 128, 128, 128, 4, 7, 7,
6, 1, 255, 112, 128, 96, 144, 96, 16, 224, 3, 1, 1, 6, 1, 5,
160, 6, 7, 7, 6, 0, 0, 120, 132, 148, 164, 148, 132, 120, 3, 5,
5, 6, 1, 1, 96, 160, 96, 0, 224, 5, 5, 5, 6, 0, 0, 40,
80, 160, 80, 40, 4, 3, 3, 6, 1, 0, 240, 16, 16, 4, 1, 1,
6, 1, 2, 240, 6, 7, 7, 6, 0, 0, 120, 132, 180, 164, 164, 132,
120, 4, 1, 1, 6, 1, 5, 240, 4, 3, 3, 6, 1, 2, 96, 144,
96, 5, 7, 7, 6, 0, 255, 32, 32, 248, 32, 32, 0, 248, 3, 5,
5, 6, 1, 1, 64, 160, 32, 64, 224, 3, 5, 5, 6, 1, 1, 192,
32, 64, 32, 192, 2, 2, 2, 6, 2, 4, 64, 128, 4, 5, 5, 6,
1, 255, 144, 144, 176, 208, 128, 5, 6, 6, 6, 0, 0, 120, 232, 232,
104, 40, 40, 1, 1, 1, 6, 2, 2, 128, 2, 2, 2, 6, 2, 254,
64, 128, 3, 5, 5, 6, 1, 1, 64, 192, 64, 64, 224, 3, 5, 5,
6, 1, 1, 64, 160, 64, 0, 224, 5, 5, 5, 6, 0, 0, 160, 80,
40, 80, 160, 5, 8, 8, 6, 0, 255, 64, 192, 64, 80, 112, 48, 120,
16, 5, 8, 8, 6, 0, 255, 64, 192, 64, 80, 104, 8, 16, 56, 5,
8, 8, 6, 0, 255, 192, 32, 64, 48, 240, 48, 120, 16, 4, 7, 7,
6, 1, 0, 32, 0, 32, 96, 128, 144, 96, 5, 7, 7, 6, 0, 0,
64, 32, 32, 80, 112, 136, 136, 5, 7, 7, 6, 0, 0, 16, 32, 32,
80, 112, 136, 136, 5, 7, 7, 6, 0, 0, 32, 80, 32, 80, 112, 136,
136, 5, 7, 7, 6, 0, 0, 40, 80, 32, 80, 112, 136, 136, 5, 7,
7, 6, 0, 0, 80, 0, 32, 80, 112, 136, 136, 5, 7, 7, 6, 0,
0, 32, 80, 32, 80, 112, 136, 136, 5, 6, 6, 6, 0, 0, 120, 160,
240, 160, 160, 184, 4, 8, 8, 6, 1, 254, 96, 144, 128, 128, 144, 96,
32, 64, 4, 7, 7, 6, 1, 0, 64, 32, 240, 128, 224, 128, 240, 4,
7, 7, 6, 1, 0, 32, 64, 240, 128, 224, 128, 240, 4, 7, 7, 6,
1, 0, 32, 80, 240, 128, 224, 128, 240, 4, 7, 7, 6, 1, 0, 80,
0, 240, 128, 224, 128, 240, 3, 7, 7, 6, 1, 0, 128, 64, 224, 64,
64, 64, 224, 3, 7, 7, 6, 1, 0, 32, 64, 224, 64, 64, 64, 224,
3, 7, 7, 6, 1, 0, 64, 160, 224, 64, 64, 64, 224, 3, 7, 7,
6, 1, 0, 160, 0, 224, 64, 64, 64, 224, 5, 6, 6, 6, 0, 0,
112, 72, 232, 72, 72, 112, 4, 7, 7, 6, 1, 0, 80, 160, 144, 208,
176, 144, 144, 4, 7, 7, 6, 1, 0, 64, 32, 96, 144, 144, 144, 96,
4, 7, 7, 6, 1, 0, 32, 64, 96, 144, 144, 144, 96, 4, 7, 7,
6, 1, 0, 32, 80, 96, 144, 144, 144, 96, 4, 7, 7, 6, 1, 0,
80, 160, 96, 144, 144, 144, 96, 4, 7, 7, 6, 1, 0, 80, 0, 96,
144, 144, 144, 96, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136, 4,
8, 8, 6, 1, 255, 16, 112, 176, 176, 208, 208, 224, 128, 4, 7, 7,
6, 1, 0, 64, 32, 144, 144, 144, 144, 96, 4, 7, 7, 6, 1, 0,
32, 64, 144, 144, 144, 144, 96, 4, 7, 7, 6, 1, 0, 32, 80, 144,
144, 144, 144, 96, 4, 7, 7, 6, 1, 0, 80, 0, 144, 144, 144, 144,
96, 5, 7, 7, 6, 0, 0, 16, 32, 136, 80, 32, 32, 32, 4, 6,
6, 6, 1, 0, 128, 224, 144, 144, 224, 128, 4, 6, 6, 6, 1, 0,
96, 144, 160, 160, 144, 160, 4, 7, 7, 6, 1, 0, 64, 32, 0, 112,
144, 144, 112, 4, 7, 7, 6, 1, 0, 32, 64, 0, 112, 144, 144, 112,
4, 7, 7, 6, 1, 0, 32, 80, 0, 112, 144, 144, 112, 4, 7, 7,
6, 1, 0, 80, 160, 0, 112, 144, 144, 112, 4, 6, 6, 6, 1, 0,
80, 0, 112, 144, 144, 112, 4, 7, 7, 6, 1, 0, 32, 80, 32, 112,
144, 144, 112, 5, 4, 4, 6, 0, 0, 112, 168, 176, 120, 4, 6, 6,
6, 1, 254, 112, 128, 128, 112, 32, 64, 4, 7, 7, 6, 1, 0, 64,
32, 0, 96, 176, 192, 112, 4, 7, 7, 6, 1, 0, 32, 64, 0, 96,
176, 192, 112, 4, 7, 7, 6, 1, 0, 32, 80, 0, 96, 176, 192, 112,
4, 6, 6, 6, 1, 0, 80, 0, 96, 176, 192, 112, 3, 7, 7, 6,
1, 0, 128, 64, 0, 192, 64, 64, 224, 3, 7, 7, 6, 1, 0, 32,
64, 0, 192, 64, 64, 224, 3, 7, 7, 6, 1, 0, 64, 160, 0, 192,
64, 64, 224, 3, 6, 6, 6, 1, 0, 160, 0, 192, 64, 64, 224, 4,
7, 7, 6, 1, 0, 48, 96, 16, 112, 144, 144, 96, 4, 7, 7, 6,
1, 0, 80, 160, 0, 224, 144, 144, 144, 4, 7, 7, 6, 1, 0, 64,
32, 0, 96, 144, 144, 96, 4, 7, 7, 6, 1, 0, 32, 64, 0, 96,
144, 144, 96, 4, 7, 7, 6, 1, 0, 32, 80, 0, 96, 144, 144, 96,
4, 7, 7, 6, 1, 0, 80, 160, 0, 96, 144, 144, 96, 4, 6, 6,
6, 1, 0, 80, 0, 96, 144, 144, 96, 5, 5, 5, 6, 0, 0, 32,
0, 248, 0, 32, 4, 4, 4, 6, 1, 0, 112, 176, 208, 224, 4, 7,
7, 6, 1, 0, 64, 32, 0, 144, 144, 144, 112, 4, 7, 7, 6, 1,
0, 32, 64, 0, 144, 144, 144, 112, 4, 7, 7, 6, 1, 0, 32, 80,
0, 144, 144, 144, 112, 4, 6, 6, 6, 1, 0, 80, 0, 144, 144, 144,
112, 4, 9, 9, 6, 1, 254, 32, 64, 0, 144, 144, 144, 112, 144, 96,
4, 8, 8, 6, 1, 254, 128, 128, 224, 144, 144, 224, 128, 128, 4, 8,
8, 6, 1, 254, 80, 0, 144, 144, 144, 112, 144, 96
};

View File

@ -11,161 +11,162 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t HD44780_C_5x7[2522] U8G_SECTION(".progmem.HD44780_C_5x7") = {
0,6,9,0,254,7,1,145,3,34,32,255,255,8,255,7,
255,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128,
128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
0,0,112,136,152,168,200,136,112,3,7,7,6,1,0,64,
192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
48,64,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
112,5,7,7,6,0,0,112,136,136,120,8,16,96,2,5,
5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1,
0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
8,16,32,0,32,5,6,6,6,0,0,112,136,8,104,168,
112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,7,
7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,0,
0,112,136,128,128,128,136,112,5,7,7,6,0,0,224,144,
136,136,136,144,224,5,7,7,6,0,0,248,128,128,240,128,
128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,5,
7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,6,
0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,128,
128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,16,
16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,136,
5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,7,
6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,0,
136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,136,
136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,128,
128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,7,
7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,0,
0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,32,
32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,136,
136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,5,
7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,6,
0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,136,
136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,32,
64,128,248,3,7,7,6,1,0,224,128,128,128,128,128,224,
5,7,7,6,0,0,32,112,160,160,168,112,32,3,7,7,
6,1,0,224,32,32,32,32,32,224,5,3,3,6,0,4,
32,80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,
128,64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,
6,0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,
112,128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,
136,120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,
6,0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,
112,136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,
136,136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,
3,8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,
7,6,0,0,128,128,144,160,192,160,144,3,7,7,6,1,
0,192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,
168,168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,
5,6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,
136,136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,
8,5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,
0,0,112,128,112,8,240,5,7,7,6,0,0,64,64,224,
64,64,72,48,5,5,5,6,0,0,136,136,136,152,104,5,
5,5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,
136,136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,
5,6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,
0,0,248,16,32,64,248,5,5,5,6,0,2,184,168,168,
168,184,5,5,5,6,0,2,184,136,184,160,184,5,5,5,
6,0,2,184,160,184,136,184,5,6,6,6,0,1,8,40,
72,248,64,32,5,5,5,6,0,0,56,112,224,136,240,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,5,
7,7,6,0,0,248,136,128,240,136,136,240,5,7,7,6,
0,0,248,136,128,128,128,128,128,5,7,7,6,0,0,80,
0,248,128,240,128,248,5,7,7,6,0,0,168,168,168,112,
168,168,168,5,7,7,6,0,0,240,8,8,112,8,8,240,
5,7,7,6,0,0,136,136,152,168,200,136,136,5,8,8,
6,0,0,80,32,136,152,168,168,200,136,5,7,7,6,0,
0,120,40,40,40,40,168,72,5,7,7,6,0,0,248,136,
136,136,136,136,136,5,7,7,6,0,0,136,136,136,80,32,
64,128,5,7,7,6,0,0,32,112,168,168,168,112,32,5,
7,7,6,0,0,136,136,136,120,8,8,8,5,7,7,6,
0,0,168,168,168,168,168,168,248,5,7,7,6,0,0,192,
64,64,112,72,72,112,5,7,7,6,0,0,136,136,136,200,
168,168,200,5,7,7,6,0,0,112,136,8,56,8,136,112,
5,7,7,6,0,0,144,168,168,232,168,168,144,5,7,7,
6,0,0,120,136,136,120,40,72,136,5,7,7,6,0,0,
24,96,128,240,136,136,112,4,5,5,6,0,0,224,144,224,
144,224,5,5,5,6,0,0,248,136,128,128,128,5,7,7,
6,0,0,80,0,112,136,248,128,112,5,5,5,6,0,0,
168,168,112,168,168,5,5,5,6,0,0,240,8,48,8,240,
5,5,5,6,0,0,136,152,168,200,136,5,7,7,6,0,
0,80,32,136,152,168,200,136,4,5,5,6,0,0,144,160,
192,160,144,5,5,5,6,0,0,248,40,40,168,72,5,5,
5,6,0,0,136,216,168,136,136,5,5,5,6,0,0,136,
136,248,136,136,5,5,5,6,0,0,248,136,136,136,136,5,
5,5,6,0,0,248,32,32,32,32,5,5,5,6,0,0,
136,136,120,8,8,5,5,5,6,0,0,168,168,168,168,248,
5,5,5,6,0,0,192,64,112,72,112,5,5,5,6,0,
0,136,136,200,168,200,4,5,5,6,0,0,128,128,224,144,
224,5,5,5,6,0,0,112,136,56,136,112,5,5,5,6,
0,0,144,168,232,168,144,5,5,5,6,0,0,120,136,120,
40,72,5,5,5,6,0,1,32,72,144,72,32,5,5,5,
6,0,1,32,144,72,144,32,5,3,3,6,0,0,72,144,
216,5,3,3,6,0,4,216,72,144,5,7,7,6,0,0,
144,208,176,144,56,40,56,5,7,7,6,0,0,32,0,32,
64,128,136,112,5,7,7,6,0,0,24,32,32,112,32,32,
192,5,7,7,6,0,0,32,80,64,240,64,64,120,1,2,
2,6,2,0,128,128,1,4,4,6,2,0,128,128,128,128,
3,5,5,6,1,0,160,160,160,0,224,3,5,5,6,1,
0,160,160,160,0,160,5,7,7,6,0,0,160,0,232,16,
32,64,128,5,5,5,6,0,1,216,112,32,112,216,5,7,
7,6,0,0,160,64,168,16,32,64,128,3,6,6,6,1,
1,224,64,64,64,64,224,5,6,6,6,0,1,248,80,80,
80,80,248,5,7,7,6,0,0,32,112,168,32,32,32,32,
5,7,7,6,0,0,32,32,32,32,168,112,32,5,7,7,
6,0,0,128,144,176,248,176,144,128,5,7,7,6,0,0,
8,72,104,248,104,72,8,5,7,7,6,0,0,128,136,168,
248,168,136,128,5,7,7,6,0,0,128,224,136,16,32,64,
128,2,2,2,6,2,2,192,192,5,8,8,6,0,255,120,
40,40,40,72,136,248,136,5,8,8,6,0,255,136,136,136,
136,136,136,248,8,5,8,8,6,0,255,168,168,168,168,168,
168,248,8,5,6,6,6,0,255,120,40,72,136,248,136,5,
7,7,6,0,255,32,32,112,168,168,112,32,5,6,6,6,
0,255,136,136,136,136,248,8,5,6,6,6,0,255,168,168,
168,168,248,8,2,2,2,6,2,6,64,128,3,1,1,6,
1,7,160,5,2,2,6,0,6,72,176,5,8,8,6,0,
0,16,32,0,112,136,248,128,112,5,6,6,6,0,255,112,
128,136,112,32,96,3,7,7,6,1,0,160,0,160,160,160,
32,192,5,6,6,6,0,1,32,112,112,112,248,32,5,5,
5,6,0,1,80,0,136,0,80,5,5,5,6,0,1,112,
136,136,136,112,5,7,7,6,0,0,136,144,168,88,184,8,
8,5,7,7,6,0,0,136,144,184,72,184,8,56,5,7,
7,6,0,0,136,144,184,72,152,32,56,5,8,8,6,0,
0,192,64,192,72,216,56,8,8,5,7,7,6,0,0,136,
248,136,248,136,248,136,4,5,5,6,0,2,192,0,48,0,
96,5,8,8,6,0,0,64,160,224,168,8,40,120,32,5,
8,8,6,0,0,64,112,64,120,64,112,64,224,5,8,8,
6,0,0,32,112,32,248,32,112,32,112,5,7,7,6,0,
0,104,0,232,0,104,16,56,5,8,8,6,0,0,16,112,
16,240,16,112,16,56,5,7,7,6,0,1,32,112,32,248,
32,112,32,5,8,8,6,0,0,16,144,80,48,80,144,16,
56,5,8,8,6,0,0,48,72,32,80,80,32,144,96,5,
7,7,6,0,0,120,168,168,120,40,40,40,5,8,8,6,
0,0,248,248,248,248,248,248,248,248};
0, 6, 9, 0, 254, 7, 1, 145, 3, 34, 32, 255, 255, 8, 255, 7,
255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
64, 152, 24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104,
2, 3, 3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32,
64, 128, 128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32,
32, 64, 128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5,
5, 6, 0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192,
64, 128, 5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192,
192, 5, 5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6,
0, 0, 112, 136, 152, 168, 200, 136, 112, 3, 7, 7, 6, 1, 0, 64,
192, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112,
128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240,
5, 7, 7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7,
6, 0, 0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0,
48, 64, 128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16,
32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 16, 96, 2, 5,
5, 6, 2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192,
192, 0, 192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64,
32, 16, 5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 1,
0, 128, 64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136,
8, 16, 32, 0, 32, 5, 6, 6, 6, 0, 0, 112, 136, 8, 104, 168,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5, 7,
7, 6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6, 0,
0, 112, 136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 224, 144,
136, 136, 136, 144, 224, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128,
128, 248, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128, 5,
7, 7, 6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7, 6,
0, 0, 136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0, 128,
128, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16, 16,
16, 144, 96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144, 136,
5, 7, 7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7, 7,
6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0,
136, 136, 200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136, 136,
136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128, 128,
128, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5, 7,
7, 6, 0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6, 0,
0, 120, 128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248, 32,
32, 32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136,
136, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32, 5,
7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7, 6,
0, 0, 136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0, 136,
136, 136, 80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16, 32,
64, 128, 248, 3, 7, 7, 6, 1, 0, 224, 128, 128, 128, 128, 128, 224,
5, 7, 7, 6, 0, 0, 32, 112, 160, 160, 168, 112, 32, 3, 7, 7,
6, 1, 0, 224, 32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4,
32, 80, 136, 5, 1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5,
128, 64, 5, 5, 5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7,
6, 0, 0, 128, 128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0,
112, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136,
136, 120, 5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7,
6, 0, 0, 48, 72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255,
112, 136, 136, 120, 8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200,
136, 136, 136, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128,
3, 8, 8, 6, 1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7,
7, 6, 0, 0, 128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1,
0, 192, 64, 64, 64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168,
168, 168, 168, 5, 5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5,
5, 6, 0, 0, 112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240,
136, 136, 240, 128, 128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8,
8, 5, 5, 5, 6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6,
0, 0, 112, 128, 112, 8, 240, 5, 7, 7, 6, 0, 0, 64, 64, 224,
64, 64, 72, 48, 5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5,
5, 5, 6, 0, 0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0,
136, 136, 168, 168, 80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136,
5, 6, 6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6,
0, 0, 248, 16, 32, 64, 248, 5, 5, 5, 6, 0, 2, 184, 168, 168,
168, 184, 5, 5, 5, 6, 0, 2, 184, 136, 184, 160, 184, 5, 5, 5,
6, 0, 2, 184, 160, 184, 136, 184, 5, 6, 6, 6, 0, 1, 8, 40,
72, 248, 64, 32, 5, 5, 5, 6, 0, 0, 56, 112, 224, 136, 240, 0,
0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 5,
7, 7, 6, 0, 0, 248, 136, 128, 240, 136, 136, 240, 5, 7, 7, 6,
0, 0, 248, 136, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 80,
0, 248, 128, 240, 128, 248, 5, 7, 7, 6, 0, 0, 168, 168, 168, 112,
168, 168, 168, 5, 7, 7, 6, 0, 0, 240, 8, 8, 112, 8, 8, 240,
5, 7, 7, 6, 0, 0, 136, 136, 152, 168, 200, 136, 136, 5, 8, 8,
6, 0, 0, 80, 32, 136, 152, 168, 168, 200, 136, 5, 7, 7, 6, 0,
0, 120, 40, 40, 40, 40, 168, 72, 5, 7, 7, 6, 0, 0, 248, 136,
136, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0, 136, 136, 136, 80, 32,
64, 128, 5, 7, 7, 6, 0, 0, 32, 112, 168, 168, 168, 112, 32, 5,
7, 7, 6, 0, 0, 136, 136, 136, 120, 8, 8, 8, 5, 7, 7, 6,
0, 0, 168, 168, 168, 168, 168, 168, 248, 5, 7, 7, 6, 0, 0, 192,
64, 64, 112, 72, 72, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 200,
168, 168, 200, 5, 7, 7, 6, 0, 0, 112, 136, 8, 56, 8, 136, 112,
5, 7, 7, 6, 0, 0, 144, 168, 168, 232, 168, 168, 144, 5, 7, 7,
6, 0, 0, 120, 136, 136, 120, 40, 72, 136, 5, 7, 7, 6, 0, 0,
24, 96, 128, 240, 136, 136, 112, 4, 5, 5, 6, 0, 0, 224, 144, 224,
144, 224, 5, 5, 5, 6, 0, 0, 248, 136, 128, 128, 128, 5, 7, 7,
6, 0, 0, 80, 0, 112, 136, 248, 128, 112, 5, 5, 5, 6, 0, 0,
168, 168, 112, 168, 168, 5, 5, 5, 6, 0, 0, 240, 8, 48, 8, 240,
5, 5, 5, 6, 0, 0, 136, 152, 168, 200, 136, 5, 7, 7, 6, 0,
0, 80, 32, 136, 152, 168, 200, 136, 4, 5, 5, 6, 0, 0, 144, 160,
192, 160, 144, 5, 5, 5, 6, 0, 0, 248, 40, 40, 168, 72, 5, 5,
5, 6, 0, 0, 136, 216, 168, 136, 136, 5, 5, 5, 6, 0, 0, 136,
136, 248, 136, 136, 5, 5, 5, 6, 0, 0, 248, 136, 136, 136, 136, 5,
5, 5, 6, 0, 0, 248, 32, 32, 32, 32, 5, 5, 5, 6, 0, 0,
136, 136, 120, 8, 8, 5, 5, 5, 6, 0, 0, 168, 168, 168, 168, 248,
5, 5, 5, 6, 0, 0, 192, 64, 112, 72, 112, 5, 5, 5, 6, 0,
0, 136, 136, 200, 168, 200, 4, 5, 5, 6, 0, 0, 128, 128, 224, 144,
224, 5, 5, 5, 6, 0, 0, 112, 136, 56, 136, 112, 5, 5, 5, 6,
0, 0, 144, 168, 232, 168, 144, 5, 5, 5, 6, 0, 0, 120, 136, 120,
40, 72, 5, 5, 5, 6, 0, 1, 32, 72, 144, 72, 32, 5, 5, 5,
6, 0, 1, 32, 144, 72, 144, 32, 5, 3, 3, 6, 0, 0, 72, 144,
216, 5, 3, 3, 6, 0, 4, 216, 72, 144, 5, 7, 7, 6, 0, 0,
144, 208, 176, 144, 56, 40, 56, 5, 7, 7, 6, 0, 0, 32, 0, 32,
64, 128, 136, 112, 5, 7, 7, 6, 0, 0, 24, 32, 32, 112, 32, 32,
192, 5, 7, 7, 6, 0, 0, 32, 80, 64, 240, 64, 64, 120, 1, 2,
2, 6, 2, 0, 128, 128, 1, 4, 4, 6, 2, 0, 128, 128, 128, 128,
3, 5, 5, 6, 1, 0, 160, 160, 160, 0, 224, 3, 5, 5, 6, 1,
0, 160, 160, 160, 0, 160, 5, 7, 7, 6, 0, 0, 160, 0, 232, 16,
32, 64, 128, 5, 5, 5, 6, 0, 1, 216, 112, 32, 112, 216, 5, 7,
7, 6, 0, 0, 160, 64, 168, 16, 32, 64, 128, 3, 6, 6, 6, 1,
1, 224, 64, 64, 64, 64, 224, 5, 6, 6, 6, 0, 1, 248, 80, 80,
80, 80, 248, 5, 7, 7, 6, 0, 0, 32, 112, 168, 32, 32, 32, 32,
5, 7, 7, 6, 0, 0, 32, 32, 32, 32, 168, 112, 32, 5, 7, 7,
6, 0, 0, 128, 144, 176, 248, 176, 144, 128, 5, 7, 7, 6, 0, 0,
8, 72, 104, 248, 104, 72, 8, 5, 7, 7, 6, 0, 0, 128, 136, 168,
248, 168, 136, 128, 5, 7, 7, 6, 0, 0, 128, 224, 136, 16, 32, 64,
128, 2, 2, 2, 6, 2, 2, 192, 192, 5, 8, 8, 6, 0, 255, 120,
40, 40, 40, 72, 136, 248, 136, 5, 8, 8, 6, 0, 255, 136, 136, 136,
136, 136, 136, 248, 8, 5, 8, 8, 6, 0, 255, 168, 168, 168, 168, 168,
168, 248, 8, 5, 6, 6, 6, 0, 255, 120, 40, 72, 136, 248, 136, 5,
7, 7, 6, 0, 255, 32, 32, 112, 168, 168, 112, 32, 5, 6, 6, 6,
0, 255, 136, 136, 136, 136, 248, 8, 5, 6, 6, 6, 0, 255, 168, 168,
168, 168, 248, 8, 2, 2, 2, 6, 2, 6, 64, 128, 3, 1, 1, 6,
1, 7, 160, 5, 2, 2, 6, 0, 6, 72, 176, 5, 8, 8, 6, 0,
0, 16, 32, 0, 112, 136, 248, 128, 112, 5, 6, 6, 6, 0, 255, 112,
128, 136, 112, 32, 96, 3, 7, 7, 6, 1, 0, 160, 0, 160, 160, 160,
32, 192, 5, 6, 6, 6, 0, 1, 32, 112, 112, 112, 248, 32, 5, 5,
5, 6, 0, 1, 80, 0, 136, 0, 80, 5, 5, 5, 6, 0, 1, 112,
136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 136, 144, 168, 88, 184, 8,
8, 5, 7, 7, 6, 0, 0, 136, 144, 184, 72, 184, 8, 56, 5, 7,
7, 6, 0, 0, 136, 144, 184, 72, 152, 32, 56, 5, 8, 8, 6, 0,
0, 192, 64, 192, 72, 216, 56, 8, 8, 5, 7, 7, 6, 0, 0, 136,
248, 136, 248, 136, 248, 136, 4, 5, 5, 6, 0, 2, 192, 0, 48, 0,
96, 5, 8, 8, 6, 0, 0, 64, 160, 224, 168, 8, 40, 120, 32, 5,
8, 8, 6, 0, 0, 64, 112, 64, 120, 64, 112, 64, 224, 5, 8, 8,
6, 0, 0, 32, 112, 32, 248, 32, 112, 32, 112, 5, 7, 7, 6, 0,
0, 104, 0, 232, 0, 104, 16, 56, 5, 8, 8, 6, 0, 0, 16, 112,
16, 240, 16, 112, 16, 56, 5, 7, 7, 6, 0, 1, 32, 112, 32, 248,
32, 112, 32, 5, 8, 8, 6, 0, 0, 16, 144, 80, 48, 80, 144, 16,
56, 5, 8, 8, 6, 0, 0, 48, 72, 32, 80, 80, 32, 144, 96, 5,
7, 7, 6, 0, 0, 120, 168, 168, 120, 40, 40, 40, 5, 8, 8, 6,
0, 0, 248, 248, 248, 248, 248, 248, 248, 248
};

View File

@ -11,159 +11,160 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t HD44780_J_5x7[2491] U8G_SECTION(".progmem.HD44780_J_5x7") = {
0,6,9,0,254,7,1,145,3,34,32,255,255,8,254,7,
255,0,0,0,6,0,8,1,7,7,6,2,0,128,128,128,
128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
0,0,112,136,152,168,200,136,112,3,7,7,6,1,0,64,
192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
48,64,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
112,5,7,7,6,0,0,112,136,136,120,8,16,96,2,5,
5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1,
0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
8,16,32,0,32,5,6,6,6,0,0,112,136,8,104,168,
112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,7,
7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,0,
0,112,136,128,128,128,136,112,5,7,7,6,0,0,224,144,
136,136,136,144,224,5,7,7,6,0,0,248,128,128,240,128,
128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,5,
7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,6,
0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,128,
128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,16,
16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,136,
5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,7,
6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,0,
136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,136,
136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,128,
128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,7,
7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,0,
0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,32,
32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,136,
136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,5,
7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,6,
0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,136,
136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,32,
64,128,248,3,7,7,6,1,0,224,128,128,128,128,128,224,
5,7,7,6,0,0,136,80,248,32,248,32,32,3,7,7,
6,1,0,224,32,32,32,32,32,224,5,3,3,6,0,4,
32,80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,
128,64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,
6,0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,
112,128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,
136,120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,
6,0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,
112,136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,
136,136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,
3,8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,
7,6,0,0,128,128,144,160,192,160,144,3,7,7,6,1,
0,192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,
168,168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,
5,6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,
136,136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,
8,5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,
0,0,112,128,112,8,240,5,7,7,6,0,0,64,64,224,
64,64,72,48,5,5,5,6,0,0,136,136,136,152,104,5,
5,5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,
136,136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,
5,6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,
0,0,248,16,32,64,248,3,7,7,6,1,0,32,64,64,
128,64,64,32,1,7,7,6,2,0,128,128,128,128,128,128,
128,3,7,7,6,1,0,128,64,64,32,64,64,128,5,5,
5,6,0,1,32,16,248,16,32,5,5,5,6,0,1,32,
64,248,64,32,0,0,0,6,0,8,0,0,0,6,0,8,
0,0,0,6,0,8,0,0,0,6,0,8,0,0,0,6,
0,8,0,0,0,6,0,8,0,0,0,6,0,8,0,0,
0,6,0,8,0,0,0,6,0,8,0,0,0,6,0,8,
0,0,0,6,0,8,0,0,0,6,0,8,0,0,0,6,
0,8,0,0,0,6,0,8,0,0,0,6,0,8,0,0,
0,6,0,8,0,0,0,6,0,8,0,0,0,6,0,8,
0,0,0,6,0,8,0,0,0,6,0,8,0,0,0,6,
0,8,0,0,0,6,0,8,0,0,0,6,0,8,0,0,
0,6,0,8,0,0,0,6,0,8,0,0,0,6,0,8,
0,0,0,6,0,8,0,0,0,6,0,8,0,0,0,6,
0,8,0,0,0,6,0,8,0,0,0,6,0,8,0,0,
0,6,0,8,0,0,0,6,0,8,3,3,3,6,0,0,
224,160,224,3,4,4,6,2,3,224,128,128,128,3,4,4,
6,0,0,32,32,32,224,3,3,3,6,0,0,128,64,32,
2,2,2,6,1,2,192,192,5,6,6,6,0,0,248,8,
248,8,16,32,5,5,5,6,0,0,248,8,48,32,64,4,
5,5,6,0,0,16,32,96,160,32,5,5,5,6,0,0,
32,248,136,8,48,5,4,4,6,0,0,248,32,32,248,5,
5,5,6,0,0,16,248,48,80,144,5,5,5,6,0,0,
64,248,72,80,64,5,4,4,6,0,0,112,16,16,248,4,
5,5,6,0,0,240,16,240,16,240,5,4,4,6,0,0,
168,168,8,48,5,1,1,6,0,4,248,5,7,7,6,0,
0,248,8,40,48,32,32,64,5,7,7,6,0,0,8,16,
32,96,160,32,32,5,7,7,6,0,0,32,248,136,136,8,
16,32,5,6,6,6,0,0,248,32,32,32,32,248,5,7,
7,6,0,0,16,248,16,48,80,144,16,5,7,7,6,0,
0,64,248,72,72,72,72,144,5,7,7,6,0,0,32,248,
32,248,32,32,32,5,6,6,6,0,0,120,72,136,8,16,
96,5,7,7,6,0,0,64,120,144,16,16,16,32,5,6,
6,6,0,0,248,8,8,8,8,248,5,7,7,6,0,0,
80,248,80,80,16,32,64,5,6,6,6,0,0,192,8,200,
8,16,224,5,6,6,6,0,0,248,8,16,32,80,136,5,
7,7,6,0,0,64,248,72,80,64,64,56,5,6,6,6,
0,0,136,136,72,8,16,96,5,6,6,6,0,0,120,72,
168,24,16,96,5,7,7,6,0,0,16,224,32,248,32,32,
64,5,6,6,6,0,0,168,168,168,8,16,32,5,7,7,
6,0,0,112,0,248,32,32,32,64,3,7,7,6,1,0,
128,128,128,192,160,128,128,5,7,7,6,0,0,32,32,248,
32,32,64,128,5,6,6,6,0,0,112,0,0,0,0,248,
5,6,6,6,0,0,248,8,80,32,80,128,5,6,6,6,
0,1,32,248,16,32,112,168,3,7,7,6,1,0,32,32,
32,32,32,64,128,5,6,6,6,0,0,32,16,136,136,136,
136,5,7,7,6,0,0,128,128,248,128,128,128,120,5,6,
6,6,0,0,248,8,8,8,16,96,5,5,5,6,0,1,
64,160,16,8,8,5,7,7,6,0,0,32,248,32,32,168,
168,32,5,6,6,6,0,0,248,8,8,80,32,16,4,6,
6,6,1,0,224,0,224,0,224,16,5,6,6,6,0,0,
32,64,128,136,248,8,5,6,6,6,0,0,8,8,80,32,
80,128,5,6,6,6,0,0,248,64,248,64,64,56,5,7,
7,6,0,0,64,64,248,72,80,64,64,5,7,7,6,0,
0,112,16,16,16,16,16,248,5,6,6,6,0,0,248,8,
248,8,8,248,5,7,7,6,0,0,112,0,248,8,8,16,
32,4,7,7,6,0,0,144,144,144,144,16,32,64,5,6,
6,6,0,0,32,160,160,168,168,176,5,7,7,6,0,0,
128,128,128,136,144,160,192,5,6,6,6,0,0,248,136,136,
136,136,248,5,6,6,6,0,0,248,136,136,8,16,32,5,
6,6,6,0,0,192,0,8,8,16,224,4,3,3,6,0,
4,32,144,64,3,3,3,6,0,4,224,160,224,5,5,5,
6,0,1,72,168,144,144,104,5,7,7,6,0,0,80,0,
112,8,120,136,120,4,8,8,6,1,255,96,144,144,224,144,
144,224,128,5,5,5,6,0,0,112,128,96,136,112,5,6,
6,6,0,255,136,136,152,232,136,128,5,5,5,6,0,0,
120,160,144,136,112,5,7,7,6,0,254,48,72,136,136,240,
128,128,5,8,8,6,0,254,120,136,136,136,120,8,8,112,
5,5,5,6,0,1,56,32,32,160,64,4,3,3,6,0,
3,16,208,16,4,8,8,6,0,255,16,0,48,16,16,16,
144,96,3,3,3,6,0,4,160,64,160,5,7,7,6,0,
0,32,112,160,160,168,112,32,5,7,7,6,0,0,64,64,
224,64,224,64,120,5,7,7,6,0,0,112,0,176,200,136,
136,136,5,7,7,6,0,0,80,0,112,136,136,136,112,5,
7,7,6,0,255,176,200,136,136,240,128,128,5,7,7,6,
0,255,104,152,136,136,120,8,8,5,6,6,6,0,0,112,
136,248,136,136,112,5,3,3,6,0,2,88,168,208,5,5,
5,6,0,0,112,136,136,80,216,5,7,7,6,0,0,80,
0,136,136,136,152,104,5,7,7,6,0,0,248,128,64,32,
64,128,248,5,5,5,6,0,0,248,80,80,80,152,5,7,
7,6,0,0,248,0,136,80,32,80,136,5,7,7,6,0,
255,136,136,136,136,120,8,112,5,6,6,6,0,1,8,240,
32,248,32,32,5,5,5,6,0,0,248,64,120,72,136,5,
5,5,6,0,0,248,168,248,136,136,5,5,5,6,0,1,
32,0,248,0,32,0,0,0,6,0,8,6,10,10,6,0,
254,252,252,252,252,252,252,252,252,252,252};
0, 6, 9, 0, 254, 7, 1, 145, 3, 34, 32, 255, 255, 8, 254, 7,
255, 0, 0, 0, 6, 0, 8, 1, 7, 7, 6, 2, 0, 128, 128, 128,
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
64, 152, 24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104,
2, 3, 3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32,
64, 128, 128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32,
32, 64, 128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5,
5, 6, 0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192,
64, 128, 5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192,
192, 5, 5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6,
0, 0, 112, 136, 152, 168, 200, 136, 112, 3, 7, 7, 6, 1, 0, 64,
192, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112,
128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240,
5, 7, 7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7,
6, 0, 0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0,
48, 64, 128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16,
32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 16, 96, 2, 5,
5, 6, 2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192,
192, 0, 192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64,
32, 16, 5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 1,
0, 128, 64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136,
8, 16, 32, 0, 32, 5, 6, 6, 6, 0, 0, 112, 136, 8, 104, 168,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5, 7,
7, 6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6, 0,
0, 112, 136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 224, 144,
136, 136, 136, 144, 224, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128,
128, 248, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128, 5,
7, 7, 6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7, 6,
0, 0, 136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0, 128,
128, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16, 16,
16, 144, 96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144, 136,
5, 7, 7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7, 7,
6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0,
136, 136, 200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136, 136,
136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128, 128,
128, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5, 7,
7, 6, 0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6, 0,
0, 120, 128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248, 32,
32, 32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136,
136, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32, 5,
7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7, 6,
0, 0, 136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0, 136,
136, 136, 80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16, 32,
64, 128, 248, 3, 7, 7, 6, 1, 0, 224, 128, 128, 128, 128, 128, 224,
5, 7, 7, 6, 0, 0, 136, 80, 248, 32, 248, 32, 32, 3, 7, 7,
6, 1, 0, 224, 32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4,
32, 80, 136, 5, 1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5,
128, 64, 5, 5, 5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7,
6, 0, 0, 128, 128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0,
112, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136,
136, 120, 5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7,
6, 0, 0, 48, 72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255,
112, 136, 136, 120, 8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200,
136, 136, 136, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128,
3, 8, 8, 6, 1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7,
7, 6, 0, 0, 128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1,
0, 192, 64, 64, 64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168,
168, 168, 168, 5, 5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5,
5, 6, 0, 0, 112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240,
136, 136, 240, 128, 128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8,
8, 5, 5, 5, 6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6,
0, 0, 112, 128, 112, 8, 240, 5, 7, 7, 6, 0, 0, 64, 64, 224,
64, 64, 72, 48, 5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5,
5, 5, 6, 0, 0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0,
136, 136, 168, 168, 80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136,
5, 6, 6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6,
0, 0, 248, 16, 32, 64, 248, 3, 7, 7, 6, 1, 0, 32, 64, 64,
128, 64, 64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128,
128, 3, 7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 5,
5, 6, 0, 1, 32, 16, 248, 16, 32, 5, 5, 5, 6, 0, 1, 32,
64, 248, 64, 32, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8,
0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6,
0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0,
0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8,
0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6,
0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0,
0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8,
0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6,
0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0,
0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8,
0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6,
0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0,
0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 3, 3, 3, 6, 0, 0,
224, 160, 224, 3, 4, 4, 6, 2, 3, 224, 128, 128, 128, 3, 4, 4,
6, 0, 0, 32, 32, 32, 224, 3, 3, 3, 6, 0, 0, 128, 64, 32,
2, 2, 2, 6, 1, 2, 192, 192, 5, 6, 6, 6, 0, 0, 248, 8,
248, 8, 16, 32, 5, 5, 5, 6, 0, 0, 248, 8, 48, 32, 64, 4,
5, 5, 6, 0, 0, 16, 32, 96, 160, 32, 5, 5, 5, 6, 0, 0,
32, 248, 136, 8, 48, 5, 4, 4, 6, 0, 0, 248, 32, 32, 248, 5,
5, 5, 6, 0, 0, 16, 248, 48, 80, 144, 5, 5, 5, 6, 0, 0,
64, 248, 72, 80, 64, 5, 4, 4, 6, 0, 0, 112, 16, 16, 248, 4,
5, 5, 6, 0, 0, 240, 16, 240, 16, 240, 5, 4, 4, 6, 0, 0,
168, 168, 8, 48, 5, 1, 1, 6, 0, 4, 248, 5, 7, 7, 6, 0,
0, 248, 8, 40, 48, 32, 32, 64, 5, 7, 7, 6, 0, 0, 8, 16,
32, 96, 160, 32, 32, 5, 7, 7, 6, 0, 0, 32, 248, 136, 136, 8,
16, 32, 5, 6, 6, 6, 0, 0, 248, 32, 32, 32, 32, 248, 5, 7,
7, 6, 0, 0, 16, 248, 16, 48, 80, 144, 16, 5, 7, 7, 6, 0,
0, 64, 248, 72, 72, 72, 72, 144, 5, 7, 7, 6, 0, 0, 32, 248,
32, 248, 32, 32, 32, 5, 6, 6, 6, 0, 0, 120, 72, 136, 8, 16,
96, 5, 7, 7, 6, 0, 0, 64, 120, 144, 16, 16, 16, 32, 5, 6,
6, 6, 0, 0, 248, 8, 8, 8, 8, 248, 5, 7, 7, 6, 0, 0,
80, 248, 80, 80, 16, 32, 64, 5, 6, 6, 6, 0, 0, 192, 8, 200,
8, 16, 224, 5, 6, 6, 6, 0, 0, 248, 8, 16, 32, 80, 136, 5,
7, 7, 6, 0, 0, 64, 248, 72, 80, 64, 64, 56, 5, 6, 6, 6,
0, 0, 136, 136, 72, 8, 16, 96, 5, 6, 6, 6, 0, 0, 120, 72,
168, 24, 16, 96, 5, 7, 7, 6, 0, 0, 16, 224, 32, 248, 32, 32,
64, 5, 6, 6, 6, 0, 0, 168, 168, 168, 8, 16, 32, 5, 7, 7,
6, 0, 0, 112, 0, 248, 32, 32, 32, 64, 3, 7, 7, 6, 1, 0,
128, 128, 128, 192, 160, 128, 128, 5, 7, 7, 6, 0, 0, 32, 32, 248,
32, 32, 64, 128, 5, 6, 6, 6, 0, 0, 112, 0, 0, 0, 0, 248,
5, 6, 6, 6, 0, 0, 248, 8, 80, 32, 80, 128, 5, 6, 6, 6,
0, 1, 32, 248, 16, 32, 112, 168, 3, 7, 7, 6, 1, 0, 32, 32,
32, 32, 32, 64, 128, 5, 6, 6, 6, 0, 0, 32, 16, 136, 136, 136,
136, 5, 7, 7, 6, 0, 0, 128, 128, 248, 128, 128, 128, 120, 5, 6,
6, 6, 0, 0, 248, 8, 8, 8, 16, 96, 5, 5, 5, 6, 0, 1,
64, 160, 16, 8, 8, 5, 7, 7, 6, 0, 0, 32, 248, 32, 32, 168,
168, 32, 5, 6, 6, 6, 0, 0, 248, 8, 8, 80, 32, 16, 4, 6,
6, 6, 1, 0, 224, 0, 224, 0, 224, 16, 5, 6, 6, 6, 0, 0,
32, 64, 128, 136, 248, 8, 5, 6, 6, 6, 0, 0, 8, 8, 80, 32,
80, 128, 5, 6, 6, 6, 0, 0, 248, 64, 248, 64, 64, 56, 5, 7,
7, 6, 0, 0, 64, 64, 248, 72, 80, 64, 64, 5, 7, 7, 6, 0,
0, 112, 16, 16, 16, 16, 16, 248, 5, 6, 6, 6, 0, 0, 248, 8,
248, 8, 8, 248, 5, 7, 7, 6, 0, 0, 112, 0, 248, 8, 8, 16,
32, 4, 7, 7, 6, 0, 0, 144, 144, 144, 144, 16, 32, 64, 5, 6,
6, 6, 0, 0, 32, 160, 160, 168, 168, 176, 5, 7, 7, 6, 0, 0,
128, 128, 128, 136, 144, 160, 192, 5, 6, 6, 6, 0, 0, 248, 136, 136,
136, 136, 248, 5, 6, 6, 6, 0, 0, 248, 136, 136, 8, 16, 32, 5,
6, 6, 6, 0, 0, 192, 0, 8, 8, 16, 224, 4, 3, 3, 6, 0,
4, 32, 144, 64, 3, 3, 3, 6, 0, 4, 224, 160, 224, 5, 5, 5,
6, 0, 1, 72, 168, 144, 144, 104, 5, 7, 7, 6, 0, 0, 80, 0,
112, 8, 120, 136, 120, 4, 8, 8, 6, 1, 255, 96, 144, 144, 224, 144,
144, 224, 128, 5, 5, 5, 6, 0, 0, 112, 128, 96, 136, 112, 5, 6,
6, 6, 0, 255, 136, 136, 152, 232, 136, 128, 5, 5, 5, 6, 0, 0,
120, 160, 144, 136, 112, 5, 7, 7, 6, 0, 254, 48, 72, 136, 136, 240,
128, 128, 5, 8, 8, 6, 0, 254, 120, 136, 136, 136, 120, 8, 8, 112,
5, 5, 5, 6, 0, 1, 56, 32, 32, 160, 64, 4, 3, 3, 6, 0,
3, 16, 208, 16, 4, 8, 8, 6, 0, 255, 16, 0, 48, 16, 16, 16,
144, 96, 3, 3, 3, 6, 0, 4, 160, 64, 160, 5, 7, 7, 6, 0,
0, 32, 112, 160, 160, 168, 112, 32, 5, 7, 7, 6, 0, 0, 64, 64,
224, 64, 224, 64, 120, 5, 7, 7, 6, 0, 0, 112, 0, 176, 200, 136,
136, 136, 5, 7, 7, 6, 0, 0, 80, 0, 112, 136, 136, 136, 112, 5,
7, 7, 6, 0, 255, 176, 200, 136, 136, 240, 128, 128, 5, 7, 7, 6,
0, 255, 104, 152, 136, 136, 120, 8, 8, 5, 6, 6, 6, 0, 0, 112,
136, 248, 136, 136, 112, 5, 3, 3, 6, 0, 2, 88, 168, 208, 5, 5,
5, 6, 0, 0, 112, 136, 136, 80, 216, 5, 7, 7, 6, 0, 0, 80,
0, 136, 136, 136, 152, 104, 5, 7, 7, 6, 0, 0, 248, 128, 64, 32,
64, 128, 248, 5, 5, 5, 6, 0, 0, 248, 80, 80, 80, 152, 5, 7,
7, 6, 0, 0, 248, 0, 136, 80, 32, 80, 136, 5, 7, 7, 6, 0,
255, 136, 136, 136, 136, 120, 8, 112, 5, 6, 6, 6, 0, 1, 8, 240,
32, 248, 32, 32, 5, 5, 5, 6, 0, 0, 248, 64, 120, 72, 136, 5,
5, 5, 6, 0, 0, 248, 168, 248, 136, 136, 5, 5, 5, 6, 0, 1,
32, 0, 248, 0, 32, 0, 0, 0, 6, 0, 8, 6, 10, 10, 6, 0,
254, 252, 252, 252, 252, 252, 252, 252, 252, 252, 252
};

View File

@ -11,193 +11,194 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t HD44780_W_5x7[3034] U8G_SECTION(".progmem.HD44780_W_5x7") = {
0,6,9,0,254,7,2,79,3,222,16,255,255,8,255,7,
255,4,7,7,6,0,0,16,48,112,240,112,48,16,4,7,
7,6,1,0,128,192,224,240,224,192,128,5,3,3,6,0,
4,216,72,144,5,3,3,6,0,4,216,144,72,5,7,7,
6,0,0,32,112,248,0,32,112,248,5,7,7,6,0,0,
248,112,32,0,248,112,32,5,5,5,6,0,1,112,248,248,
248,112,5,7,7,6,0,0,8,8,40,72,248,64,32,5,
7,7,6,0,0,32,112,168,32,32,32,32,5,7,7,6,
0,0,32,32,32,32,168,112,32,5,5,5,6,0,1,32,
64,248,64,32,5,5,5,6,0,1,32,16,248,16,32,5,
7,7,6,0,0,16,32,64,32,16,0,248,5,7,7,6,
0,0,64,32,16,32,64,0,248,5,5,5,6,0,1,32,
32,112,112,248,5,5,5,6,0,0,248,112,112,32,32,0,
0,0,6,0,0,1,7,7,6,2,0,128,128,128,128,128,
0,128,3,2,2,6,1,5,160,160,5,7,7,6,0,0,
80,80,248,80,248,80,80,5,7,7,6,0,0,32,120,160,
112,40,240,32,5,7,7,6,0,0,192,200,16,32,64,152,
24,5,7,7,6,0,0,96,144,160,64,168,144,104,2,3,
3,6,1,4,192,64,128,3,7,7,6,1,0,32,64,128,
128,128,64,32,3,7,7,6,1,0,128,64,32,32,32,64,
128,5,5,5,6,0,1,32,168,112,168,32,5,5,5,6,
0,1,32,32,248,32,32,2,3,3,6,2,255,192,64,128,
5,1,1,6,0,3,248,2,2,2,6,2,0,192,192,5,
5,5,6,0,1,8,16,32,64,128,5,7,7,6,0,0,
112,136,152,168,200,136,112,3,7,7,6,1,0,64,192,64,
64,64,64,224,5,7,7,6,0,0,112,136,8,112,128,128,
248,5,7,7,6,0,0,248,16,32,16,8,8,240,5,7,
7,6,0,0,16,48,80,144,248,16,16,5,7,7,6,0,
0,248,128,240,8,8,136,112,5,7,7,6,0,0,48,64,
128,240,136,136,112,5,7,7,6,0,0,248,8,16,32,32,
32,32,5,7,7,6,0,0,112,136,136,112,136,136,112,5,
7,7,6,0,0,112,136,136,120,8,16,96,2,5,5,6,
2,0,192,192,0,192,192,2,6,6,6,2,255,192,192,0,
192,64,128,4,7,7,6,0,0,16,32,64,128,64,32,16,
5,3,3,6,0,2,248,0,248,4,7,7,6,1,0,128,
64,32,16,32,64,128,5,7,7,6,0,0,112,136,8,16,
32,0,32,5,6,6,6,0,0,112,136,8,104,168,112,5,
7,7,6,0,0,112,136,136,248,136,136,136,5,7,7,6,
0,0,240,136,136,240,136,136,240,5,7,7,6,0,0,112,
136,128,128,128,136,112,5,7,7,6,0,0,224,144,136,136,
136,144,224,5,7,7,6,0,0,248,128,128,240,128,128,248,
5,7,7,6,0,0,248,128,128,240,128,128,128,5,7,7,
6,0,0,112,136,128,184,136,136,112,5,7,7,6,0,0,
136,136,136,248,136,136,136,1,7,7,6,2,0,128,128,128,
128,128,128,128,5,7,7,6,0,0,56,16,16,16,16,144,
96,5,7,7,6,0,0,136,144,160,192,160,144,136,5,7,
7,6,0,0,128,128,128,128,128,128,248,5,7,7,6,0,
0,136,216,168,136,136,136,136,5,7,7,6,0,0,136,136,
200,168,152,136,136,5,7,7,6,0,0,112,136,136,136,136,
136,112,5,7,7,6,0,0,240,136,136,240,128,128,128,5,
7,7,6,0,0,112,136,136,136,168,144,104,5,7,7,6,
0,0,240,136,136,240,160,144,136,5,7,7,6,0,0,120,
128,128,112,8,8,240,5,7,7,6,0,0,248,32,32,32,
32,32,32,5,7,7,6,0,0,136,136,136,136,136,136,112,
5,7,7,6,0,0,136,136,136,136,136,80,32,5,7,7,
6,0,0,136,136,136,136,136,168,80,5,7,7,6,0,0,
136,136,80,32,80,136,136,5,7,7,6,0,0,136,136,136,
80,32,32,32,5,7,7,6,0,0,248,8,16,32,64,128,
248,3,7,7,6,1,0,224,128,128,128,128,128,224,5,5,
5,6,0,1,128,64,32,16,8,3,7,7,6,1,0,224,
32,32,32,32,32,224,5,3,3,6,0,4,32,80,136,5,
1,1,6,0,0,248,2,2,2,6,2,5,128,64,5,5,
5,6,0,0,112,8,120,136,120,5,7,7,6,0,0,128,
128,176,200,136,136,240,5,5,5,6,0,0,112,128,128,136,
112,5,7,7,6,0,0,8,8,104,152,136,136,120,5,5,
5,6,0,0,112,136,248,128,112,5,7,7,6,0,0,48,
72,224,64,64,64,64,5,6,6,6,0,255,112,136,136,120,
8,112,5,7,7,6,0,0,128,128,176,200,136,136,136,1,
7,7,6,2,0,128,0,128,128,128,128,128,3,8,8,6,
1,255,32,0,32,32,32,32,160,64,4,7,7,6,0,0,
128,128,144,160,192,160,144,3,7,7,6,1,0,192,64,64,
64,64,64,224,5,5,5,6,0,0,208,168,168,168,168,5,
5,5,6,0,0,176,200,136,136,136,5,5,5,6,0,0,
112,136,136,136,112,5,6,6,6,0,255,240,136,136,240,128,
128,5,6,6,6,0,255,120,136,136,120,8,8,5,5,5,
6,0,0,176,200,128,128,128,5,5,5,6,0,0,112,128,
112,8,240,5,7,7,6,0,0,64,64,224,64,64,72,48,
5,5,5,6,0,0,136,136,136,152,104,5,5,5,6,0,
0,136,136,136,80,32,5,5,5,6,0,0,136,136,168,168,
80,5,5,5,6,0,0,136,80,32,80,136,5,6,6,6,
0,255,136,136,136,120,8,112,5,5,5,6,0,0,248,16,
32,64,248,3,7,7,6,1,0,32,64,64,128,64,64,32,
1,7,7,6,2,0,128,128,128,128,128,128,128,3,7,7,
6,1,0,128,64,64,32,64,64,128,5,6,6,6,0,1,
8,40,72,248,64,32,5,7,7,6,0,0,32,80,136,136,
136,136,248,5,7,7,6,0,0,248,136,128,240,136,136,240,
5,8,8,6,0,255,120,40,40,40,72,136,248,136,5,7,
7,6,0,0,168,168,168,112,168,168,168,5,7,7,6,0,
0,240,8,8,112,8,8,240,5,7,7,6,0,0,136,136,
152,168,200,136,136,5,8,8,6,0,0,80,32,136,152,168,
168,200,136,5,7,7,6,0,0,120,40,40,40,40,168,72,
5,7,7,6,0,0,248,136,136,136,136,136,136,5,7,7,
6,0,0,136,136,136,80,32,64,128,5,8,8,6,0,255,
136,136,136,136,136,136,248,8,5,7,7,6,0,0,136,136,
136,120,8,8,8,5,7,7,6,0,0,168,168,168,168,168,
168,248,5,8,8,6,0,255,168,168,168,168,168,168,248,8,
5,7,7,6,0,0,192,64,64,112,72,72,112,5,7,7,
6,0,0,136,136,136,200,168,168,200,5,7,7,6,0,0,
112,136,40,80,8,136,112,5,5,5,6,0,0,64,160,144,
144,104,5,7,7,6,0,0,32,48,40,40,32,224,224,5,
7,7,6,0,0,248,136,128,128,128,128,128,5,5,5,6,
0,0,248,80,80,80,152,5,7,7,6,0,0,248,128,64,
32,64,128,248,5,5,5,6,0,0,120,144,144,144,96,5,
7,7,6,0,0,48,40,56,40,200,216,24,5,6,6,6,
0,0,8,112,160,32,32,16,5,6,6,6,0,1,32,112,
112,112,248,32,5,7,7,6,0,0,112,136,136,248,136,136,
112,5,5,5,6,0,0,112,136,136,80,216,5,7,7,6,
0,0,48,72,32,80,136,136,112,5,3,3,6,0,2,88,
168,208,5,6,6,6,0,0,80,248,248,248,112,32,5,5,
5,6,0,0,112,128,96,136,112,5,7,7,6,0,0,112,
136,136,136,136,136,136,5,7,7,6,0,0,216,216,216,216,
216,216,216,1,7,7,6,2,0,128,0,128,128,128,128,128,
5,7,7,6,0,0,32,112,160,160,168,112,32,5,7,7,
6,0,0,48,64,64,224,64,80,168,5,5,5,6,0,0,
136,112,80,112,136,5,7,7,6,0,0,136,80,248,32,248,
32,32,1,7,7,6,2,0,128,128,128,0,128,128,128,5,
8,8,6,0,0,48,72,32,80,80,32,144,96,5,7,7,
6,0,0,24,32,32,112,32,32,192,5,7,7,6,0,0,
248,136,184,184,184,136,248,5,7,7,6,0,0,112,8,120,
136,120,0,248,5,5,5,6,0,1,40,80,160,80,40,5,
7,7,6,0,0,144,168,168,232,168,168,144,5,7,7,6,
0,0,120,136,136,120,40,72,136,5,7,7,6,0,0,248,
136,168,136,152,168,248,2,3,3,6,2,4,64,128,192,4,
5,5,6,0,3,96,144,144,144,96,5,7,7,6,0,0,
32,32,248,32,32,0,248,4,5,5,6,0,3,96,144,32,
64,240,3,5,5,6,0,3,224,32,224,32,224,5,8,8,
6,0,0,224,144,224,128,144,184,144,24,5,8,8,6,0,
255,136,136,136,136,152,232,128,128,5,7,7,6,0,0,120,
152,152,120,24,24,24,2,2,2,6,2,2,192,192,5,5,
5,6,0,0,80,136,168,168,80,3,5,5,6,0,3,64,
192,64,64,224,5,7,7,6,0,0,112,136,136,136,112,0,
248,5,5,5,6,0,1,160,80,40,80,160,5,7,7,6,
0,0,136,144,168,88,184,8,8,5,7,7,6,0,0,136,
144,184,72,152,32,56,5,8,8,6,0,0,192,64,192,72,
216,56,8,8,5,7,7,6,0,0,32,0,32,64,128,136,
112,5,8,8,6,0,0,64,32,32,80,136,248,136,136,5,
8,8,6,0,0,16,32,32,80,136,248,136,136,5,8,8,
6,0,0,32,80,0,112,136,248,136,136,5,8,8,6,0,
0,104,144,0,112,136,248,136,136,5,8,8,6,0,0,80,
0,32,80,136,248,136,136,5,8,8,6,0,0,32,80,32,
112,136,248,136,136,5,7,7,6,0,0,56,96,160,184,224,
160,184,5,8,8,6,0,255,112,136,128,128,136,112,32,96,
5,8,8,6,0,0,64,32,0,248,128,240,128,248,5,8,
8,6,0,0,8,16,0,248,128,240,128,248,5,8,8,6,
0,0,32,80,0,248,128,240,128,248,5,7,7,6,0,0,
80,0,248,128,240,128,248,3,8,8,6,1,0,128,64,0,
224,64,64,64,224,3,8,8,6,1,0,32,64,0,224,64,
64,64,224,3,8,8,6,1,0,64,160,0,224,64,64,64,
224,3,7,7,6,1,0,160,0,224,64,64,64,224,5,7,
7,6,0,0,112,72,72,232,72,72,112,5,8,8,6,0,
0,104,144,0,136,200,168,152,136,5,8,8,6,0,0,64,
32,112,136,136,136,136,112,5,8,8,6,0,0,16,32,112,
136,136,136,136,112,5,8,8,6,0,0,32,80,0,112,136,
136,136,112,5,8,8,6,0,0,104,144,0,112,136,136,136,
112,5,8,8,6,0,0,80,0,112,136,136,136,136,112,5,
5,5,6,0,1,136,80,32,80,136,5,7,7,6,0,0,
112,32,112,168,112,32,112,5,8,8,6,0,0,64,32,136,
136,136,136,136,112,5,8,8,6,0,0,16,32,136,136,136,
136,136,112,5,8,8,6,0,0,32,80,0,136,136,136,136,
112,5,8,8,6,0,0,80,0,136,136,136,136,136,112,5,
8,8,6,0,0,16,32,136,80,32,32,32,32,5,8,8,
6,0,0,192,64,112,72,72,112,64,224,5,7,7,6,0,
0,48,72,72,112,72,72,176,5,8,8,6,0,0,64,32,
0,112,8,120,136,120,5,8,8,6,0,0,16,32,0,112,
8,120,136,120,5,8,8,6,0,0,32,80,0,112,8,120,
136,120,5,8,8,6,0,0,104,144,0,112,8,120,136,120,
5,7,7,6,0,0,80,0,112,8,120,136,120,5,8,8,
6,0,0,32,80,32,112,8,120,136,120,5,6,6,6,0,
0,208,40,120,160,168,80,5,6,6,6,0,255,112,128,136,
112,32,96,5,8,8,6,0,0,64,32,0,112,136,248,128,
112,5,8,8,6,0,0,16,32,0,112,136,248,128,112,5,
8,8,6,0,0,32,80,0,112,136,248,128,112,5,7,7,
6,0,0,80,0,112,136,248,128,112,3,8,8,6,1,0,
128,64,0,64,192,64,64,224,3,8,8,6,1,0,32,64,
0,64,192,64,64,224,3,8,8,6,1,0,64,160,0,64,
192,64,64,224,3,7,7,6,1,0,160,0,64,192,64,64,
224,5,7,7,6,0,0,160,64,160,16,120,136,112,5,8,
8,6,0,0,104,144,0,176,200,136,136,136,5,8,8,6,
0,0,64,32,0,112,136,136,136,112,5,8,8,6,0,0,
16,32,0,112,136,136,136,112,5,8,8,6,0,0,32,80,
0,112,136,136,136,112,5,8,8,6,0,0,104,144,0,112,
136,136,136,112,5,7,7,6,0,0,80,0,112,136,136,136,
112,5,5,5,6,0,1,32,0,248,0,32,5,7,7,6,
0,0,16,32,112,168,112,32,64,5,8,8,6,0,0,64,
32,0,136,136,136,152,104,5,8,8,6,0,0,16,32,0,
136,136,136,152,104,5,8,8,6,0,0,32,80,0,136,136,
136,152,104,5,7,7,6,0,0,80,0,136,136,136,152,104,
5,9,9,6,0,255,16,32,0,136,136,136,248,8,112,4,
7,7,6,1,0,192,64,96,80,96,64,224,5,8,8,6,
0,255,80,0,136,136,136,248,8,112};
0, 6, 9, 0, 254, 7, 2, 79, 3, 222, 16, 255, 255, 8, 255, 7,
255, 4, 7, 7, 6, 0, 0, 16, 48, 112, 240, 112, 48, 16, 4, 7,
7, 6, 1, 0, 128, 192, 224, 240, 224, 192, 128, 5, 3, 3, 6, 0,
4, 216, 72, 144, 5, 3, 3, 6, 0, 4, 216, 144, 72, 5, 7, 7,
6, 0, 0, 32, 112, 248, 0, 32, 112, 248, 5, 7, 7, 6, 0, 0,
248, 112, 32, 0, 248, 112, 32, 5, 5, 5, 6, 0, 1, 112, 248, 248,
248, 112, 5, 7, 7, 6, 0, 0, 8, 8, 40, 72, 248, 64, 32, 5,
7, 7, 6, 0, 0, 32, 112, 168, 32, 32, 32, 32, 5, 7, 7, 6,
0, 0, 32, 32, 32, 32, 168, 112, 32, 5, 5, 5, 6, 0, 1, 32,
64, 248, 64, 32, 5, 5, 5, 6, 0, 1, 32, 16, 248, 16, 32, 5,
7, 7, 6, 0, 0, 16, 32, 64, 32, 16, 0, 248, 5, 7, 7, 6,
0, 0, 64, 32, 16, 32, 64, 0, 248, 5, 5, 5, 6, 0, 1, 32,
32, 112, 112, 248, 5, 5, 5, 6, 0, 0, 248, 112, 112, 32, 32, 0,
0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128,
0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6, 0, 0,
80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32, 120, 160,
112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32, 64, 152,
24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104, 2, 3,
3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32, 64, 128,
128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32, 32, 64,
128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5, 5, 6,
0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192, 64, 128,
5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192, 192, 5,
5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0,
112, 136, 152, 168, 200, 136, 112, 3, 7, 7, 6, 1, 0, 64, 192, 64,
64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112, 128, 128,
248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240, 5, 7,
7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7, 6, 0,
0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0, 48, 64,
128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16, 32, 32,
32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136, 112, 5,
7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 16, 96, 2, 5, 5, 6,
2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192, 192, 0,
192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64, 32, 16,
5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 1, 0, 128,
64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136, 8, 16,
32, 0, 32, 5, 6, 6, 6, 0, 0, 112, 136, 8, 104, 168, 112, 5,
7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5, 7, 7, 6,
0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6, 0, 0, 112,
136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 224, 144, 136, 136,
136, 144, 224, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 248,
5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128, 5, 7, 7,
6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7, 6, 0, 0,
136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0, 128, 128, 128,
128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16, 16, 16, 144,
96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144, 136, 5, 7,
7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7, 7, 6, 0,
0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0, 136, 136,
200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 136,
136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128, 128, 128, 5,
7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5, 7, 7, 6,
0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6, 0, 0, 120,
128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248, 32, 32, 32,
32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 136, 112,
5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32, 5, 7, 7,
6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7, 6, 0, 0,
136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0, 136, 136, 136,
80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16, 32, 64, 128,
248, 3, 7, 7, 6, 1, 0, 224, 128, 128, 128, 128, 128, 224, 5, 5,
5, 6, 0, 1, 128, 64, 32, 16, 8, 3, 7, 7, 6, 1, 0, 224,
32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4, 32, 80, 136, 5,
1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5, 128, 64, 5, 5,
5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7, 6, 0, 0, 128,
128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0, 112, 128, 128, 136,
112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136, 136, 120, 5, 5,
5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7, 6, 0, 0, 48,
72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255, 112, 136, 136, 120,
8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200, 136, 136, 136, 1,
7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 3, 8, 8, 6,
1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7, 7, 6, 0, 0,
128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1, 0, 192, 64, 64,
64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168, 168, 168, 168, 5,
5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5, 5, 6, 0, 0,
112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240, 136, 136, 240, 128,
128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8, 8, 5, 5, 5,
6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6, 0, 0, 112, 128,
112, 8, 240, 5, 7, 7, 6, 0, 0, 64, 64, 224, 64, 64, 72, 48,
5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5, 5, 5, 6, 0,
0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0, 136, 136, 168, 168,
80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136, 5, 6, 6, 6,
0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6, 0, 0, 248, 16,
32, 64, 248, 3, 7, 7, 6, 1, 0, 32, 64, 64, 128, 64, 64, 32,
1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128, 128, 3, 7, 7,
6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 6, 6, 6, 0, 1,
8, 40, 72, 248, 64, 32, 5, 7, 7, 6, 0, 0, 32, 80, 136, 136,
136, 136, 248, 5, 7, 7, 6, 0, 0, 248, 136, 128, 240, 136, 136, 240,
5, 8, 8, 6, 0, 255, 120, 40, 40, 40, 72, 136, 248, 136, 5, 7,
7, 6, 0, 0, 168, 168, 168, 112, 168, 168, 168, 5, 7, 7, 6, 0,
0, 240, 8, 8, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 136, 136,
152, 168, 200, 136, 136, 5, 8, 8, 6, 0, 0, 80, 32, 136, 152, 168,
168, 200, 136, 5, 7, 7, 6, 0, 0, 120, 40, 40, 40, 40, 168, 72,
5, 7, 7, 6, 0, 0, 248, 136, 136, 136, 136, 136, 136, 5, 7, 7,
6, 0, 0, 136, 136, 136, 80, 32, 64, 128, 5, 8, 8, 6, 0, 255,
136, 136, 136, 136, 136, 136, 248, 8, 5, 7, 7, 6, 0, 0, 136, 136,
136, 120, 8, 8, 8, 5, 7, 7, 6, 0, 0, 168, 168, 168, 168, 168,
168, 248, 5, 8, 8, 6, 0, 255, 168, 168, 168, 168, 168, 168, 248, 8,
5, 7, 7, 6, 0, 0, 192, 64, 64, 112, 72, 72, 112, 5, 7, 7,
6, 0, 0, 136, 136, 136, 200, 168, 168, 200, 5, 7, 7, 6, 0, 0,
112, 136, 40, 80, 8, 136, 112, 5, 5, 5, 6, 0, 0, 64, 160, 144,
144, 104, 5, 7, 7, 6, 0, 0, 32, 48, 40, 40, 32, 224, 224, 5,
7, 7, 6, 0, 0, 248, 136, 128, 128, 128, 128, 128, 5, 5, 5, 6,
0, 0, 248, 80, 80, 80, 152, 5, 7, 7, 6, 0, 0, 248, 128, 64,
32, 64, 128, 248, 5, 5, 5, 6, 0, 0, 120, 144, 144, 144, 96, 5,
7, 7, 6, 0, 0, 48, 40, 56, 40, 200, 216, 24, 5, 6, 6, 6,
0, 0, 8, 112, 160, 32, 32, 16, 5, 6, 6, 6, 0, 1, 32, 112,
112, 112, 248, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136,
112, 5, 5, 5, 6, 0, 0, 112, 136, 136, 80, 216, 5, 7, 7, 6,
0, 0, 48, 72, 32, 80, 136, 136, 112, 5, 3, 3, 6, 0, 2, 88,
168, 208, 5, 6, 6, 6, 0, 0, 80, 248, 248, 248, 112, 32, 5, 5,
5, 6, 0, 0, 112, 128, 96, 136, 112, 5, 7, 7, 6, 0, 0, 112,
136, 136, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0, 216, 216, 216, 216,
216, 216, 216, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128,
5, 7, 7, 6, 0, 0, 32, 112, 160, 160, 168, 112, 32, 5, 7, 7,
6, 0, 0, 48, 64, 64, 224, 64, 80, 168, 5, 5, 5, 6, 0, 0,
136, 112, 80, 112, 136, 5, 7, 7, 6, 0, 0, 136, 80, 248, 32, 248,
32, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 0, 128, 128, 128, 5,
8, 8, 6, 0, 0, 48, 72, 32, 80, 80, 32, 144, 96, 5, 7, 7,
6, 0, 0, 24, 32, 32, 112, 32, 32, 192, 5, 7, 7, 6, 0, 0,
248, 136, 184, 184, 184, 136, 248, 5, 7, 7, 6, 0, 0, 112, 8, 120,
136, 120, 0, 248, 5, 5, 5, 6, 0, 1, 40, 80, 160, 80, 40, 5,
7, 7, 6, 0, 0, 144, 168, 168, 232, 168, 168, 144, 5, 7, 7, 6,
0, 0, 120, 136, 136, 120, 40, 72, 136, 5, 7, 7, 6, 0, 0, 248,
136, 168, 136, 152, 168, 248, 2, 3, 3, 6, 2, 4, 64, 128, 192, 4,
5, 5, 6, 0, 3, 96, 144, 144, 144, 96, 5, 7, 7, 6, 0, 0,
32, 32, 248, 32, 32, 0, 248, 4, 5, 5, 6, 0, 3, 96, 144, 32,
64, 240, 3, 5, 5, 6, 0, 3, 224, 32, 224, 32, 224, 5, 8, 8,
6, 0, 0, 224, 144, 224, 128, 144, 184, 144, 24, 5, 8, 8, 6, 0,
255, 136, 136, 136, 136, 152, 232, 128, 128, 5, 7, 7, 6, 0, 0, 120,
152, 152, 120, 24, 24, 24, 2, 2, 2, 6, 2, 2, 192, 192, 5, 5,
5, 6, 0, 0, 80, 136, 168, 168, 80, 3, 5, 5, 6, 0, 3, 64,
192, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 112, 0,
248, 5, 5, 5, 6, 0, 1, 160, 80, 40, 80, 160, 5, 7, 7, 6,
0, 0, 136, 144, 168, 88, 184, 8, 8, 5, 7, 7, 6, 0, 0, 136,
144, 184, 72, 152, 32, 56, 5, 8, 8, 6, 0, 0, 192, 64, 192, 72,
216, 56, 8, 8, 5, 7, 7, 6, 0, 0, 32, 0, 32, 64, 128, 136,
112, 5, 8, 8, 6, 0, 0, 64, 32, 32, 80, 136, 248, 136, 136, 5,
8, 8, 6, 0, 0, 16, 32, 32, 80, 136, 248, 136, 136, 5, 8, 8,
6, 0, 0, 32, 80, 0, 112, 136, 248, 136, 136, 5, 8, 8, 6, 0,
0, 104, 144, 0, 112, 136, 248, 136, 136, 5, 8, 8, 6, 0, 0, 80,
0, 32, 80, 136, 248, 136, 136, 5, 8, 8, 6, 0, 0, 32, 80, 32,
112, 136, 248, 136, 136, 5, 7, 7, 6, 0, 0, 56, 96, 160, 184, 224,
160, 184, 5, 8, 8, 6, 0, 255, 112, 136, 128, 128, 136, 112, 32, 96,
5, 8, 8, 6, 0, 0, 64, 32, 0, 248, 128, 240, 128, 248, 5, 8,
8, 6, 0, 0, 8, 16, 0, 248, 128, 240, 128, 248, 5, 8, 8, 6,
0, 0, 32, 80, 0, 248, 128, 240, 128, 248, 5, 7, 7, 6, 0, 0,
80, 0, 248, 128, 240, 128, 248, 3, 8, 8, 6, 1, 0, 128, 64, 0,
224, 64, 64, 64, 224, 3, 8, 8, 6, 1, 0, 32, 64, 0, 224, 64,
64, 64, 224, 3, 8, 8, 6, 1, 0, 64, 160, 0, 224, 64, 64, 64,
224, 3, 7, 7, 6, 1, 0, 160, 0, 224, 64, 64, 64, 224, 5, 7,
7, 6, 0, 0, 112, 72, 72, 232, 72, 72, 112, 5, 8, 8, 6, 0,
0, 104, 144, 0, 136, 200, 168, 152, 136, 5, 8, 8, 6, 0, 0, 64,
32, 112, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 16, 32, 112,
136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80, 0, 112, 136,
136, 136, 112, 5, 8, 8, 6, 0, 0, 104, 144, 0, 112, 136, 136, 136,
112, 5, 8, 8, 6, 0, 0, 80, 0, 112, 136, 136, 136, 136, 112, 5,
5, 5, 6, 0, 1, 136, 80, 32, 80, 136, 5, 7, 7, 6, 0, 0,
112, 32, 112, 168, 112, 32, 112, 5, 8, 8, 6, 0, 0, 64, 32, 136,
136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 16, 32, 136, 136, 136,
136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80, 0, 136, 136, 136, 136,
112, 5, 8, 8, 6, 0, 0, 80, 0, 136, 136, 136, 136, 136, 112, 5,
8, 8, 6, 0, 0, 16, 32, 136, 80, 32, 32, 32, 32, 5, 8, 8,
6, 0, 0, 192, 64, 112, 72, 72, 112, 64, 224, 5, 7, 7, 6, 0,
0, 48, 72, 72, 112, 72, 72, 176, 5, 8, 8, 6, 0, 0, 64, 32,
0, 112, 8, 120, 136, 120, 5, 8, 8, 6, 0, 0, 16, 32, 0, 112,
8, 120, 136, 120, 5, 8, 8, 6, 0, 0, 32, 80, 0, 112, 8, 120,
136, 120, 5, 8, 8, 6, 0, 0, 104, 144, 0, 112, 8, 120, 136, 120,
5, 7, 7, 6, 0, 0, 80, 0, 112, 8, 120, 136, 120, 5, 8, 8,
6, 0, 0, 32, 80, 32, 112, 8, 120, 136, 120, 5, 6, 6, 6, 0,
0, 208, 40, 120, 160, 168, 80, 5, 6, 6, 6, 0, 255, 112, 128, 136,
112, 32, 96, 5, 8, 8, 6, 0, 0, 64, 32, 0, 112, 136, 248, 128,
112, 5, 8, 8, 6, 0, 0, 16, 32, 0, 112, 136, 248, 128, 112, 5,
8, 8, 6, 0, 0, 32, 80, 0, 112, 136, 248, 128, 112, 5, 7, 7,
6, 0, 0, 80, 0, 112, 136, 248, 128, 112, 3, 8, 8, 6, 1, 0,
128, 64, 0, 64, 192, 64, 64, 224, 3, 8, 8, 6, 1, 0, 32, 64,
0, 64, 192, 64, 64, 224, 3, 8, 8, 6, 1, 0, 64, 160, 0, 64,
192, 64, 64, 224, 3, 7, 7, 6, 1, 0, 160, 0, 64, 192, 64, 64,
224, 5, 7, 7, 6, 0, 0, 160, 64, 160, 16, 120, 136, 112, 5, 8,
8, 6, 0, 0, 104, 144, 0, 176, 200, 136, 136, 136, 5, 8, 8, 6,
0, 0, 64, 32, 0, 112, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0,
16, 32, 0, 112, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80,
0, 112, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 104, 144, 0, 112,
136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 80, 0, 112, 136, 136, 136,
112, 5, 5, 5, 6, 0, 1, 32, 0, 248, 0, 32, 5, 7, 7, 6,
0, 0, 16, 32, 112, 168, 112, 32, 64, 5, 8, 8, 6, 0, 0, 64,
32, 0, 136, 136, 136, 152, 104, 5, 8, 8, 6, 0, 0, 16, 32, 0,
136, 136, 136, 152, 104, 5, 8, 8, 6, 0, 0, 32, 80, 0, 136, 136,
136, 152, 104, 5, 7, 7, 6, 0, 0, 80, 0, 136, 136, 136, 152, 104,
5, 9, 9, 6, 0, 255, 16, 32, 0, 136, 136, 136, 248, 8, 112, 4,
7, 7, 6, 1, 0, 192, 64, 96, 80, 96, 64, 224, 5, 8, 8, 6,
0, 255, 80, 0, 136, 136, 136, 248, 8, 112
};

View File

@ -11,166 +11,166 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t ISO10646_1_5x7[2592] U8G_SECTION(".progmem.ISO10646_1_5x7") = {
0,6,9,0,254,7,1,146,3,33,32,255,255,8,255,7,
255,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128,
128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
0,0,112,136,136,136,136,136,112,3,7,7,6,1,0,64,
192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
112,128,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
112,5,7,7,6,0,0,112,136,136,120,8,8,112,2,5,
5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1,
0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
8,16,32,0,32,5,7,7,6,0,0,112,136,8,104,168,
168,112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,
7,7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,
0,0,112,136,128,128,128,136,112,5,7,7,6,0,0,240,
136,136,136,136,136,240,5,7,7,6,0,0,248,128,128,240,
128,128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,
5,7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,
6,0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,
128,128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,
16,16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,
136,5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,
7,6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,
0,136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,
136,136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,
128,128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,
7,7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,
0,0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,
32,32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,
136,136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,
5,7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,
6,0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,
136,136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,
32,64,128,248,3,7,7,6,1,0,224,128,128,128,128,128,
224,5,5,5,6,0,1,128,64,32,16,8,3,7,7,6,
1,0,224,32,32,32,32,32,224,5,3,3,6,0,4,32,
80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,128,
64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,6,
0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,112,
128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,136,
120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,6,
0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,112,
136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,136,
136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,3,
8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,7,
6,0,0,128,128,144,160,192,160,144,3,7,7,6,1,0,
192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,168,
168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,5,
6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,136,
136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,8,
5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,0,
0,112,128,112,8,240,4,7,7,6,0,0,64,64,224,64,
64,64,48,5,5,5,6,0,0,136,136,136,152,104,5,5,
5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,136,
136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,5,
6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,0,
0,248,16,32,64,248,3,7,7,6,1,0,32,64,64,128,
64,64,32,1,7,7,6,2,0,128,128,128,128,128,128,128,
3,7,7,6,1,0,128,64,64,32,64,64,128,5,2,2,
6,0,2,104,144,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,1,7,7,6,2,0,128,0,128,128,128,128,128,5,7,
7,6,0,0,32,112,168,160,168,112,32,5,7,7,6,0,
0,48,64,64,224,64,80,168,5,5,5,6,0,0,136,112,
80,112,136,5,7,7,6,0,0,136,80,32,248,32,248,32,
1,7,7,6,2,0,128,128,128,0,128,128,128,5,8,8,
6,0,0,48,72,32,80,80,32,144,96,3,1,1,6,1,
7,160,5,7,7,6,0,0,248,136,184,184,184,136,248,5,
7,7,6,0,1,112,8,120,136,120,0,248,5,5,5,6,
0,1,40,80,160,80,40,5,3,3,6,0,1,248,8,8,
2,2,2,6,2,6,64,128,5,7,7,6,0,0,248,136,
168,136,152,168,248,5,1,1,6,0,6,248,4,4,4,6,
0,3,96,144,144,96,5,7,7,6,0,0,32,32,248,32,
32,0,248,4,5,5,6,0,3,96,144,32,64,240,3,5,
5,6,0,3,224,32,224,32,224,2,2,2,6,2,6,64,
128,5,8,8,6,0,255,136,136,136,136,152,232,128,128,5,
7,7,6,0,0,120,152,152,120,24,24,24,2,2,2,6,
2,2,192,192,2,2,2,6,2,255,64,128,3,5,5,6,
0,3,64,192,64,64,224,5,7,7,6,0,1,112,136,136,
136,112,0,248,5,5,5,6,0,1,160,80,40,80,160,5,
7,7,6,0,0,136,144,168,88,184,8,8,5,7,7,6,
0,0,136,144,184,72,152,32,56,5,8,8,6,0,0,192,
64,192,72,216,56,8,8,5,7,7,6,0,0,32,0,32,
64,128,136,112,5,8,8,6,0,0,64,32,0,112,136,248,
136,136,5,8,8,6,0,0,16,32,0,112,136,248,136,136,
5,8,8,6,0,0,32,80,0,112,136,248,136,136,5,8,
8,6,0,0,104,144,0,112,136,248,136,136,5,8,8,6,
0,0,80,0,112,136,136,248,136,136,5,8,8,6,0,0,
32,80,32,112,136,248,136,136,5,7,7,6,0,0,56,96,
160,184,224,160,184,5,8,8,6,0,255,112,136,128,128,136,
112,32,96,5,8,8,6,0,0,64,32,0,248,128,240,128,
248,5,8,8,6,0,0,8,16,0,248,128,240,128,248,5,
8,8,6,0,0,32,80,0,248,128,240,128,248,5,7,7,
6,0,0,80,0,248,128,240,128,248,3,8,8,6,1,0,
128,64,0,224,64,64,64,224,3,8,8,6,1,0,32,64,
0,224,64,64,64,224,3,8,8,6,1,0,64,160,0,224,
64,64,64,224,3,7,7,6,1,0,160,0,224,64,64,64,
224,5,7,7,6,0,0,112,72,72,232,72,72,112,5,8,
8,6,0,0,104,144,0,136,200,168,152,136,5,8,8,6,
0,0,64,32,112,136,136,136,136,112,5,8,8,6,0,0,
16,32,112,136,136,136,136,112,5,8,8,6,0,0,32,80,
0,112,136,136,136,112,5,8,8,6,0,0,104,144,0,112,
136,136,136,112,5,8,8,6,0,0,80,0,112,136,136,136,
136,112,5,5,5,6,0,1,136,80,32,80,136,5,8,8,
6,0,255,16,112,168,168,168,168,112,64,5,8,8,6,0,
0,64,32,136,136,136,136,136,112,5,8,8,6,0,0,16,
32,136,136,136,136,136,112,5,8,8,6,0,0,32,80,0,
136,136,136,136,112,5,8,8,6,0,0,80,0,136,136,136,
136,136,112,5,8,8,6,0,0,16,32,136,80,32,32,32,
32,5,9,9,6,0,255,192,64,112,72,72,112,64,64,224,
4,8,8,6,1,255,96,144,144,160,144,144,224,128,5,8,
8,6,0,0,64,32,0,112,8,120,136,120,5,8,8,6,
0,0,16,32,0,112,8,120,136,120,5,8,8,6,0,0,
32,80,0,112,8,120,136,120,5,8,8,6,0,0,104,144,
0,112,8,120,136,120,5,7,7,6,0,0,80,0,112,8,
120,136,120,5,8,8,6,0,0,32,80,32,112,8,120,136,
120,5,6,6,6,0,0,208,40,120,160,168,80,5,6,6,
6,0,255,112,128,136,112,32,96,5,8,8,6,0,0,64,
32,0,112,136,248,128,112,5,8,8,6,0,0,16,32,0,
112,136,248,128,112,5,8,8,6,0,0,32,80,0,112,136,
248,128,112,5,7,7,6,0,0,80,0,112,136,248,128,112,
3,8,8,6,1,0,128,64,0,64,192,64,64,224,3,8,
8,6,1,0,32,64,0,64,192,64,64,224,3,8,8,6,
1,0,64,160,0,64,192,64,64,224,3,7,7,6,1,0,
160,0,64,192,64,64,224,5,7,7,6,0,0,160,64,160,
16,120,136,112,5,8,8,6,0,0,104,144,0,176,200,136,
136,136,5,8,8,6,0,0,64,32,0,112,136,136,136,112,
5,8,8,6,0,0,16,32,0,112,136,136,136,112,5,8,
8,6,0,0,32,80,0,112,136,136,136,112,5,8,8,6,
0,0,104,144,0,112,136,136,136,112,5,7,7,6,0,0,
80,0,112,136,136,136,112,5,5,5,6,0,1,32,0,248,
0,32,5,7,7,6,0,255,16,112,168,168,168,112,64,5,
8,8,6,0,0,64,32,0,136,136,136,152,104,5,8,8,
6,0,0,16,32,0,136,136,136,152,104,5,8,8,6,0,
0,32,80,0,136,136,136,152,104,5,7,7,6,0,0,80,
0,136,136,136,152,104,5,9,9,6,0,255,16,32,0,136,
136,136,248,8,112,4,7,7,6,1,255,192,64,96,80,96,
64,224,5,8,8,6,0,255,80,0,136,136,136,120,8,112
};
0, 6, 9, 0, 254, 7, 1, 146, 3, 33, 32, 255, 255, 8, 255, 7,
255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
64, 152, 24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104,
2, 3, 3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32,
64, 128, 128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32,
32, 64, 128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5,
5, 6, 0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192,
64, 128, 5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192,
192, 5, 5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6,
0, 0, 112, 136, 136, 136, 136, 136, 112, 3, 7, 7, 6, 1, 0, 64,
192, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112,
128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240,
5, 7, 7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7,
6, 0, 0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0,
112, 128, 128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16,
32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 8, 112, 2, 5,
5, 6, 2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192,
192, 0, 192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64,
32, 16, 5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 1,
0, 128, 64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136,
8, 16, 32, 0, 32, 5, 7, 7, 6, 0, 0, 112, 136, 8, 104, 168,
168, 112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5,
7, 7, 6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6,
0, 0, 112, 136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 240,
136, 136, 136, 136, 136, 240, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240,
128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128,
5, 7, 7, 6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7,
6, 0, 0, 136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0,
128, 128, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16,
16, 16, 144, 96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144,
136, 5, 7, 7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7,
7, 6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0,
0, 136, 136, 200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136,
136, 136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128,
128, 128, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5,
7, 7, 6, 0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6,
0, 0, 120, 128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248,
32, 32, 32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136,
136, 136, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32,
5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7,
6, 0, 0, 136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0,
136, 136, 136, 80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16,
32, 64, 128, 248, 3, 7, 7, 6, 1, 0, 224, 128, 128, 128, 128, 128,
224, 5, 5, 5, 6, 0, 1, 128, 64, 32, 16, 8, 3, 7, 7, 6,
1, 0, 224, 32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4, 32,
80, 136, 5, 1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5, 128,
64, 5, 5, 5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7, 6,
0, 0, 128, 128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0, 112,
128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136, 136,
120, 5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7, 6,
0, 0, 48, 72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255, 112,
136, 136, 120, 8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200, 136,
136, 136, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 3,
8, 8, 6, 1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7, 7,
6, 0, 0, 128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1, 0,
192, 64, 64, 64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168, 168,
168, 168, 5, 5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5, 5,
6, 0, 0, 112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240, 136,
136, 240, 128, 128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8, 8,
5, 5, 5, 6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6, 0,
0, 112, 128, 112, 8, 240, 4, 7, 7, 6, 0, 0, 64, 64, 224, 64,
64, 64, 48, 5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5, 5,
5, 6, 0, 0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0, 136,
136, 168, 168, 80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136, 5,
6, 6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6, 0,
0, 248, 16, 32, 64, 248, 3, 7, 7, 6, 1, 0, 32, 64, 64, 128,
64, 64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128, 128,
3, 7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 2, 2,
6, 0, 2, 104, 144, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0,
6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0,
0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0,
0, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 5, 7,
7, 6, 0, 0, 32, 112, 168, 160, 168, 112, 32, 5, 7, 7, 6, 0,
0, 48, 64, 64, 224, 64, 80, 168, 5, 5, 5, 6, 0, 0, 136, 112,
80, 112, 136, 5, 7, 7, 6, 0, 0, 136, 80, 32, 248, 32, 248, 32,
1, 7, 7, 6, 2, 0, 128, 128, 128, 0, 128, 128, 128, 5, 8, 8,
6, 0, 0, 48, 72, 32, 80, 80, 32, 144, 96, 3, 1, 1, 6, 1,
7, 160, 5, 7, 7, 6, 0, 0, 248, 136, 184, 184, 184, 136, 248, 5,
7, 7, 6, 0, 1, 112, 8, 120, 136, 120, 0, 248, 5, 5, 5, 6,
0, 1, 40, 80, 160, 80, 40, 5, 3, 3, 6, 0, 1, 248, 8, 8,
2, 2, 2, 6, 2, 6, 64, 128, 5, 7, 7, 6, 0, 0, 248, 136,
168, 136, 152, 168, 248, 5, 1, 1, 6, 0, 6, 248, 4, 4, 4, 6,
0, 3, 96, 144, 144, 96, 5, 7, 7, 6, 0, 0, 32, 32, 248, 32,
32, 0, 248, 4, 5, 5, 6, 0, 3, 96, 144, 32, 64, 240, 3, 5,
5, 6, 0, 3, 224, 32, 224, 32, 224, 2, 2, 2, 6, 2, 6, 64,
128, 5, 8, 8, 6, 0, 255, 136, 136, 136, 136, 152, 232, 128, 128, 5,
7, 7, 6, 0, 0, 120, 152, 152, 120, 24, 24, 24, 2, 2, 2, 6,
2, 2, 192, 192, 2, 2, 2, 6, 2, 255, 64, 128, 3, 5, 5, 6,
0, 3, 64, 192, 64, 64, 224, 5, 7, 7, 6, 0, 1, 112, 136, 136,
136, 112, 0, 248, 5, 5, 5, 6, 0, 1, 160, 80, 40, 80, 160, 5,
7, 7, 6, 0, 0, 136, 144, 168, 88, 184, 8, 8, 5, 7, 7, 6,
0, 0, 136, 144, 184, 72, 152, 32, 56, 5, 8, 8, 6, 0, 0, 192,
64, 192, 72, 216, 56, 8, 8, 5, 7, 7, 6, 0, 0, 32, 0, 32,
64, 128, 136, 112, 5, 8, 8, 6, 0, 0, 64, 32, 0, 112, 136, 248,
136, 136, 5, 8, 8, 6, 0, 0, 16, 32, 0, 112, 136, 248, 136, 136,
5, 8, 8, 6, 0, 0, 32, 80, 0, 112, 136, 248, 136, 136, 5, 8,
8, 6, 0, 0, 104, 144, 0, 112, 136, 248, 136, 136, 5, 8, 8, 6,
0, 0, 80, 0, 112, 136, 136, 248, 136, 136, 5, 8, 8, 6, 0, 0,
32, 80, 32, 112, 136, 248, 136, 136, 5, 7, 7, 6, 0, 0, 56, 96,
160, 184, 224, 160, 184, 5, 8, 8, 6, 0, 255, 112, 136, 128, 128, 136,
112, 32, 96, 5, 8, 8, 6, 0, 0, 64, 32, 0, 248, 128, 240, 128,
248, 5, 8, 8, 6, 0, 0, 8, 16, 0, 248, 128, 240, 128, 248, 5,
8, 8, 6, 0, 0, 32, 80, 0, 248, 128, 240, 128, 248, 5, 7, 7,
6, 0, 0, 80, 0, 248, 128, 240, 128, 248, 3, 8, 8, 6, 1, 0,
128, 64, 0, 224, 64, 64, 64, 224, 3, 8, 8, 6, 1, 0, 32, 64,
0, 224, 64, 64, 64, 224, 3, 8, 8, 6, 1, 0, 64, 160, 0, 224,
64, 64, 64, 224, 3, 7, 7, 6, 1, 0, 160, 0, 224, 64, 64, 64,
224, 5, 7, 7, 6, 0, 0, 112, 72, 72, 232, 72, 72, 112, 5, 8,
8, 6, 0, 0, 104, 144, 0, 136, 200, 168, 152, 136, 5, 8, 8, 6,
0, 0, 64, 32, 112, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0,
16, 32, 112, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80,
0, 112, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 104, 144, 0, 112,
136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 80, 0, 112, 136, 136, 136,
136, 112, 5, 5, 5, 6, 0, 1, 136, 80, 32, 80, 136, 5, 8, 8,
6, 0, 255, 16, 112, 168, 168, 168, 168, 112, 64, 5, 8, 8, 6, 0,
0, 64, 32, 136, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 16,
32, 136, 136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 32, 80, 0,
136, 136, 136, 136, 112, 5, 8, 8, 6, 0, 0, 80, 0, 136, 136, 136,
136, 136, 112, 5, 8, 8, 6, 0, 0, 16, 32, 136, 80, 32, 32, 32,
32, 5, 9, 9, 6, 0, 255, 192, 64, 112, 72, 72, 112, 64, 64, 224,
4, 8, 8, 6, 1, 255, 96, 144, 144, 160, 144, 144, 224, 128, 5, 8,
8, 6, 0, 0, 64, 32, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6,
0, 0, 16, 32, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6, 0, 0,
32, 80, 0, 112, 8, 120, 136, 120, 5, 8, 8, 6, 0, 0, 104, 144,
0, 112, 8, 120, 136, 120, 5, 7, 7, 6, 0, 0, 80, 0, 112, 8,
120, 136, 120, 5, 8, 8, 6, 0, 0, 32, 80, 32, 112, 8, 120, 136,
120, 5, 6, 6, 6, 0, 0, 208, 40, 120, 160, 168, 80, 5, 6, 6,
6, 0, 255, 112, 128, 136, 112, 32, 96, 5, 8, 8, 6, 0, 0, 64,
32, 0, 112, 136, 248, 128, 112, 5, 8, 8, 6, 0, 0, 16, 32, 0,
112, 136, 248, 128, 112, 5, 8, 8, 6, 0, 0, 32, 80, 0, 112, 136,
248, 128, 112, 5, 7, 7, 6, 0, 0, 80, 0, 112, 136, 248, 128, 112,
3, 8, 8, 6, 1, 0, 128, 64, 0, 64, 192, 64, 64, 224, 3, 8,
8, 6, 1, 0, 32, 64, 0, 64, 192, 64, 64, 224, 3, 8, 8, 6,
1, 0, 64, 160, 0, 64, 192, 64, 64, 224, 3, 7, 7, 6, 1, 0,
160, 0, 64, 192, 64, 64, 224, 5, 7, 7, 6, 0, 0, 160, 64, 160,
16, 120, 136, 112, 5, 8, 8, 6, 0, 0, 104, 144, 0, 176, 200, 136,
136, 136, 5, 8, 8, 6, 0, 0, 64, 32, 0, 112, 136, 136, 136, 112,
5, 8, 8, 6, 0, 0, 16, 32, 0, 112, 136, 136, 136, 112, 5, 8,
8, 6, 0, 0, 32, 80, 0, 112, 136, 136, 136, 112, 5, 8, 8, 6,
0, 0, 104, 144, 0, 112, 136, 136, 136, 112, 5, 7, 7, 6, 0, 0,
80, 0, 112, 136, 136, 136, 112, 5, 5, 5, 6, 0, 1, 32, 0, 248,
0, 32, 5, 7, 7, 6, 0, 255, 16, 112, 168, 168, 168, 112, 64, 5,
8, 8, 6, 0, 0, 64, 32, 0, 136, 136, 136, 152, 104, 5, 8, 8,
6, 0, 0, 16, 32, 0, 136, 136, 136, 152, 104, 5, 8, 8, 6, 0,
0, 32, 80, 0, 136, 136, 136, 152, 104, 5, 7, 7, 6, 0, 0, 80,
0, 136, 136, 136, 152, 104, 5, 9, 9, 6, 0, 255, 16, 32, 0, 136,
136, 136, 248, 8, 112, 4, 7, 7, 6, 1, 255, 192, 64, 96, 80, 96,
64, 224, 5, 8, 8, 6, 0, 255, 80, 0, 136, 136, 136, 120, 8, 112
};

View File

@ -11,164 +11,164 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t ISO10646_5_Cyrillic_5x7[2560] U8G_SECTION(".progmem.ISO10646_5_Cyrillic_5x7") = {
0,6,9,0,254,7,1,145,3,32,32,255,255,8,255,7,
255,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128,
128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
0,0,112,136,152,168,200,136,112,3,7,7,6,1,0,64,
192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
48,64,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
112,5,7,7,6,0,0,112,136,136,120,8,16,96,2,5,
5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1,
0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
8,16,32,0,32,5,6,6,6,0,0,112,136,8,104,168,
112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,7,
7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,0,
0,112,136,128,128,128,136,112,5,7,7,6,0,0,224,144,
136,136,136,144,224,5,7,7,6,0,0,248,128,128,240,128,
128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,5,
7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,6,
0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,128,
128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,16,
16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,136,
5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,7,
6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,0,
136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,136,
136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,128,
128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,7,
7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,0,
0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,32,
32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,136,
136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,5,
7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,6,
0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,136,
136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,32,
64,128,248,3,7,7,6,1,0,224,128,128,128,128,128,224,
5,5,5,6,0,1,128,64,32,16,8,3,7,7,6,1,
0,224,32,32,32,32,32,224,5,3,3,6,0,4,32,80,
136,5,1,1,6,0,0,248,2,2,2,6,2,5,128,64,
5,5,5,6,0,0,112,8,120,136,120,5,7,7,6,0,
0,128,128,176,200,136,136,240,5,5,5,6,0,0,112,128,
128,136,112,5,7,7,6,0,0,8,8,104,152,136,136,120,
5,5,5,6,0,0,112,136,248,128,112,5,7,7,6,0,
0,48,72,224,64,64,64,64,5,6,6,6,0,255,112,136,
136,120,8,112,5,7,7,6,0,0,128,128,176,200,136,136,
136,1,7,7,6,2,0,128,0,128,128,128,128,128,3,8,
8,6,1,255,32,0,32,32,32,32,160,64,4,7,7,6,
0,0,128,128,144,160,192,160,144,3,7,7,6,1,0,192,
64,64,64,64,64,224,5,5,5,6,0,0,208,168,168,168,
168,5,5,5,6,0,0,176,200,136,136,136,5,5,5,6,
0,0,112,136,136,136,112,5,6,6,6,0,255,240,136,136,
240,128,128,5,6,6,6,0,255,120,136,136,120,8,8,5,
5,5,6,0,0,176,200,128,128,128,5,5,5,6,0,0,
112,128,112,8,240,5,7,7,6,0,0,64,64,224,64,64,
72,48,5,5,5,6,0,0,136,136,136,152,104,5,5,5,
6,0,0,136,136,136,80,32,5,5,5,6,0,0,136,136,
168,168,80,5,5,5,6,0,0,136,80,32,80,136,5,6,
6,6,0,255,136,136,136,120,8,112,5,5,5,6,0,0,
248,16,32,64,248,3,7,7,6,1,0,32,64,64,128,64,
64,32,1,7,7,6,2,0,128,128,128,128,128,128,128,3,
7,7,6,1,0,128,64,64,32,64,64,128,5,2,2,6,
0,3,104,144,0,0,0,6,0,0,0,0,0,6,0,0,
0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,
0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,
0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,
0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,
0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,
0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,
0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,
0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,
0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,
0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,
0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,
0,6,0,0,0,0,0,6,0,0,5,8,8,6,0,0,
64,248,128,128,240,128,128,248,5,8,8,6,0,0,80,248,
128,128,240,128,128,248,5,7,7,6,0,0,224,64,64,112,
72,72,112,5,8,8,6,0,0,16,32,248,136,128,128,128,
128,5,7,7,6,0,0,48,72,128,224,128,72,48,5,7,
7,6,0,0,112,136,128,112,8,136,112,3,7,7,6,1,
0,224,64,64,64,64,64,224,3,8,8,6,1,0,160,0,
224,64,64,64,64,224,5,7,7,6,0,0,56,16,16,16,
16,144,96,5,7,7,6,0,0,160,160,160,184,168,168,184,
5,7,7,6,0,0,160,160,160,248,168,168,184,4,7,7,
6,0,0,224,64,112,80,80,80,80,5,8,8,6,0,0,
16,32,136,144,160,224,144,136,5,8,8,6,0,0,64,32,
136,152,168,200,136,136,5,9,9,6,0,255,80,32,136,136,
136,80,32,32,32,5,8,8,6,0,255,136,136,136,136,136,
136,248,32,5,7,7,6,0,0,112,136,136,248,136,136,136,
5,7,7,6,0,0,248,128,128,240,136,136,240,5,7,7,
6,0,0,240,136,136,240,136,136,240,5,7,7,6,0,0,
248,136,128,128,128,128,128,5,8,8,6,0,255,120,40,40,
40,72,136,248,136,5,7,7,6,0,0,248,128,128,240,128,
128,248,5,7,7,6,0,0,168,168,168,112,168,168,168,5,
7,7,6,0,0,240,8,8,112,8,8,240,5,7,7,6,
0,0,136,136,152,168,200,136,136,5,8,8,6,0,0,80,
32,136,152,168,168,200,136,5,7,7,6,0,0,136,144,160,
192,160,144,136,5,7,7,6,0,0,120,40,40,40,40,168,
72,5,7,7,6,0,0,136,216,168,136,136,136,136,5,7,
7,6,0,0,136,136,136,248,136,136,136,5,7,7,6,0,
0,112,136,136,136,136,136,112,5,7,7,6,0,0,248,136,
136,136,136,136,136,5,7,7,6,0,0,240,136,136,240,128,
128,128,5,7,7,6,0,0,112,136,128,128,128,136,112,5,
7,7,6,0,0,248,32,32,32,32,32,32,5,7,7,6,
0,0,136,136,136,80,32,64,128,5,7,7,6,0,0,32,
112,168,168,168,112,32,5,7,7,6,0,0,136,136,80,32,
80,136,136,5,8,8,6,0,255,136,136,136,136,136,136,248,
8,5,7,7,6,0,0,136,136,136,152,104,8,8,5,7,
7,6,0,0,168,168,168,168,168,168,248,5,8,8,6,0,
255,168,168,168,168,168,168,248,8,5,7,7,6,0,0,192,
64,64,112,72,72,112,5,7,7,6,0,0,136,136,136,200,
168,168,200,5,7,7,6,0,0,128,128,128,240,136,136,240,
5,7,7,6,0,0,112,136,8,56,8,136,112,5,7,7,
6,0,0,144,168,168,232,168,168,144,5,7,7,6,0,0,
120,136,136,120,40,72,136,5,5,5,6,0,0,112,8,120,
136,120,5,7,7,6,0,0,24,96,128,240,136,136,112,4,
5,5,6,0,0,224,144,224,144,224,5,5,5,6,0,0,
248,136,128,128,128,5,6,6,6,0,255,120,40,72,136,248,
136,5,5,5,6,0,0,112,136,248,128,112,5,5,5,6,
0,0,168,168,112,168,168,5,5,5,6,0,0,240,8,48,
8,240,5,5,5,6,0,0,136,152,168,200,136,5,7,7,
6,0,0,80,32,136,152,168,200,136,4,5,5,6,0,0,
144,160,192,160,144,5,5,5,6,0,0,248,40,40,168,72,
5,5,5,6,0,0,136,216,168,136,136,5,5,5,6,0,
0,136,136,248,136,136,5,5,5,6,0,0,112,136,136,136,
112,5,5,5,6,0,0,248,136,136,136,136,5,6,6,6,
0,255,240,136,136,240,128,128,5,5,5,6,0,0,112,128,
128,136,112,5,5,5,6,0,0,248,32,32,32,32,5,6,
6,6,0,255,136,136,136,120,8,112,5,6,6,6,0,0,
32,112,168,168,112,32,5,5,5,6,0,0,136,80,32,80,
136,5,6,6,6,0,255,136,136,136,136,248,8,5,5,5,
6,0,0,136,136,248,8,8,5,5,5,6,0,0,168,168,
168,168,248,5,6,6,6,0,255,168,168,168,168,248,8,5,
5,5,6,0,0,192,64,112,72,112,5,5,5,6,0,0,
136,136,200,168,200,3,5,5,6,1,0,128,128,192,160,192,
5,5,5,6,0,0,112,136,56,136,112,5,5,5,6,0,
0,144,168,232,168,144,5,5,5,6,0,0,120,136,120,40,
72,5,8,8,6,0,0,64,32,0,112,136,248,128,112,5,
7,7,6,0,0,80,0,112,136,248,128,112,5,9,9,6,
0,255,64,224,64,64,120,72,72,72,16,5,8,8,6,0,
0,16,32,0,248,136,128,128,128,5,5,5,6,0,0,112,
136,96,136,112,5,5,5,6,0,0,112,128,112,8,240,1,
7,7,6,2,0,128,0,128,128,128,128,128,3,7,7,6,
1,0,160,0,64,64,64,64,64,3,8,8,6,1,255,32,
0,32,32,32,32,160,64,5,5,5,6,0,0,160,160,184,
168,184,5,5,5,6,0,0,160,160,248,168,184,5,6,6,
6,0,0,64,224,64,120,72,72,4,8,8,6,0,0,16,
32,0,144,160,192,160,144,5,8,8,6,0,0,64,32,0,
136,152,168,200,136,5,9,9,6,0,255,80,32,0,136,136,
136,120,8,112,5,6,6,6,0,255,136,136,136,136,248,32
};
0, 6, 9, 0, 254, 7, 1, 145, 3, 32, 32, 255, 255, 8, 255, 7,
255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
64, 152, 24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104,
2, 3, 3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32,
64, 128, 128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32,
32, 64, 128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5,
5, 6, 0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192,
64, 128, 5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192,
192, 5, 5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6,
0, 0, 112, 136, 152, 168, 200, 136, 112, 3, 7, 7, 6, 1, 0, 64,
192, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112,
128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240,
5, 7, 7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7,
6, 0, 0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0,
48, 64, 128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16,
32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 16, 96, 2, 5,
5, 6, 2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192,
192, 0, 192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64,
32, 16, 5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 1,
0, 128, 64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136,
8, 16, 32, 0, 32, 5, 6, 6, 6, 0, 0, 112, 136, 8, 104, 168,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5, 7,
7, 6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6, 0,
0, 112, 136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 224, 144,
136, 136, 136, 144, 224, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128,
128, 248, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128, 5,
7, 7, 6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7, 6,
0, 0, 136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0, 128,
128, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16, 16,
16, 144, 96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144, 136,
5, 7, 7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7, 7,
6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0,
136, 136, 200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136, 136,
136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128, 128,
128, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5, 7,
7, 6, 0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6, 0,
0, 120, 128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248, 32,
32, 32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136,
136, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32, 5,
7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7, 6,
0, 0, 136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0, 136,
136, 136, 80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16, 32,
64, 128, 248, 3, 7, 7, 6, 1, 0, 224, 128, 128, 128, 128, 128, 224,
5, 5, 5, 6, 0, 1, 128, 64, 32, 16, 8, 3, 7, 7, 6, 1,
0, 224, 32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4, 32, 80,
136, 5, 1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5, 128, 64,
5, 5, 5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7, 6, 0,
0, 128, 128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0, 112, 128,
128, 136, 112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136, 136, 120,
5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7, 6, 0,
0, 48, 72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255, 112, 136,
136, 120, 8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200, 136, 136,
136, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 3, 8,
8, 6, 1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7, 7, 6,
0, 0, 128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1, 0, 192,
64, 64, 64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168, 168, 168,
168, 5, 5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5, 5, 6,
0, 0, 112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240, 136, 136,
240, 128, 128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8, 8, 5,
5, 5, 6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6, 0, 0,
112, 128, 112, 8, 240, 5, 7, 7, 6, 0, 0, 64, 64, 224, 64, 64,
72, 48, 5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5, 5, 5,
6, 0, 0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0, 136, 136,
168, 168, 80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136, 5, 6,
6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6, 0, 0,
248, 16, 32, 64, 248, 3, 7, 7, 6, 1, 0, 32, 64, 64, 128, 64,
64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128, 128, 3,
7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 2, 2, 6,
0, 3, 104, 144, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 5, 8, 8, 6, 0, 0,
64, 248, 128, 128, 240, 128, 128, 248, 5, 8, 8, 6, 0, 0, 80, 248,
128, 128, 240, 128, 128, 248, 5, 7, 7, 6, 0, 0, 224, 64, 64, 112,
72, 72, 112, 5, 8, 8, 6, 0, 0, 16, 32, 248, 136, 128, 128, 128,
128, 5, 7, 7, 6, 0, 0, 48, 72, 128, 224, 128, 72, 48, 5, 7,
7, 6, 0, 0, 112, 136, 128, 112, 8, 136, 112, 3, 7, 7, 6, 1,
0, 224, 64, 64, 64, 64, 64, 224, 3, 8, 8, 6, 1, 0, 160, 0,
224, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 56, 16, 16, 16,
16, 144, 96, 5, 7, 7, 6, 0, 0, 160, 160, 160, 184, 168, 168, 184,
5, 7, 7, 6, 0, 0, 160, 160, 160, 248, 168, 168, 184, 4, 7, 7,
6, 0, 0, 224, 64, 112, 80, 80, 80, 80, 5, 8, 8, 6, 0, 0,
16, 32, 136, 144, 160, 224, 144, 136, 5, 8, 8, 6, 0, 0, 64, 32,
136, 152, 168, 200, 136, 136, 5, 9, 9, 6, 0, 255, 80, 32, 136, 136,
136, 80, 32, 32, 32, 5, 8, 8, 6, 0, 255, 136, 136, 136, 136, 136,
136, 248, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136,
5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 136, 136, 240, 5, 7, 7,
6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6, 0, 0,
248, 136, 128, 128, 128, 128, 128, 5, 8, 8, 6, 0, 255, 120, 40, 40,
40, 72, 136, 248, 136, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128,
128, 248, 5, 7, 7, 6, 0, 0, 168, 168, 168, 112, 168, 168, 168, 5,
7, 7, 6, 0, 0, 240, 8, 8, 112, 8, 8, 240, 5, 7, 7, 6,
0, 0, 136, 136, 152, 168, 200, 136, 136, 5, 8, 8, 6, 0, 0, 80,
32, 136, 152, 168, 168, 200, 136, 5, 7, 7, 6, 0, 0, 136, 144, 160,
192, 160, 144, 136, 5, 7, 7, 6, 0, 0, 120, 40, 40, 40, 40, 168,
72, 5, 7, 7, 6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7,
7, 6, 0, 0, 136, 136, 136, 248, 136, 136, 136, 5, 7, 7, 6, 0,
0, 112, 136, 136, 136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 136,
136, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128,
128, 128, 5, 7, 7, 6, 0, 0, 112, 136, 128, 128, 128, 136, 112, 5,
7, 7, 6, 0, 0, 248, 32, 32, 32, 32, 32, 32, 5, 7, 7, 6,
0, 0, 136, 136, 136, 80, 32, 64, 128, 5, 7, 7, 6, 0, 0, 32,
112, 168, 168, 168, 112, 32, 5, 7, 7, 6, 0, 0, 136, 136, 80, 32,
80, 136, 136, 5, 8, 8, 6, 0, 255, 136, 136, 136, 136, 136, 136, 248,
8, 5, 7, 7, 6, 0, 0, 136, 136, 136, 152, 104, 8, 8, 5, 7,
7, 6, 0, 0, 168, 168, 168, 168, 168, 168, 248, 5, 8, 8, 6, 0,
255, 168, 168, 168, 168, 168, 168, 248, 8, 5, 7, 7, 6, 0, 0, 192,
64, 64, 112, 72, 72, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 200,
168, 168, 200, 5, 7, 7, 6, 0, 0, 128, 128, 128, 240, 136, 136, 240,
5, 7, 7, 6, 0, 0, 112, 136, 8, 56, 8, 136, 112, 5, 7, 7,
6, 0, 0, 144, 168, 168, 232, 168, 168, 144, 5, 7, 7, 6, 0, 0,
120, 136, 136, 120, 40, 72, 136, 5, 5, 5, 6, 0, 0, 112, 8, 120,
136, 120, 5, 7, 7, 6, 0, 0, 24, 96, 128, 240, 136, 136, 112, 4,
5, 5, 6, 0, 0, 224, 144, 224, 144, 224, 5, 5, 5, 6, 0, 0,
248, 136, 128, 128, 128, 5, 6, 6, 6, 0, 255, 120, 40, 72, 136, 248,
136, 5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 5, 5, 6,
0, 0, 168, 168, 112, 168, 168, 5, 5, 5, 6, 0, 0, 240, 8, 48,
8, 240, 5, 5, 5, 6, 0, 0, 136, 152, 168, 200, 136, 5, 7, 7,
6, 0, 0, 80, 32, 136, 152, 168, 200, 136, 4, 5, 5, 6, 0, 0,
144, 160, 192, 160, 144, 5, 5, 5, 6, 0, 0, 248, 40, 40, 168, 72,
5, 5, 5, 6, 0, 0, 136, 216, 168, 136, 136, 5, 5, 5, 6, 0,
0, 136, 136, 248, 136, 136, 5, 5, 5, 6, 0, 0, 112, 136, 136, 136,
112, 5, 5, 5, 6, 0, 0, 248, 136, 136, 136, 136, 5, 6, 6, 6,
0, 255, 240, 136, 136, 240, 128, 128, 5, 5, 5, 6, 0, 0, 112, 128,
128, 136, 112, 5, 5, 5, 6, 0, 0, 248, 32, 32, 32, 32, 5, 6,
6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 6, 6, 6, 0, 0,
32, 112, 168, 168, 112, 32, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80,
136, 5, 6, 6, 6, 0, 255, 136, 136, 136, 136, 248, 8, 5, 5, 5,
6, 0, 0, 136, 136, 248, 8, 8, 5, 5, 5, 6, 0, 0, 168, 168,
168, 168, 248, 5, 6, 6, 6, 0, 255, 168, 168, 168, 168, 248, 8, 5,
5, 5, 6, 0, 0, 192, 64, 112, 72, 112, 5, 5, 5, 6, 0, 0,
136, 136, 200, 168, 200, 3, 5, 5, 6, 1, 0, 128, 128, 192, 160, 192,
5, 5, 5, 6, 0, 0, 112, 136, 56, 136, 112, 5, 5, 5, 6, 0,
0, 144, 168, 232, 168, 144, 5, 5, 5, 6, 0, 0, 120, 136, 120, 40,
72, 5, 8, 8, 6, 0, 0, 64, 32, 0, 112, 136, 248, 128, 112, 5,
7, 7, 6, 0, 0, 80, 0, 112, 136, 248, 128, 112, 5, 9, 9, 6,
0, 255, 64, 224, 64, 64, 120, 72, 72, 72, 16, 5, 8, 8, 6, 0,
0, 16, 32, 0, 248, 136, 128, 128, 128, 5, 5, 5, 6, 0, 0, 112,
136, 96, 136, 112, 5, 5, 5, 6, 0, 0, 112, 128, 112, 8, 240, 1,
7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 3, 7, 7, 6,
1, 0, 160, 0, 64, 64, 64, 64, 64, 3, 8, 8, 6, 1, 255, 32,
0, 32, 32, 32, 32, 160, 64, 5, 5, 5, 6, 0, 0, 160, 160, 184,
168, 184, 5, 5, 5, 6, 0, 0, 160, 160, 248, 168, 184, 5, 6, 6,
6, 0, 0, 64, 224, 64, 120, 72, 72, 4, 8, 8, 6, 0, 0, 16,
32, 0, 144, 160, 192, 160, 144, 5, 8, 8, 6, 0, 0, 64, 32, 0,
136, 152, 168, 200, 136, 5, 9, 9, 6, 0, 255, 80, 32, 0, 136, 136,
136, 120, 8, 112, 5, 6, 6, 6, 0, 255, 136, 136, 136, 136, 248, 32
};

View File

@ -11,260 +11,261 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t ISO10646_CN[4105] U8G_SECTION(".progmem.ISO10646_CN") = {
0,12,11,0,254,7,1,146,3,33,32,255,255,10,255,7,
255,0,0,0,6,0,10,1,7,7,6,2,0,128,128,128,
128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
0,0,112,136,152,168,200,136,112,3,7,7,6,1,0,64,
192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
112,128,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
112,5,7,7,6,0,0,112,136,136,120,8,8,112,2,5,
5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,0,
0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
8,16,32,0,32,5,7,7,6,0,0,112,136,8,104,168,
168,112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,
7,7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,
0,0,112,136,128,128,128,136,112,5,7,7,6,0,0,240,
136,136,136,136,136,240,5,7,7,6,0,0,248,128,128,240,
128,128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,
5,7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,
6,0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,
128,128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,
16,16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,
136,5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,
7,6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,
0,136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,
136,136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,
128,128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,
7,7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,
0,0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,
32,32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,
136,136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,
5,7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,
6,0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,
136,136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,
32,64,128,248,3,7,7,6,0,0,224,128,128,128,128,128,
224,5,5,5,6,0,1,128,64,32,16,8,3,7,7,6,
0,0,224,32,32,32,32,32,224,5,3,3,6,0,4,32,
80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,128,
64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,6,
0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,112,
128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,136,
120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,6,
0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,112,
136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,136,
136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,3,
8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,7,
6,1,0,128,128,144,160,192,160,144,3,7,7,6,1,0,
192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,168,
168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,5,
6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,136,
136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,8,
5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,0,
0,112,128,112,8,240,4,7,7,6,0,0,64,64,224,64,
64,64,48,5,5,5,6,0,0,136,136,136,152,104,5,5,
5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,136,
136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,5,
6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,0,
0,248,16,32,64,248,3,7,7,6,1,0,32,64,64,128,
64,64,32,1,7,7,6,2,0,128,128,128,128,128,128,128,
3,7,7,6,1,0,128,64,64,32,64,64,128,5,2,2,
6,0,3,104,144,0,0,0,6,0,10,0,0,0,12,0,
10,0,0,0,12,0,10,0,0,0,12,0,10,0,0,0,
12,0,10,0,0,0,12,0,10,0,0,0,12,0,10,0,
0,0,12,0,10,0,0,0,12,0,10,0,0,0,12,0,
10,0,0,0,12,0,10,0,0,0,12,0,10,0,0,0,
12,0,10,0,0,0,12,0,10,0,0,0,12,0,10,0,
0,0,12,0,10,0,0,0,12,0,10,0,0,0,12,0,
10,0,0,0,12,0,10,0,0,0,12,0,10,0,0,0,
12,0,10,0,0,0,12,0,10,0,0,0,12,0,10,0,
0,0,12,0,10,0,0,0,12,0,10,0,0,0,12,0,
10,0,0,0,12,0,10,0,0,0,12,0,10,0,0,0,
12,0,10,0,0,0,12,0,10,11,11,22,12,0,255,255,
224,2,0,2,0,4,0,13,0,20,128,36,64,196,32,4,
0,4,0,4,0,11,11,22,12,0,255,249,0,138,0,171,
224,172,64,170,64,170,64,170,64,170,128,33,0,82,128,140,
96,11,11,22,12,0,255,36,0,36,0,63,128,68,0,132,
0,4,0,255,224,10,0,17,0,32,128,192,96,11,11,22,
12,0,255,36,0,36,0,63,192,68,0,4,0,255,224,9,
0,9,0,17,32,33,32,64,224,11,11,22,12,0,255,32,
0,61,224,81,32,145,32,17,32,255,32,17,32,41,32,37,
224,69,32,128,0,11,11,22,12,0,255,32,128,127,192,8,
64,255,224,17,0,32,128,95,64,128,32,63,128,0,0,127,
192,11,11,22,12,0,255,34,64,71,224,148,128,228,128,47,
224,68,128,244,128,7,224,52,128,196,128,7,224,11,11,22,
12,0,255,4,128,143,224,73,0,25,0,47,192,9,0,9,
0,47,192,73,0,137,0,15,224,11,11,22,12,0,255,16,
0,63,128,81,0,14,0,49,128,192,96,63,128,36,128,63,
128,36,128,63,128,11,11,22,12,0,255,34,128,250,64,7,
224,250,128,138,128,138,128,250,128,34,128,178,128,170,160,100,
224,11,11,22,12,0,255,34,32,71,64,146,128,239,224,34,
0,71,192,236,64,7,192,52,64,199,192,4,64,11,11,22,
12,0,255,8,0,15,192,8,0,8,0,255,224,8,0,14,
0,9,128,8,64,8,0,8,0,10,11,22,12,0,255,255,
128,0,128,0,128,128,128,128,128,255,128,128,0,128,0,128,
64,128,64,127,192,11,11,22,12,0,255,71,192,65,0,239,
224,65,0,69,0,105,96,201,32,77,96,73,32,79,224,200,
32,11,11,22,12,0,255,8,0,4,0,4,0,10,0,10,
0,10,0,17,0,17,0,32,128,64,64,128,32,11,11,22,
12,0,255,34,64,34,0,247,224,34,0,35,224,53,32,229,
32,37,64,40,128,41,64,114,32,11,10,20,12,0,0,68,
64,68,64,68,64,127,192,4,0,4,0,132,32,132,32,132,
32,255,224,11,11,22,12,0,255,4,0,0,0,127,192,4,
0,4,0,4,0,127,192,4,0,4,0,4,0,255,224,11,
11,22,12,0,255,255,224,17,0,1,192,254,0,72,128,37,
0,4,0,255,224,21,0,36,128,196,96,11,11,22,12,0,
255,17,0,127,192,68,64,127,192,68,64,127,192,4,0,255,
224,4,0,4,0,4,0,9,11,22,12,0,255,16,0,255,
128,128,128,128,128,255,128,128,128,128,128,255,128,128,128,128,
128,255,128,11,11,22,12,0,255,113,0,1,0,3,224,249,
32,33,32,65,32,81,32,137,32,250,32,2,32,4,192,11,
11,22,12,0,255,127,192,17,0,17,0,17,0,17,0,255,
224,17,0,17,0,33,0,33,0,65,0,11,11,22,12,0,
255,33,0,34,0,244,64,87,224,80,32,87,192,148,64,84,
64,36,64,87,192,148,64,11,11,22,12,0,255,17,0,10,
0,127,192,4,0,4,0,255,224,4,0,10,0,17,0,32,
128,192,96,10,11,22,12,0,255,95,192,0,64,132,64,132,
64,191,64,132,64,140,64,148,64,164,64,140,64,129,192,11,
11,22,12,0,255,36,0,39,192,36,0,36,0,255,224,0,
0,20,64,36,128,71,0,12,0,112,0,11,11,22,12,0,
255,36,128,4,128,15,192,228,128,36,128,63,224,36,128,36,
128,40,128,80,0,143,224,11,11,22,12,0,255,8,0,8,
0,255,128,136,128,136,128,255,128,136,128,136,128,255,160,136,
32,7,224,11,11,22,12,0,255,39,128,36,128,244,128,36,
128,116,128,108,128,164,128,36,128,36,160,40,160,48,96,10,
11,22,12,0,255,255,192,128,64,128,64,158,64,146,64,146,
64,158,64,128,64,128,64,255,192,128,64,11,11,22,12,0,
255,127,192,68,0,95,192,80,64,95,192,80,64,95,192,66,
0,74,128,82,64,166,32,11,11,22,12,0,255,4,0,7,
224,4,0,127,192,64,64,64,64,64,64,127,192,0,0,82,
64,137,32,11,11,22,12,0,255,71,128,36,128,4,128,4,
128,232,96,32,0,47,192,36,64,34,128,49,0,38,192,11,
11,22,12,0,255,127,192,74,64,127,192,4,0,255,224,4,
0,63,128,32,128,36,128,36,128,255,224,11,11,22,12,0,
255,34,0,79,224,72,32,79,224,200,0,79,224,74,160,90,
160,111,224,74,160,72,96,11,11,22,12,0,255,243,192,36,
64,42,128,241,0,34,128,101,224,114,32,165,64,32,128,35,
0,44,0,11,11,22,12,0,255,4,0,255,224,128,32,0,
0,255,224,4,0,36,0,39,192,36,0,84,0,143,224,11,
11,22,12,0,255,115,224,16,128,81,0,35,224,250,32,42,
160,34,160,34,160,32,128,33,64,98,32,11,11,22,12,0,
255,34,0,247,128,34,128,54,128,226,160,37,160,36,96,104,
32,0,0,82,64,137,32,11,11,22,12,0,255,115,192,66,
0,66,0,123,224,74,64,74,64,122,64,74,64,66,64,68,
64,136,64,11,11,22,12,0,255,8,0,255,224,8,0,31,
192,48,64,95,192,144,64,31,192,16,64,16,64,16,192,11,
11,22,12,0,255,2,0,127,224,66,0,66,0,95,192,66,
0,71,0,74,128,82,64,98,32,130,0,11,11,22,12,0,
255,243,192,150,64,145,128,166,96,161,0,151,192,145,0,149,
0,231,224,129,0,129,0,11,11,22,12,0,255,15,128,136,
128,79,128,8,128,143,128,64,0,31,192,53,64,85,64,149,
64,63,224,11,11,22,12,0,255,39,224,32,128,248,128,32,
128,32,128,56,128,224,128,32,128,32,128,32,128,97,128,11,
11,22,12,0,255,31,224,145,0,87,192,20,64,23,192,148,
64,87,192,17,0,85,64,153,32,35,0,11,11,22,12,0,
255,32,128,39,224,242,64,33,128,34,64,52,32,226,64,34,
64,34,64,34,64,100,64,11,11,22,12,0,255,65,0,65,
0,79,224,233,32,73,32,73,32,111,224,201,32,73,32,73,
32,207,224,11,11,22,12,0,255,33,0,241,0,79,224,169,
32,249,32,47,224,57,32,233,32,41,32,47,224,40,32,11,
11,22,12,0,255,143,224,73,32,9,32,203,160,73,32,79,
224,72,32,75,160,74,160,107,160,80,224,11,11,22,12,0,
255,127,192,4,0,68,64,36,64,36,128,4,0,255,224,4,
0,4,0,4,0,4,0,11,11,22,12,0,255,130,0,66,
0,31,224,194,0,95,192,82,64,95,192,71,0,74,128,82,
64,191,224,11,11,22,12,0,255,4,0,127,224,72,128,127,
224,72,128,79,128,64,0,95,192,72,64,71,128,152,96,11,
11,22,12,0,255,1,0,239,224,161,0,164,64,175,224,164,
64,175,224,169,32,233,32,2,128,12,96,11,11,22,12,0,
255,20,192,246,160,188,96,167,128,168,128,191,224,169,32,239,
224,9,32,15,224,9,32,11,11,22,12,0,255,127,128,64,
128,66,128,98,128,84,128,72,128,72,128,84,160,98,160,64,
96,128,32,11,11,22,12,0,255,4,0,127,224,64,32,127,
224,64,0,125,224,84,32,76,160,84,96,100,160,141,96,11,
11,22,12,0,255,130,0,95,224,4,0,8,64,159,224,64,
32,10,128,10,128,74,160,146,160,34,96,11,11,22,12,0,
255,65,0,79,224,232,32,66,128,68,64,104,32,199,192,65,
0,65,0,65,0,207,224,11,11,22,12,0,255,80,32,125,
32,145,32,255,32,17,32,125,32,85,32,85,32,84,32,92,
32,16,224,11,11,22,12,0,255,63,128,32,128,63,128,32,
128,255,224,72,0,123,192,73,64,121,64,72,128,251,96,11,
11,22,12,0,255,4,0,4,0,4,0,36,128,36,64,68,
64,68,32,132,32,4,0,4,0,28,0,11,11,22,12,0,
255,4,0,4,0,4,0,255,224,4,0,10,0,10,0,17,
0,17,0,32,128,192,96,9,10,20,10,0,0,136,128,73,
0,8,0,255,128,0,128,0,128,127,128,0,128,0,128,255,
128,11,11,22,12,0,255,33,0,18,0,255,224,0,0,120,
128,74,128,122,128,74,128,122,128,72,128,89,128,11,11,22,
12,0,255,39,192,0,0,0,0,239,224,33,0,34,0,36,
64,47,224,32,32,80,0,143,224,11,11,22,12,0,255,32,
128,39,0,249,0,33,192,119,0,33,0,249,224,39,0,113,
32,169,32,32,224,11,11,22,12,0,255,16,64,16,64,253,
224,16,64,56,192,53,64,82,64,148,64,16,64,16,64,16,
192,11,11,22,12,0,255,0,64,248,64,11,224,8,64,136,
64,82,64,81,64,33,64,80,64,72,64,137,192,10,11,22,
12,0,255,132,0,132,64,132,128,245,0,134,0,132,0,132,
0,148,0,164,64,196,64,131,192,11,11,22,12,0,255,17,
32,125,0,17,0,255,224,41,0,253,64,73,64,124,128,8,
160,253,96,10,32,11,11,22,12,0,255,23,192,36,64,36,
64,103,192,161,0,47,224,33,0,35,128,37,64,41,32,33,
0,11,11,22,12,0,255,8,0,255,224,16,0,39,192,32,
128,97,0,175,224,33,0,33,0,33,0,35,0,11,11,22,
12,0,255,36,0,47,224,180,0,164,128,164,160,170,192,42,
128,40,128,41,64,50,64,36,32,11,11,22,12,0,255,127,
224,128,0,63,192,32,64,63,192,16,0,31,192,16,64,40,
128,71,0,56,224,11,11,22,12,0,255,127,224,64,0,64,
0,64,0,64,0,64,0,64,0,64,0,64,0,64,0,128,
0,11,11,22,12,0,255,255,224,4,0,127,192,68,64,127,
192,68,64,127,192,68,0,36,0,24,0,231,224,11,11,22,
12,0,255,17,224,253,0,69,0,41,224,253,64,17,64,125,
64,17,64,85,64,146,64,52,64,11,11,22,12,0,255,33,
0,95,224,64,0,207,192,64,0,79,192,64,0,79,192,72,
64,79,192,72,64,11,11,22,12,0,255,4,0,127,192,64,
64,127,192,64,64,127,192,64,64,127,192,4,64,82,32,191,
160,11,11,22,12,0,255,127,192,68,64,127,192,68,64,127,
192,4,0,27,0,224,224,17,0,17,0,97,0,11,11,22,
12,0,255,255,224,4,0,8,0,127,224,73,32,79,32,73,
32,79,32,73,32,73,32,127,224,11,11,22,12,0,255,253,
224,86,64,121,64,56,128,85,64,146,32,255,224,4,0,39,
192,36,0,255,224,11,11,22,12,0,255,251,128,82,0,123,
224,18,64,250,64,20,64,63,128,32,128,63,128,32,128,63,
128,11,11,22,12,0,255,31,224,32,0,39,192,100,64,167,
192,32,0,47,224,40,32,39,192,33,0,35,0,11,11,22,
12,0,255,243,224,130,32,130,32,250,32,130,32,130,32,138,
32,178,32,194,224,2,0,2,0,11,11,22,12,0,255,36,
128,70,160,149,192,228,128,39,224,68,128,245,192,6,160,52,
128,196,128,7,224,11,11,22,12,0,255,39,192,65,0,135,
224,224,32,34,128,69,128,242,128,15,224,48,128,193,64,2,
32,11,11,22,12,0,255,2,0,2,0,34,0,35,192,34,
0,34,0,34,0,34,0,34,0,34,0,255,224,9,11,22,
12,0,255,8,0,8,0,255,128,136,128,136,128,136,128,255,
128,136,128,136,128,136,128,255,128,11,11,22,12,0,255,33,
0,83,160,65,0,247,224,81,0,83,192,86,64,83,192,90,
64,83,192,66,64,11,11,22,12,0,255,127,192,4,0,4,
0,4,0,255,224,10,0,10,0,18,0,34,32,66,32,129,
224,11,11,22,12,0,255,17,0,33,0,47,224,97,0,163,
128,35,128,37,64,37,64,41,32,33,0,33,0,11,11,22,
12,0,255,247,224,148,32,244,32,151,224,148,128,244,128,151,
224,148,128,244,160,150,96,4,32,11,11,22,12,0,255,123,
224,148,128,4,0,127,192,4,0,255,224,1,0,255,224,33,
0,17,0,7,0,11,11,22,12,0,255,33,0,71,192,145,
0,47,224,96,128,175,224,32,128,36,128,34,128,32,128,35,
128,11,11,22,12,0,255,39,192,36,64,247,192,46,224,42,
160,62,224,225,0,47,224,35,128,37,64,105,32,11,11,22,
12,0,255,20,0,39,224,42,0,98,0,163,192,34,0,34,
0,35,224,34,0,34,0,34,0};
0, 12, 11, 0, 254, 7, 1, 146, 3, 33, 32, 255, 255, 10, 255, 7,
255, 0, 0, 0, 6, 0, 10, 1, 7, 7, 6, 2, 0, 128, 128, 128,
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
64, 152, 24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104,
2, 3, 3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32,
64, 128, 128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32,
32, 64, 128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5,
5, 6, 0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192,
64, 128, 5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192,
192, 5, 5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6,
0, 0, 112, 136, 152, 168, 200, 136, 112, 3, 7, 7, 6, 1, 0, 64,
192, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112,
128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240,
5, 7, 7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7,
6, 0, 0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0,
112, 128, 128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16,
32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 8, 112, 2, 5,
5, 6, 2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192,
192, 0, 192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64,
32, 16, 5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 0,
0, 128, 64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136,
8, 16, 32, 0, 32, 5, 7, 7, 6, 0, 0, 112, 136, 8, 104, 168,
168, 112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5,
7, 7, 6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6,
0, 0, 112, 136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 240,
136, 136, 136, 136, 136, 240, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240,
128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128,
5, 7, 7, 6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7,
6, 0, 0, 136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0,
128, 128, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16,
16, 16, 144, 96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144,
136, 5, 7, 7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7,
7, 6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0,
0, 136, 136, 200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136,
136, 136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128,
128, 128, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5,
7, 7, 6, 0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6,
0, 0, 120, 128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248,
32, 32, 32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136,
136, 136, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32,
5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7,
6, 0, 0, 136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0,
136, 136, 136, 80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16,
32, 64, 128, 248, 3, 7, 7, 6, 0, 0, 224, 128, 128, 128, 128, 128,
224, 5, 5, 5, 6, 0, 1, 128, 64, 32, 16, 8, 3, 7, 7, 6,
0, 0, 224, 32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4, 32,
80, 136, 5, 1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5, 128,
64, 5, 5, 5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7, 6,
0, 0, 128, 128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0, 112,
128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136, 136,
120, 5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7, 6,
0, 0, 48, 72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255, 112,
136, 136, 120, 8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200, 136,
136, 136, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 3,
8, 8, 6, 1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7, 7,
6, 1, 0, 128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1, 0,
192, 64, 64, 64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168, 168,
168, 168, 5, 5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5, 5,
6, 0, 0, 112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240, 136,
136, 240, 128, 128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8, 8,
5, 5, 5, 6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6, 0,
0, 112, 128, 112, 8, 240, 4, 7, 7, 6, 0, 0, 64, 64, 224, 64,
64, 64, 48, 5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5, 5,
5, 6, 0, 0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0, 136,
136, 168, 168, 80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136, 5,
6, 6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6, 0,
0, 248, 16, 32, 64, 248, 3, 7, 7, 6, 1, 0, 32, 64, 64, 128,
64, 64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128, 128,
3, 7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 2, 2,
6, 0, 3, 104, 144, 0, 0, 0, 6, 0, 10, 0, 0, 0, 12, 0,
10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0,
12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0,
0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0,
10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0,
12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0,
0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0,
10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0,
12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0,
0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0,
10, 0, 0, 0, 12, 0, 10, 0, 0, 0, 12, 0, 10, 0, 0, 0,
12, 0, 10, 0, 0, 0, 12, 0, 10, 11, 11, 22, 12, 0, 255, 255,
224, 2, 0, 2, 0, 4, 0, 13, 0, 20, 128, 36, 64, 196, 32, 4,
0, 4, 0, 4, 0, 11, 11, 22, 12, 0, 255, 249, 0, 138, 0, 171,
224, 172, 64, 170, 64, 170, 64, 170, 64, 170, 128, 33, 0, 82, 128, 140,
96, 11, 11, 22, 12, 0, 255, 36, 0, 36, 0, 63, 128, 68, 0, 132,
0, 4, 0, 255, 224, 10, 0, 17, 0, 32, 128, 192, 96, 11, 11, 22,
12, 0, 255, 36, 0, 36, 0, 63, 192, 68, 0, 4, 0, 255, 224, 9,
0, 9, 0, 17, 32, 33, 32, 64, 224, 11, 11, 22, 12, 0, 255, 32,
0, 61, 224, 81, 32, 145, 32, 17, 32, 255, 32, 17, 32, 41, 32, 37,
224, 69, 32, 128, 0, 11, 11, 22, 12, 0, 255, 32, 128, 127, 192, 8,
64, 255, 224, 17, 0, 32, 128, 95, 64, 128, 32, 63, 128, 0, 0, 127,
192, 11, 11, 22, 12, 0, 255, 34, 64, 71, 224, 148, 128, 228, 128, 47,
224, 68, 128, 244, 128, 7, 224, 52, 128, 196, 128, 7, 224, 11, 11, 22,
12, 0, 255, 4, 128, 143, 224, 73, 0, 25, 0, 47, 192, 9, 0, 9,
0, 47, 192, 73, 0, 137, 0, 15, 224, 11, 11, 22, 12, 0, 255, 16,
0, 63, 128, 81, 0, 14, 0, 49, 128, 192, 96, 63, 128, 36, 128, 63,
128, 36, 128, 63, 128, 11, 11, 22, 12, 0, 255, 34, 128, 250, 64, 7,
224, 250, 128, 138, 128, 138, 128, 250, 128, 34, 128, 178, 128, 170, 160, 100,
224, 11, 11, 22, 12, 0, 255, 34, 32, 71, 64, 146, 128, 239, 224, 34,
0, 71, 192, 236, 64, 7, 192, 52, 64, 199, 192, 4, 64, 11, 11, 22,
12, 0, 255, 8, 0, 15, 192, 8, 0, 8, 0, 255, 224, 8, 0, 14,
0, 9, 128, 8, 64, 8, 0, 8, 0, 10, 11, 22, 12, 0, 255, 255,
128, 0, 128, 0, 128, 128, 128, 128, 128, 255, 128, 128, 0, 128, 0, 128,
64, 128, 64, 127, 192, 11, 11, 22, 12, 0, 255, 71, 192, 65, 0, 239,
224, 65, 0, 69, 0, 105, 96, 201, 32, 77, 96, 73, 32, 79, 224, 200,
32, 11, 11, 22, 12, 0, 255, 8, 0, 4, 0, 4, 0, 10, 0, 10,
0, 10, 0, 17, 0, 17, 0, 32, 128, 64, 64, 128, 32, 11, 11, 22,
12, 0, 255, 34, 64, 34, 0, 247, 224, 34, 0, 35, 224, 53, 32, 229,
32, 37, 64, 40, 128, 41, 64, 114, 32, 11, 10, 20, 12, 0, 0, 68,
64, 68, 64, 68, 64, 127, 192, 4, 0, 4, 0, 132, 32, 132, 32, 132,
32, 255, 224, 11, 11, 22, 12, 0, 255, 4, 0, 0, 0, 127, 192, 4,
0, 4, 0, 4, 0, 127, 192, 4, 0, 4, 0, 4, 0, 255, 224, 11,
11, 22, 12, 0, 255, 255, 224, 17, 0, 1, 192, 254, 0, 72, 128, 37,
0, 4, 0, 255, 224, 21, 0, 36, 128, 196, 96, 11, 11, 22, 12, 0,
255, 17, 0, 127, 192, 68, 64, 127, 192, 68, 64, 127, 192, 4, 0, 255,
224, 4, 0, 4, 0, 4, 0, 9, 11, 22, 12, 0, 255, 16, 0, 255,
128, 128, 128, 128, 128, 255, 128, 128, 128, 128, 128, 255, 128, 128, 128, 128,
128, 255, 128, 11, 11, 22, 12, 0, 255, 113, 0, 1, 0, 3, 224, 249,
32, 33, 32, 65, 32, 81, 32, 137, 32, 250, 32, 2, 32, 4, 192, 11,
11, 22, 12, 0, 255, 127, 192, 17, 0, 17, 0, 17, 0, 17, 0, 255,
224, 17, 0, 17, 0, 33, 0, 33, 0, 65, 0, 11, 11, 22, 12, 0,
255, 33, 0, 34, 0, 244, 64, 87, 224, 80, 32, 87, 192, 148, 64, 84,
64, 36, 64, 87, 192, 148, 64, 11, 11, 22, 12, 0, 255, 17, 0, 10,
0, 127, 192, 4, 0, 4, 0, 255, 224, 4, 0, 10, 0, 17, 0, 32,
128, 192, 96, 10, 11, 22, 12, 0, 255, 95, 192, 0, 64, 132, 64, 132,
64, 191, 64, 132, 64, 140, 64, 148, 64, 164, 64, 140, 64, 129, 192, 11,
11, 22, 12, 0, 255, 36, 0, 39, 192, 36, 0, 36, 0, 255, 224, 0,
0, 20, 64, 36, 128, 71, 0, 12, 0, 112, 0, 11, 11, 22, 12, 0,
255, 36, 128, 4, 128, 15, 192, 228, 128, 36, 128, 63, 224, 36, 128, 36,
128, 40, 128, 80, 0, 143, 224, 11, 11, 22, 12, 0, 255, 8, 0, 8,
0, 255, 128, 136, 128, 136, 128, 255, 128, 136, 128, 136, 128, 255, 160, 136,
32, 7, 224, 11, 11, 22, 12, 0, 255, 39, 128, 36, 128, 244, 128, 36,
128, 116, 128, 108, 128, 164, 128, 36, 128, 36, 160, 40, 160, 48, 96, 10,
11, 22, 12, 0, 255, 255, 192, 128, 64, 128, 64, 158, 64, 146, 64, 146,
64, 158, 64, 128, 64, 128, 64, 255, 192, 128, 64, 11, 11, 22, 12, 0,
255, 127, 192, 68, 0, 95, 192, 80, 64, 95, 192, 80, 64, 95, 192, 66,
0, 74, 128, 82, 64, 166, 32, 11, 11, 22, 12, 0, 255, 4, 0, 7,
224, 4, 0, 127, 192, 64, 64, 64, 64, 64, 64, 127, 192, 0, 0, 82,
64, 137, 32, 11, 11, 22, 12, 0, 255, 71, 128, 36, 128, 4, 128, 4,
128, 232, 96, 32, 0, 47, 192, 36, 64, 34, 128, 49, 0, 38, 192, 11,
11, 22, 12, 0, 255, 127, 192, 74, 64, 127, 192, 4, 0, 255, 224, 4,
0, 63, 128, 32, 128, 36, 128, 36, 128, 255, 224, 11, 11, 22, 12, 0,
255, 34, 0, 79, 224, 72, 32, 79, 224, 200, 0, 79, 224, 74, 160, 90,
160, 111, 224, 74, 160, 72, 96, 11, 11, 22, 12, 0, 255, 243, 192, 36,
64, 42, 128, 241, 0, 34, 128, 101, 224, 114, 32, 165, 64, 32, 128, 35,
0, 44, 0, 11, 11, 22, 12, 0, 255, 4, 0, 255, 224, 128, 32, 0,
0, 255, 224, 4, 0, 36, 0, 39, 192, 36, 0, 84, 0, 143, 224, 11,
11, 22, 12, 0, 255, 115, 224, 16, 128, 81, 0, 35, 224, 250, 32, 42,
160, 34, 160, 34, 160, 32, 128, 33, 64, 98, 32, 11, 11, 22, 12, 0,
255, 34, 0, 247, 128, 34, 128, 54, 128, 226, 160, 37, 160, 36, 96, 104,
32, 0, 0, 82, 64, 137, 32, 11, 11, 22, 12, 0, 255, 115, 192, 66,
0, 66, 0, 123, 224, 74, 64, 74, 64, 122, 64, 74, 64, 66, 64, 68,
64, 136, 64, 11, 11, 22, 12, 0, 255, 8, 0, 255, 224, 8, 0, 31,
192, 48, 64, 95, 192, 144, 64, 31, 192, 16, 64, 16, 64, 16, 192, 11,
11, 22, 12, 0, 255, 2, 0, 127, 224, 66, 0, 66, 0, 95, 192, 66,
0, 71, 0, 74, 128, 82, 64, 98, 32, 130, 0, 11, 11, 22, 12, 0,
255, 243, 192, 150, 64, 145, 128, 166, 96, 161, 0, 151, 192, 145, 0, 149,
0, 231, 224, 129, 0, 129, 0, 11, 11, 22, 12, 0, 255, 15, 128, 136,
128, 79, 128, 8, 128, 143, 128, 64, 0, 31, 192, 53, 64, 85, 64, 149,
64, 63, 224, 11, 11, 22, 12, 0, 255, 39, 224, 32, 128, 248, 128, 32,
128, 32, 128, 56, 128, 224, 128, 32, 128, 32, 128, 32, 128, 97, 128, 11,
11, 22, 12, 0, 255, 31, 224, 145, 0, 87, 192, 20, 64, 23, 192, 148,
64, 87, 192, 17, 0, 85, 64, 153, 32, 35, 0, 11, 11, 22, 12, 0,
255, 32, 128, 39, 224, 242, 64, 33, 128, 34, 64, 52, 32, 226, 64, 34,
64, 34, 64, 34, 64, 100, 64, 11, 11, 22, 12, 0, 255, 65, 0, 65,
0, 79, 224, 233, 32, 73, 32, 73, 32, 111, 224, 201, 32, 73, 32, 73,
32, 207, 224, 11, 11, 22, 12, 0, 255, 33, 0, 241, 0, 79, 224, 169,
32, 249, 32, 47, 224, 57, 32, 233, 32, 41, 32, 47, 224, 40, 32, 11,
11, 22, 12, 0, 255, 143, 224, 73, 32, 9, 32, 203, 160, 73, 32, 79,
224, 72, 32, 75, 160, 74, 160, 107, 160, 80, 224, 11, 11, 22, 12, 0,
255, 127, 192, 4, 0, 68, 64, 36, 64, 36, 128, 4, 0, 255, 224, 4,
0, 4, 0, 4, 0, 4, 0, 11, 11, 22, 12, 0, 255, 130, 0, 66,
0, 31, 224, 194, 0, 95, 192, 82, 64, 95, 192, 71, 0, 74, 128, 82,
64, 191, 224, 11, 11, 22, 12, 0, 255, 4, 0, 127, 224, 72, 128, 127,
224, 72, 128, 79, 128, 64, 0, 95, 192, 72, 64, 71, 128, 152, 96, 11,
11, 22, 12, 0, 255, 1, 0, 239, 224, 161, 0, 164, 64, 175, 224, 164,
64, 175, 224, 169, 32, 233, 32, 2, 128, 12, 96, 11, 11, 22, 12, 0,
255, 20, 192, 246, 160, 188, 96, 167, 128, 168, 128, 191, 224, 169, 32, 239,
224, 9, 32, 15, 224, 9, 32, 11, 11, 22, 12, 0, 255, 127, 128, 64,
128, 66, 128, 98, 128, 84, 128, 72, 128, 72, 128, 84, 160, 98, 160, 64,
96, 128, 32, 11, 11, 22, 12, 0, 255, 4, 0, 127, 224, 64, 32, 127,
224, 64, 0, 125, 224, 84, 32, 76, 160, 84, 96, 100, 160, 141, 96, 11,
11, 22, 12, 0, 255, 130, 0, 95, 224, 4, 0, 8, 64, 159, 224, 64,
32, 10, 128, 10, 128, 74, 160, 146, 160, 34, 96, 11, 11, 22, 12, 0,
255, 65, 0, 79, 224, 232, 32, 66, 128, 68, 64, 104, 32, 199, 192, 65,
0, 65, 0, 65, 0, 207, 224, 11, 11, 22, 12, 0, 255, 80, 32, 125,
32, 145, 32, 255, 32, 17, 32, 125, 32, 85, 32, 85, 32, 84, 32, 92,
32, 16, 224, 11, 11, 22, 12, 0, 255, 63, 128, 32, 128, 63, 128, 32,
128, 255, 224, 72, 0, 123, 192, 73, 64, 121, 64, 72, 128, 251, 96, 11,
11, 22, 12, 0, 255, 4, 0, 4, 0, 4, 0, 36, 128, 36, 64, 68,
64, 68, 32, 132, 32, 4, 0, 4, 0, 28, 0, 11, 11, 22, 12, 0,
255, 4, 0, 4, 0, 4, 0, 255, 224, 4, 0, 10, 0, 10, 0, 17,
0, 17, 0, 32, 128, 192, 96, 9, 10, 20, 10, 0, 0, 136, 128, 73,
0, 8, 0, 255, 128, 0, 128, 0, 128, 127, 128, 0, 128, 0, 128, 255,
128, 11, 11, 22, 12, 0, 255, 33, 0, 18, 0, 255, 224, 0, 0, 120,
128, 74, 128, 122, 128, 74, 128, 122, 128, 72, 128, 89, 128, 11, 11, 22,
12, 0, 255, 39, 192, 0, 0, 0, 0, 239, 224, 33, 0, 34, 0, 36,
64, 47, 224, 32, 32, 80, 0, 143, 224, 11, 11, 22, 12, 0, 255, 32,
128, 39, 0, 249, 0, 33, 192, 119, 0, 33, 0, 249, 224, 39, 0, 113,
32, 169, 32, 32, 224, 11, 11, 22, 12, 0, 255, 16, 64, 16, 64, 253,
224, 16, 64, 56, 192, 53, 64, 82, 64, 148, 64, 16, 64, 16, 64, 16,
192, 11, 11, 22, 12, 0, 255, 0, 64, 248, 64, 11, 224, 8, 64, 136,
64, 82, 64, 81, 64, 33, 64, 80, 64, 72, 64, 137, 192, 10, 11, 22,
12, 0, 255, 132, 0, 132, 64, 132, 128, 245, 0, 134, 0, 132, 0, 132,
0, 148, 0, 164, 64, 196, 64, 131, 192, 11, 11, 22, 12, 0, 255, 17,
32, 125, 0, 17, 0, 255, 224, 41, 0, 253, 64, 73, 64, 124, 128, 8,
160, 253, 96, 10, 32, 11, 11, 22, 12, 0, 255, 23, 192, 36, 64, 36,
64, 103, 192, 161, 0, 47, 224, 33, 0, 35, 128, 37, 64, 41, 32, 33,
0, 11, 11, 22, 12, 0, 255, 8, 0, 255, 224, 16, 0, 39, 192, 32,
128, 97, 0, 175, 224, 33, 0, 33, 0, 33, 0, 35, 0, 11, 11, 22,
12, 0, 255, 36, 0, 47, 224, 180, 0, 164, 128, 164, 160, 170, 192, 42,
128, 40, 128, 41, 64, 50, 64, 36, 32, 11, 11, 22, 12, 0, 255, 127,
224, 128, 0, 63, 192, 32, 64, 63, 192, 16, 0, 31, 192, 16, 64, 40,
128, 71, 0, 56, 224, 11, 11, 22, 12, 0, 255, 127, 224, 64, 0, 64,
0, 64, 0, 64, 0, 64, 0, 64, 0, 64, 0, 64, 0, 64, 0, 128,
0, 11, 11, 22, 12, 0, 255, 255, 224, 4, 0, 127, 192, 68, 64, 127,
192, 68, 64, 127, 192, 68, 0, 36, 0, 24, 0, 231, 224, 11, 11, 22,
12, 0, 255, 17, 224, 253, 0, 69, 0, 41, 224, 253, 64, 17, 64, 125,
64, 17, 64, 85, 64, 146, 64, 52, 64, 11, 11, 22, 12, 0, 255, 33,
0, 95, 224, 64, 0, 207, 192, 64, 0, 79, 192, 64, 0, 79, 192, 72,
64, 79, 192, 72, 64, 11, 11, 22, 12, 0, 255, 4, 0, 127, 192, 64,
64, 127, 192, 64, 64, 127, 192, 64, 64, 127, 192, 4, 64, 82, 32, 191,
160, 11, 11, 22, 12, 0, 255, 127, 192, 68, 64, 127, 192, 68, 64, 127,
192, 4, 0, 27, 0, 224, 224, 17, 0, 17, 0, 97, 0, 11, 11, 22,
12, 0, 255, 255, 224, 4, 0, 8, 0, 127, 224, 73, 32, 79, 32, 73,
32, 79, 32, 73, 32, 73, 32, 127, 224, 11, 11, 22, 12, 0, 255, 253,
224, 86, 64, 121, 64, 56, 128, 85, 64, 146, 32, 255, 224, 4, 0, 39,
192, 36, 0, 255, 224, 11, 11, 22, 12, 0, 255, 251, 128, 82, 0, 123,
224, 18, 64, 250, 64, 20, 64, 63, 128, 32, 128, 63, 128, 32, 128, 63,
128, 11, 11, 22, 12, 0, 255, 31, 224, 32, 0, 39, 192, 100, 64, 167,
192, 32, 0, 47, 224, 40, 32, 39, 192, 33, 0, 35, 0, 11, 11, 22,
12, 0, 255, 243, 224, 130, 32, 130, 32, 250, 32, 130, 32, 130, 32, 138,
32, 178, 32, 194, 224, 2, 0, 2, 0, 11, 11, 22, 12, 0, 255, 36,
128, 70, 160, 149, 192, 228, 128, 39, 224, 68, 128, 245, 192, 6, 160, 52,
128, 196, 128, 7, 224, 11, 11, 22, 12, 0, 255, 39, 192, 65, 0, 135,
224, 224, 32, 34, 128, 69, 128, 242, 128, 15, 224, 48, 128, 193, 64, 2,
32, 11, 11, 22, 12, 0, 255, 2, 0, 2, 0, 34, 0, 35, 192, 34,
0, 34, 0, 34, 0, 34, 0, 34, 0, 34, 0, 255, 224, 9, 11, 22,
12, 0, 255, 8, 0, 8, 0, 255, 128, 136, 128, 136, 128, 136, 128, 255,
128, 136, 128, 136, 128, 136, 128, 255, 128, 11, 11, 22, 12, 0, 255, 33,
0, 83, 160, 65, 0, 247, 224, 81, 0, 83, 192, 86, 64, 83, 192, 90,
64, 83, 192, 66, 64, 11, 11, 22, 12, 0, 255, 127, 192, 4, 0, 4,
0, 4, 0, 255, 224, 10, 0, 10, 0, 18, 0, 34, 32, 66, 32, 129,
224, 11, 11, 22, 12, 0, 255, 17, 0, 33, 0, 47, 224, 97, 0, 163,
128, 35, 128, 37, 64, 37, 64, 41, 32, 33, 0, 33, 0, 11, 11, 22,
12, 0, 255, 247, 224, 148, 32, 244, 32, 151, 224, 148, 128, 244, 128, 151,
224, 148, 128, 244, 160, 150, 96, 4, 32, 11, 11, 22, 12, 0, 255, 123,
224, 148, 128, 4, 0, 127, 192, 4, 0, 255, 224, 1, 0, 255, 224, 33,
0, 17, 0, 7, 0, 11, 11, 22, 12, 0, 255, 33, 0, 71, 192, 145,
0, 47, 224, 96, 128, 175, 224, 32, 128, 36, 128, 34, 128, 32, 128, 35,
128, 11, 11, 22, 12, 0, 255, 39, 192, 36, 64, 247, 192, 46, 224, 42,
160, 62, 224, 225, 0, 47, 224, 35, 128, 37, 64, 105, 32, 11, 11, 22,
12, 0, 255, 20, 0, 39, 224, 42, 0, 98, 0, 163, 192, 34, 0, 34,
0, 35, 224, 34, 0, 34, 0, 34, 0
};

View File

@ -11,163 +11,164 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t ISO10646_Kana_5x7[2549] U8G_SECTION(".progmem.ISO10646_Kana_5x7") = {
0,6,9,0,254,7,1,145,3,32,32,255,255,8,255,7,
255,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128,
128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
0,0,112,136,152,168,200,136,112,3,7,7,6,1,0,64,
192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
48,64,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
112,5,7,7,6,0,0,112,136,136,120,8,16,96,2,5,
5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1,
0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
8,16,32,0,32,5,6,6,6,0,0,112,136,8,104,168,
112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,7,
7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,0,
0,112,136,128,128,128,136,112,5,7,7,6,0,0,224,144,
136,136,136,144,224,5,7,7,6,0,0,248,128,128,240,128,
128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,5,
7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,6,
0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,128,
128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,16,
16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,136,
5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,7,
6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,0,
136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,136,
136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,128,
128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,7,
7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,0,
0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,32,
32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,136,
136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,5,
7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,6,
0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,136,
136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,32,
64,128,248,3,7,7,6,1,0,224,128,128,128,128,128,224,
5,5,5,6,0,1,128,64,32,16,8,3,7,7,6,1,
0,224,32,32,32,32,32,224,5,3,3,6,0,4,32,80,
136,5,1,1,6,0,0,248,2,2,2,6,2,5,128,64,
5,5,5,6,0,0,112,8,120,136,120,5,7,7,6,0,
0,128,128,176,200,136,136,240,5,5,5,6,0,0,112,128,
128,136,112,5,7,7,6,0,0,8,8,104,152,136,136,120,
5,5,5,6,0,0,112,136,248,128,112,5,7,7,6,0,
0,48,72,224,64,64,64,64,5,6,6,6,0,255,112,136,
136,120,8,112,5,7,7,6,0,0,128,128,176,200,136,136,
136,1,7,7,6,2,0,128,0,128,128,128,128,128,3,8,
8,6,1,255,32,0,32,32,32,32,160,64,4,7,7,6,
0,0,128,128,144,160,192,160,144,3,7,7,6,1,0,192,
64,64,64,64,64,224,5,5,5,6,0,0,208,168,168,168,
168,5,5,5,6,0,0,176,200,136,136,136,5,5,5,6,
0,0,112,136,136,136,112,5,6,6,6,0,255,240,136,136,
240,128,128,5,6,6,6,0,255,120,136,136,120,8,8,5,
5,5,6,0,0,176,200,128,128,128,5,5,5,6,0,0,
112,128,112,8,240,5,7,7,6,0,0,64,64,224,64,64,
72,48,5,5,5,6,0,0,136,136,136,152,104,5,5,5,
6,0,0,136,136,136,80,32,5,5,5,6,0,0,136,136,
168,168,80,5,5,5,6,0,0,136,80,32,80,136,5,6,
6,6,0,255,136,136,136,120,8,112,5,5,5,6,0,0,
248,16,32,64,248,3,7,7,6,1,0,32,64,64,128,64,
64,32,1,7,7,6,2,0,128,128,128,128,128,128,128,3,
7,7,6,1,0,128,64,64,32,64,64,128,5,2,2,6,
0,3,104,144,0,0,0,6,0,0,0,0,0,6,0,0,
0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,
0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,
0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,
0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,
0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,
0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,
0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,
0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,
0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,
0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,
0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,
0,6,0,0,0,0,0,6,0,0,5,3,3,6,0,2,
248,0,248,5,6,6,6,0,0,248,8,40,48,32,64,5,
7,7,6,0,0,248,8,40,48,32,32,64,4,5,5,6,
0,0,16,32,96,160,32,5,7,7,6,0,0,8,16,32,
96,160,32,32,5,5,5,6,0,0,32,248,136,8,48,5,
7,7,6,0,0,32,248,136,136,8,16,32,5,4,4,6,
0,0,248,32,32,248,5,6,6,6,0,0,248,32,32,32,
32,248,5,5,5,6,0,0,16,248,48,80,144,5,7,7,
6,0,0,16,248,16,48,80,144,16,5,5,5,6,0,0,
64,248,72,80,64,5,7,7,6,0,0,40,0,64,248,72,
80,64,5,7,7,6,0,0,32,248,32,248,32,32,32,5,
8,8,6,0,0,40,0,32,248,32,248,32,32,4,6,6,
6,0,0,64,112,144,16,16,32,5,8,8,6,0,0,40,
0,64,112,144,16,16,32,5,6,6,6,0,0,64,120,144,
16,16,32,5,8,8,6,0,0,40,0,64,120,144,16,16,
32,5,5,5,6,0,0,248,8,8,8,248,5,7,7,6,
0,0,40,0,248,8,8,8,248,5,7,7,6,0,255,80,
248,80,80,16,32,64,5,9,9,6,0,255,40,0,80,248,
80,80,16,32,64,5,6,6,6,0,0,192,8,200,8,16,
224,5,8,8,6,0,0,40,0,192,8,200,8,16,224,5,
6,6,6,0,0,248,8,16,32,80,136,5,8,8,6,0,
0,40,0,248,8,16,32,80,136,5,6,6,6,0,0,64,
248,72,80,64,120,5,8,8,6,0,0,40,0,64,248,72,
80,64,120,4,4,4,6,0,1,16,208,16,224,5,7,7,
6,0,0,40,0,8,200,8,16,224,5,7,7,6,0,255,
32,120,136,40,16,40,64,5,9,9,6,0,255,40,0,32,
120,136,40,16,40,64,5,6,6,6,0,0,240,32,248,32,
64,128,5,8,8,6,0,0,40,0,240,32,248,32,64,128,
4,5,5,6,0,1,192,16,208,16,224,5,6,6,6,0,
0,192,8,200,8,16,224,5,8,8,6,0,0,40,0,192,
8,200,8,16,224,5,6,6,6,0,0,112,0,248,32,32,
64,5,8,8,6,0,0,40,0,112,0,248,32,32,64,3,
7,7,6,1,0,128,128,128,192,160,128,128,4,8,8,6,
1,0,80,0,128,128,192,160,128,128,5,7,7,6,0,0,
32,32,248,32,32,64,128,5,6,6,6,0,0,112,0,0,
0,0,248,5,6,6,6,0,0,248,8,80,32,80,128,5,
7,7,6,0,255,32,248,8,16,32,112,168,3,7,7,6,
1,0,32,32,32,32,32,64,128,5,5,5,6,0,0,16,
136,136,136,136,5,7,7,6,0,0,40,0,16,136,136,136,
136,5,8,8,6,0,0,24,24,0,16,136,136,136,136,5,
7,7,6,0,0,128,128,248,128,128,128,120,5,8,8,6,
0,0,40,128,128,248,128,128,128,120,5,8,8,6,0,0,
24,152,128,248,128,128,128,120,5,6,6,6,0,0,248,8,
8,8,16,96,5,8,8,6,0,0,40,0,248,8,8,8,
16,96,5,8,8,6,0,0,24,24,248,8,8,8,16,96,
5,5,5,6,0,1,64,160,16,8,8,5,7,7,6,0,
1,40,0,64,160,16,8,8,5,7,7,6,0,1,24,24,
64,160,16,8,8,5,6,6,6,0,0,32,248,32,32,168,
168,5,8,8,6,0,0,40,0,32,248,32,32,168,168,5,
8,8,6,0,0,24,24,32,248,32,32,168,168,5,6,6,
6,0,0,248,8,8,80,32,16,4,6,6,6,1,0,224,
0,224,0,224,16,5,6,6,6,0,0,32,64,128,144,248,
8,5,6,6,6,0,0,8,8,80,32,80,128,5,6,6,
6,0,0,120,32,248,32,32,56,5,7,7,6,0,0,64,
64,248,72,80,64,64,5,7,7,6,0,0,64,248,72,80,
64,64,64,5,5,5,6,0,0,112,16,16,16,248,5,7,
7,6,0,0,112,16,16,16,16,16,248,4,5,5,6,1,
0,240,16,240,16,240,5,7,7,6,0,0,248,8,8,248,
8,8,248,5,6,6,6,0,0,112,0,248,8,16,32,3,
6,6,6,1,0,160,160,160,160,32,64,5,6,6,6,0,
0,80,80,80,80,88,144,4,6,6,6,1,0,128,128,128,
144,160,192,5,6,6,6,0,0,248,136,136,136,248,136,5,
5,5,6,0,0,248,136,8,16,96,5,6,6,6,0,0,
248,136,8,8,16,96,5,6,6,6,0,0,16,248,80,80,
248,16,5,6,6,6,0,0,248,8,80,96,64,248,5,6,
6,6,0,0,248,8,248,8,16,32,5,6,6,6,0,0,
128,64,8,8,16,224,5,8,8,6,0,0,40,0,32,248,
136,8,24,32,5,6,6,6,0,0,64,248,72,72,136,144,
4,5,5,6,1,0,128,240,160,32,32,5,8,8,6,0,
0,40,0,248,136,8,8,16,96,5,8,8,6,0,0,40,
0,16,248,80,80,248,16,5,7,7,6,0,0,40,0,248,
16,32,32,248,5,8,8,6,0,0,40,0,248,8,248,8,
16,32,2,2,2,6,2,2,192,192,5,1,1,6,0,3,
248,5,5,5,6,0,1,128,64,32,16,8,5,6,6,6,
0,1,40,128,64,32,16,8,5,7,7,6,0,0,248,8,
8,8,8,8,8};
0, 6, 9, 0, 254, 7, 1, 145, 3, 32, 32, 255, 255, 8, 255, 7,
255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
64, 152, 24, 5, 7, 7, 6, 0, 0, 96, 144, 160, 64, 168, 144, 104,
2, 3, 3, 6, 1, 4, 192, 64, 128, 3, 7, 7, 6, 1, 0, 32,
64, 128, 128, 128, 64, 32, 3, 7, 7, 6, 1, 0, 128, 64, 32, 32,
32, 64, 128, 5, 5, 5, 6, 0, 1, 32, 168, 112, 168, 32, 5, 5,
5, 6, 0, 1, 32, 32, 248, 32, 32, 2, 3, 3, 6, 2, 255, 192,
64, 128, 5, 1, 1, 6, 0, 3, 248, 2, 2, 2, 6, 2, 0, 192,
192, 5, 5, 5, 6, 0, 1, 8, 16, 32, 64, 128, 5, 7, 7, 6,
0, 0, 112, 136, 152, 168, 200, 136, 112, 3, 7, 7, 6, 1, 0, 64,
192, 64, 64, 64, 64, 224, 5, 7, 7, 6, 0, 0, 112, 136, 8, 112,
128, 128, 248, 5, 7, 7, 6, 0, 0, 248, 16, 32, 16, 8, 8, 240,
5, 7, 7, 6, 0, 0, 16, 48, 80, 144, 248, 16, 16, 5, 7, 7,
6, 0, 0, 248, 128, 240, 8, 8, 136, 112, 5, 7, 7, 6, 0, 0,
48, 64, 128, 240, 136, 136, 112, 5, 7, 7, 6, 0, 0, 248, 8, 16,
32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 112, 136, 136, 112, 136, 136,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 120, 8, 16, 96, 2, 5,
5, 6, 2, 0, 192, 192, 0, 192, 192, 2, 6, 6, 6, 2, 255, 192,
192, 0, 192, 64, 128, 4, 7, 7, 6, 0, 0, 16, 32, 64, 128, 64,
32, 16, 5, 3, 3, 6, 0, 2, 248, 0, 248, 4, 7, 7, 6, 1,
0, 128, 64, 32, 16, 32, 64, 128, 5, 7, 7, 6, 0, 0, 112, 136,
8, 16, 32, 0, 32, 5, 6, 6, 6, 0, 0, 112, 136, 8, 104, 168,
112, 5, 7, 7, 6, 0, 0, 112, 136, 136, 248, 136, 136, 136, 5, 7,
7, 6, 0, 0, 240, 136, 136, 240, 136, 136, 240, 5, 7, 7, 6, 0,
0, 112, 136, 128, 128, 128, 136, 112, 5, 7, 7, 6, 0, 0, 224, 144,
136, 136, 136, 144, 224, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128,
128, 248, 5, 7, 7, 6, 0, 0, 248, 128, 128, 240, 128, 128, 128, 5,
7, 7, 6, 0, 0, 112, 136, 128, 184, 136, 136, 112, 5, 7, 7, 6,
0, 0, 136, 136, 136, 248, 136, 136, 136, 1, 7, 7, 6, 2, 0, 128,
128, 128, 128, 128, 128, 128, 5, 7, 7, 6, 0, 0, 56, 16, 16, 16,
16, 144, 96, 5, 7, 7, 6, 0, 0, 136, 144, 160, 192, 160, 144, 136,
5, 7, 7, 6, 0, 0, 128, 128, 128, 128, 128, 128, 248, 5, 7, 7,
6, 0, 0, 136, 216, 168, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0,
136, 136, 200, 168, 152, 136, 136, 5, 7, 7, 6, 0, 0, 112, 136, 136,
136, 136, 136, 112, 5, 7, 7, 6, 0, 0, 240, 136, 136, 240, 128, 128,
128, 5, 7, 7, 6, 0, 0, 112, 136, 136, 136, 168, 144, 104, 5, 7,
7, 6, 0, 0, 240, 136, 136, 240, 160, 144, 136, 5, 7, 7, 6, 0,
0, 120, 128, 128, 112, 8, 8, 240, 5, 7, 7, 6, 0, 0, 248, 32,
32, 32, 32, 32, 32, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136,
136, 112, 5, 7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 80, 32, 5,
7, 7, 6, 0, 0, 136, 136, 136, 136, 136, 168, 80, 5, 7, 7, 6,
0, 0, 136, 136, 80, 32, 80, 136, 136, 5, 7, 7, 6, 0, 0, 136,
136, 136, 80, 32, 32, 32, 5, 7, 7, 6, 0, 0, 248, 8, 16, 32,
64, 128, 248, 3, 7, 7, 6, 1, 0, 224, 128, 128, 128, 128, 128, 224,
5, 5, 5, 6, 0, 1, 128, 64, 32, 16, 8, 3, 7, 7, 6, 1,
0, 224, 32, 32, 32, 32, 32, 224, 5, 3, 3, 6, 0, 4, 32, 80,
136, 5, 1, 1, 6, 0, 0, 248, 2, 2, 2, 6, 2, 5, 128, 64,
5, 5, 5, 6, 0, 0, 112, 8, 120, 136, 120, 5, 7, 7, 6, 0,
0, 128, 128, 176, 200, 136, 136, 240, 5, 5, 5, 6, 0, 0, 112, 128,
128, 136, 112, 5, 7, 7, 6, 0, 0, 8, 8, 104, 152, 136, 136, 120,
5, 5, 5, 6, 0, 0, 112, 136, 248, 128, 112, 5, 7, 7, 6, 0,
0, 48, 72, 224, 64, 64, 64, 64, 5, 6, 6, 6, 0, 255, 112, 136,
136, 120, 8, 112, 5, 7, 7, 6, 0, 0, 128, 128, 176, 200, 136, 136,
136, 1, 7, 7, 6, 2, 0, 128, 0, 128, 128, 128, 128, 128, 3, 8,
8, 6, 1, 255, 32, 0, 32, 32, 32, 32, 160, 64, 4, 7, 7, 6,
0, 0, 128, 128, 144, 160, 192, 160, 144, 3, 7, 7, 6, 1, 0, 192,
64, 64, 64, 64, 64, 224, 5, 5, 5, 6, 0, 0, 208, 168, 168, 168,
168, 5, 5, 5, 6, 0, 0, 176, 200, 136, 136, 136, 5, 5, 5, 6,
0, 0, 112, 136, 136, 136, 112, 5, 6, 6, 6, 0, 255, 240, 136, 136,
240, 128, 128, 5, 6, 6, 6, 0, 255, 120, 136, 136, 120, 8, 8, 5,
5, 5, 6, 0, 0, 176, 200, 128, 128, 128, 5, 5, 5, 6, 0, 0,
112, 128, 112, 8, 240, 5, 7, 7, 6, 0, 0, 64, 64, 224, 64, 64,
72, 48, 5, 5, 5, 6, 0, 0, 136, 136, 136, 152, 104, 5, 5, 5,
6, 0, 0, 136, 136, 136, 80, 32, 5, 5, 5, 6, 0, 0, 136, 136,
168, 168, 80, 5, 5, 5, 6, 0, 0, 136, 80, 32, 80, 136, 5, 6,
6, 6, 0, 255, 136, 136, 136, 120, 8, 112, 5, 5, 5, 6, 0, 0,
248, 16, 32, 64, 248, 3, 7, 7, 6, 1, 0, 32, 64, 64, 128, 64,
64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128, 128, 3,
7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 2, 2, 6,
0, 3, 104, 144, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 5, 3, 3, 6, 0, 2,
248, 0, 248, 5, 6, 6, 6, 0, 0, 248, 8, 40, 48, 32, 64, 5,
7, 7, 6, 0, 0, 248, 8, 40, 48, 32, 32, 64, 4, 5, 5, 6,
0, 0, 16, 32, 96, 160, 32, 5, 7, 7, 6, 0, 0, 8, 16, 32,
96, 160, 32, 32, 5, 5, 5, 6, 0, 0, 32, 248, 136, 8, 48, 5,
7, 7, 6, 0, 0, 32, 248, 136, 136, 8, 16, 32, 5, 4, 4, 6,
0, 0, 248, 32, 32, 248, 5, 6, 6, 6, 0, 0, 248, 32, 32, 32,
32, 248, 5, 5, 5, 6, 0, 0, 16, 248, 48, 80, 144, 5, 7, 7,
6, 0, 0, 16, 248, 16, 48, 80, 144, 16, 5, 5, 5, 6, 0, 0,
64, 248, 72, 80, 64, 5, 7, 7, 6, 0, 0, 40, 0, 64, 248, 72,
80, 64, 5, 7, 7, 6, 0, 0, 32, 248, 32, 248, 32, 32, 32, 5,
8, 8, 6, 0, 0, 40, 0, 32, 248, 32, 248, 32, 32, 4, 6, 6,
6, 0, 0, 64, 112, 144, 16, 16, 32, 5, 8, 8, 6, 0, 0, 40,
0, 64, 112, 144, 16, 16, 32, 5, 6, 6, 6, 0, 0, 64, 120, 144,
16, 16, 32, 5, 8, 8, 6, 0, 0, 40, 0, 64, 120, 144, 16, 16,
32, 5, 5, 5, 6, 0, 0, 248, 8, 8, 8, 248, 5, 7, 7, 6,
0, 0, 40, 0, 248, 8, 8, 8, 248, 5, 7, 7, 6, 0, 255, 80,
248, 80, 80, 16, 32, 64, 5, 9, 9, 6, 0, 255, 40, 0, 80, 248,
80, 80, 16, 32, 64, 5, 6, 6, 6, 0, 0, 192, 8, 200, 8, 16,
224, 5, 8, 8, 6, 0, 0, 40, 0, 192, 8, 200, 8, 16, 224, 5,
6, 6, 6, 0, 0, 248, 8, 16, 32, 80, 136, 5, 8, 8, 6, 0,
0, 40, 0, 248, 8, 16, 32, 80, 136, 5, 6, 6, 6, 0, 0, 64,
248, 72, 80, 64, 120, 5, 8, 8, 6, 0, 0, 40, 0, 64, 248, 72,
80, 64, 120, 4, 4, 4, 6, 0, 1, 16, 208, 16, 224, 5, 7, 7,
6, 0, 0, 40, 0, 8, 200, 8, 16, 224, 5, 7, 7, 6, 0, 255,
32, 120, 136, 40, 16, 40, 64, 5, 9, 9, 6, 0, 255, 40, 0, 32,
120, 136, 40, 16, 40, 64, 5, 6, 6, 6, 0, 0, 240, 32, 248, 32,
64, 128, 5, 8, 8, 6, 0, 0, 40, 0, 240, 32, 248, 32, 64, 128,
4, 5, 5, 6, 0, 1, 192, 16, 208, 16, 224, 5, 6, 6, 6, 0,
0, 192, 8, 200, 8, 16, 224, 5, 8, 8, 6, 0, 0, 40, 0, 192,
8, 200, 8, 16, 224, 5, 6, 6, 6, 0, 0, 112, 0, 248, 32, 32,
64, 5, 8, 8, 6, 0, 0, 40, 0, 112, 0, 248, 32, 32, 64, 3,
7, 7, 6, 1, 0, 128, 128, 128, 192, 160, 128, 128, 4, 8, 8, 6,
1, 0, 80, 0, 128, 128, 192, 160, 128, 128, 5, 7, 7, 6, 0, 0,
32, 32, 248, 32, 32, 64, 128, 5, 6, 6, 6, 0, 0, 112, 0, 0,
0, 0, 248, 5, 6, 6, 6, 0, 0, 248, 8, 80, 32, 80, 128, 5,
7, 7, 6, 0, 255, 32, 248, 8, 16, 32, 112, 168, 3, 7, 7, 6,
1, 0, 32, 32, 32, 32, 32, 64, 128, 5, 5, 5, 6, 0, 0, 16,
136, 136, 136, 136, 5, 7, 7, 6, 0, 0, 40, 0, 16, 136, 136, 136,
136, 5, 8, 8, 6, 0, 0, 24, 24, 0, 16, 136, 136, 136, 136, 5,
7, 7, 6, 0, 0, 128, 128, 248, 128, 128, 128, 120, 5, 8, 8, 6,
0, 0, 40, 128, 128, 248, 128, 128, 128, 120, 5, 8, 8, 6, 0, 0,
24, 152, 128, 248, 128, 128, 128, 120, 5, 6, 6, 6, 0, 0, 248, 8,
8, 8, 16, 96, 5, 8, 8, 6, 0, 0, 40, 0, 248, 8, 8, 8,
16, 96, 5, 8, 8, 6, 0, 0, 24, 24, 248, 8, 8, 8, 16, 96,
5, 5, 5, 6, 0, 1, 64, 160, 16, 8, 8, 5, 7, 7, 6, 0,
1, 40, 0, 64, 160, 16, 8, 8, 5, 7, 7, 6, 0, 1, 24, 24,
64, 160, 16, 8, 8, 5, 6, 6, 6, 0, 0, 32, 248, 32, 32, 168,
168, 5, 8, 8, 6, 0, 0, 40, 0, 32, 248, 32, 32, 168, 168, 5,
8, 8, 6, 0, 0, 24, 24, 32, 248, 32, 32, 168, 168, 5, 6, 6,
6, 0, 0, 248, 8, 8, 80, 32, 16, 4, 6, 6, 6, 1, 0, 224,
0, 224, 0, 224, 16, 5, 6, 6, 6, 0, 0, 32, 64, 128, 144, 248,
8, 5, 6, 6, 6, 0, 0, 8, 8, 80, 32, 80, 128, 5, 6, 6,
6, 0, 0, 120, 32, 248, 32, 32, 56, 5, 7, 7, 6, 0, 0, 64,
64, 248, 72, 80, 64, 64, 5, 7, 7, 6, 0, 0, 64, 248, 72, 80,
64, 64, 64, 5, 5, 5, 6, 0, 0, 112, 16, 16, 16, 248, 5, 7,
7, 6, 0, 0, 112, 16, 16, 16, 16, 16, 248, 4, 5, 5, 6, 1,
0, 240, 16, 240, 16, 240, 5, 7, 7, 6, 0, 0, 248, 8, 8, 248,
8, 8, 248, 5, 6, 6, 6, 0, 0, 112, 0, 248, 8, 16, 32, 3,
6, 6, 6, 1, 0, 160, 160, 160, 160, 32, 64, 5, 6, 6, 6, 0,
0, 80, 80, 80, 80, 88, 144, 4, 6, 6, 6, 1, 0, 128, 128, 128,
144, 160, 192, 5, 6, 6, 6, 0, 0, 248, 136, 136, 136, 248, 136, 5,
5, 5, 6, 0, 0, 248, 136, 8, 16, 96, 5, 6, 6, 6, 0, 0,
248, 136, 8, 8, 16, 96, 5, 6, 6, 6, 0, 0, 16, 248, 80, 80,
248, 16, 5, 6, 6, 6, 0, 0, 248, 8, 80, 96, 64, 248, 5, 6,
6, 6, 0, 0, 248, 8, 248, 8, 16, 32, 5, 6, 6, 6, 0, 0,
128, 64, 8, 8, 16, 224, 5, 8, 8, 6, 0, 0, 40, 0, 32, 248,
136, 8, 24, 32, 5, 6, 6, 6, 0, 0, 64, 248, 72, 72, 136, 144,
4, 5, 5, 6, 1, 0, 128, 240, 160, 32, 32, 5, 8, 8, 6, 0,
0, 40, 0, 248, 136, 8, 8, 16, 96, 5, 8, 8, 6, 0, 0, 40,
0, 16, 248, 80, 80, 248, 16, 5, 7, 7, 6, 0, 0, 40, 0, 248,
16, 32, 32, 248, 5, 8, 8, 6, 0, 0, 40, 0, 248, 8, 248, 8,
16, 32, 2, 2, 2, 6, 2, 2, 192, 192, 5, 1, 1, 6, 0, 3,
248, 5, 5, 5, 6, 0, 1, 128, 64, 32, 16, 8, 5, 6, 6, 6,
0, 1, 40, 128, 64, 32, 16, 8, 5, 7, 7, 6, 0, 0, 248, 8,
8, 8, 8, 8, 8
};

View File

@ -11,12 +11,13 @@
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t Marlin_symbols[140] U8G_SECTION(".progmem.Marlin_symbols") = {
0,6,9,0,254,0,0,0,0,0,1,9,0,8,254,0,
0,5,8,8,6,0,0,64,240,200,136,136,152,120,16,5,
8,8,6,0,0,192,248,136,136,136,136,136,248,5,5,5,
6,0,1,32,48,248,48,32,5,8,8,6,0,0,32,112,
248,32,32,32,32,224,5,9,9,6,0,255,32,112,168,168,
184,136,136,112,32,5,9,9,6,0,255,224,128,192,176,168,
40,48,40,40,5,9,9,6,0,255,248,168,136,136,136,136,
136,168,248,5,10,10,6,0,254,32,80,80,80,80,136,168,
168,136,112,3,3,3,6,0,3,64,160,64};
0, 6, 9, 0, 254, 0, 0, 0, 0, 0, 1, 9, 0, 8, 254, 0,
0, 5, 8, 8, 6, 0, 0, 64, 240, 200, 136, 136, 152, 120, 16, 5,
8, 8, 6, 0, 0, 192, 248, 136, 136, 136, 136, 136, 248, 5, 5, 5,
6, 0, 1, 32, 48, 248, 48, 32, 5, 8, 8, 6, 0, 0, 32, 112,
248, 32, 32, 32, 32, 224, 5, 9, 9, 6, 0, 255, 32, 112, 168, 168,
184, 136, 136, 112, 32, 5, 9, 9, 6, 0, 255, 224, 128, 192, 176, 168,
40, 48, 40, 40, 5, 9, 9, 6, 0, 255, 248, 168, 136, 136, 136, 136,
136, 168, 248, 5, 10, 10, 6, 0, 254, 32, 80, 80, 80, 80, 136, 168,
168, 136, 112, 3, 3, 3, 6, 0, 3, 64, 160, 64
};

View File

@ -36,7 +36,7 @@
#include "Configuration.h"
#if DISABLED(MAPPER_C2C3) && DISABLED(MAPPER_NON) && ENABLED(USE_BIG_EDIT_FONT)
#undef USE_BIG_EDIT_FONT
#undef USE_BIG_EDIT_FONT
#endif
@ -203,11 +203,11 @@ static void lcd_implementation_init() {
#endif
#if ENABLED(LCD_PIN_RESET)
pinMode(LCD_PIN_RESET, OUTPUT);
pinMode(LCD_PIN_RESET, OUTPUT);
digitalWrite(LCD_PIN_RESET, HIGH);
#endif
#if DISABLED(MINIPANEL) // setContrast not working for Mini Panel
u8g.setContrast(lcd_contrast);
u8g.setContrast(lcd_contrast);
#endif
// FIXME: remove this workaround
// Uncomment this if you have the first generation (V1.10) of STBs board
@ -230,7 +230,7 @@ static void lcd_implementation_init() {
int offy = DOG_CHAR_HEIGHT;
#endif
int txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1)*DOG_CHAR_WIDTH) / 2;
int txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * DOG_CHAR_WIDTH) / 2;
u8g.firstPage();
do {
@ -240,9 +240,9 @@ static void lcd_implementation_init() {
#ifndef STRING_SPLASH_LINE2
u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT, STRING_SPLASH_LINE1);
#else
int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1)*DOG_CHAR_WIDTH) / 2;
u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT*3/2, STRING_SPLASH_LINE1);
u8g.drawStr(txt2X, u8g.getHeight() - DOG_CHAR_HEIGHT*1/2, STRING_SPLASH_LINE2);
int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * DOG_CHAR_WIDTH) / 2;
u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT * 3 / 2, STRING_SPLASH_LINE1);
u8g.drawStr(txt2X, u8g.getHeight() - DOG_CHAR_HEIGHT * 1 / 2, STRING_SPLASH_LINE2);
#endif
}
} while (u8g.nextPage());
@ -261,10 +261,10 @@ static void _draw_heater_status(int x, int heater) {
int y = 17 + (isBed ? 1 : 0);
lcd_setFont(FONT_STATUSMENU);
u8g.setPrintPos(x,7);
u8g.setPrintPos(x, 7);
lcd_print(itostr3(int((heater >= 0 ? degTargetHotend(heater) : degTargetBed()) + 0.5)));
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
u8g.setPrintPos(x,28);
u8g.setPrintPos(x, 28);
lcd_print(itostr3(int(heater >= 0 ? degHotend(heater) : degBed()) + 0.5));
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
@ -273,7 +273,7 @@ static void _draw_heater_status(int x, int heater) {
}
else {
u8g.setColorIndex(0); // white on black
u8g.drawBox(x+7,y,2,2);
u8g.drawBox(x + 7, y, 2, 2);
u8g.setColorIndex(1); // black on white
}
}
@ -283,7 +283,7 @@ static void lcd_implementation_status_screen() {
// Symbols menu graphics, animated fan
u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT, (blink % 2) && fanSpeed ? status_screen0_bmp : status_screen1_bmp);
#if ENABLED(SDSUPPORT)
// SD Card Symbol
u8g.drawBox(42, 42 - TALL_FONT_CORRECTION, 8, 7);
@ -296,7 +296,7 @@ static void lcd_implementation_status_screen() {
// SD Card Progress bar and clock
lcd_setFont(FONT_STATUSMENU);
if (IS_SD_PRINTING) {
// Progress bar solid part
u8g.drawBox(55, 50, (unsigned int)(71.f * card.percentDone() / 100.f), 2 - TALL_FONT_CORRECTION);
@ -315,14 +315,14 @@ static void lcd_implementation_status_screen() {
#endif
// Extruders
for (int i=0; i<EXTRUDERS; i++) _draw_heater_status(6 + i * 25, i);
for (int i = 0; i < EXTRUDERS; i++) _draw_heater_status(6 + i * 25, i);
// Heatbed
if (EXTRUDERS < 4) _draw_heater_status(81, -1);
// Fan
lcd_setFont(FONT_STATUSMENU);
u8g.setPrintPos(104,27);
u8g.setPrintPos(104, 27);
#if HAS_FAN
int per = ((fanSpeed + 1) * 100) / 256;
if (per) {
@ -340,55 +340,55 @@ static void lcd_implementation_status_screen() {
lcd_setFont(FONT_STATUSMENU);
#if ENABLED(USE_SMALL_INFOFONT)
u8g.drawBox(0,30,LCD_PIXEL_WIDTH,10);
u8g.drawBox(0, 30, LCD_PIXEL_WIDTH, 10);
#else
u8g.drawBox(0,30,LCD_PIXEL_WIDTH,9);
u8g.drawBox(0, 30, LCD_PIXEL_WIDTH, 9);
#endif
u8g.setColorIndex(0); // white on black
u8g.setPrintPos(2,XYZ_BASELINE);
u8g.setPrintPos(2, XYZ_BASELINE);
lcd_print('X');
u8g.drawPixel(8,XYZ_BASELINE - 5);
u8g.drawPixel(8,XYZ_BASELINE - 3);
u8g.setPrintPos(10,XYZ_BASELINE);
u8g.drawPixel(8, XYZ_BASELINE - 5);
u8g.drawPixel(8, XYZ_BASELINE - 3);
u8g.setPrintPos(10, XYZ_BASELINE);
if (axis_known_position[X_AXIS])
lcd_print(ftostr31ns(current_position[X_AXIS]));
else
lcd_printPGM(PSTR("---"));
u8g.setPrintPos(43,XYZ_BASELINE);
u8g.setPrintPos(43, XYZ_BASELINE);
lcd_print('Y');
u8g.drawPixel(49,XYZ_BASELINE - 5);
u8g.drawPixel(49,XYZ_BASELINE - 3);
u8g.setPrintPos(51,XYZ_BASELINE);
u8g.drawPixel(49, XYZ_BASELINE - 5);
u8g.drawPixel(49, XYZ_BASELINE - 3);
u8g.setPrintPos(51, XYZ_BASELINE);
if (axis_known_position[Y_AXIS])
lcd_print(ftostr31ns(current_position[Y_AXIS]));
else
lcd_printPGM(PSTR("---"));
u8g.setPrintPos(83,XYZ_BASELINE);
u8g.setPrintPos(83, XYZ_BASELINE);
lcd_print('Z');
u8g.drawPixel(89,XYZ_BASELINE - 5);
u8g.drawPixel(89,XYZ_BASELINE - 3);
u8g.setPrintPos(91,XYZ_BASELINE);
u8g.drawPixel(89, XYZ_BASELINE - 5);
u8g.drawPixel(89, XYZ_BASELINE - 3);
u8g.setPrintPos(91, XYZ_BASELINE);
if (axis_known_position[Z_AXIS])
lcd_print(ftostr32sp(current_position[Z_AXIS]));
else
lcd_printPGM(PSTR("---.--"));
u8g.setColorIndex(1); // black on white
// Feedrate
lcd_setFont(FONT_MENU);
u8g.setPrintPos(3,49);
u8g.setPrintPos(3, 49);
lcd_print(LCD_STR_FEEDRATE[0]);
lcd_setFont(FONT_STATUSMENU);
u8g.setPrintPos(12,49);
u8g.setPrintPos(12, 49);
lcd_print(itostr3(feedrate_multiplier));
lcd_print('%');
// Status line
lcd_setFont(FONT_STATUSMENU);
#if ENABLED(USE_SMALL_INFOFONT)
u8g.setPrintPos(0,62);
u8g.setPrintPos(0, 62);
#else
u8g.setPrintPos(0,63);
u8g.setPrintPos(0, 63);
#endif
#if DISABLED(FILAMENT_LCD_DISPLAY)
lcd_print(lcd_status_message);
@ -429,7 +429,7 @@ static void lcd_implementation_drawmenu_generic(bool isSelected, uint8_t row, co
pstr++;
}
while (n--) lcd_print(' ');
u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT);
u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT);
lcd_print(post_char);
lcd_print(' ');
}
@ -448,7 +448,7 @@ static void _drawmenu_setting_edit_generic(bool isSelected, uint8_t row, const c
lcd_print(':');
while (n--) lcd_print(' ');
u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH * vallen, (row + 1) * DOG_CHAR_HEIGHT);
if (pgm) { lcd_printPGM(data); } else { lcd_print((char *)data); }
if (pgm) lcd_printPGM(data); else lcd_print((char*)data);
}
#define lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, data) _drawmenu_setting_edit_generic(sel, row, pstr, data, false)
@ -506,7 +506,7 @@ void lcd_implementation_drawedit(const char* pstr, char* value) {
#if ENABLED(SDSUPPORT)
static void _drawmenu_sd(bool isSelected, uint8_t row, const char* pstr, const char* filename, char * const longFilename, bool isDir) {
static void _drawmenu_sd(bool isSelected, uint8_t row, const char* pstr, const char* filename, char* const longFilename, bool isDir) {
char c;
uint8_t n = LCD_WIDTH - 1;

File diff suppressed because it is too large Load Diff

View File

@ -1,4 +1,4 @@
The fonts are created with Fony.exe (http://hukka.ncn.fi/?fony) because Fontforge didn't do what I want (probably lack off experience).
The fonts are created with Fony.exe (http://hukka.ncn.fi/?fony) because Fontforge didn't do what I want (probably lack of experience).
In Fony export the fonts to bdf-format. Maybe another one can edit them with Fontforge.
Then run make_fonts.bat what calls bdf2u8g.exe with the needed parameters to produce the .h files.
The .h files must be edited to replace '#include "u8g.h"' with '#include <utility/u8g.h>', replace 'U8G_FONT_SECTION' with 'U8G_SECTION', insert '.progmem.' right behind the first '"' and moved to the main directory.
@ -6,7 +6,7 @@ The .h files must be edited to replace '#include "u8g.h"' with '#include <utilit
How to integrate a new font:
Currently we are limited to 256 symbols per font. We use a menu system with 5 lines, on a display with 64 pixel height. That means we have 12 pixel for a line. To have some space in between the lines we can't use more then 10 pixel height for the symbols. For up to 11 pixel set TALL_FONT_CORRECTION 1 when loading the font.
To fit 22 Symbols on the 128 pixel wide screen, the symbols can't be wider than 5 pixel, for the first 128 symbols.
For the second half of the font we now support up to 11x11 pixel.
For the second half of the font we now support up to 11x11 pixel.
* Get 'Fony.exe'
* Copy one of the existing *.fon files and work with this.

View File

@ -81,8 +81,8 @@
#error BUILD_VERSION Information must be specified
#endif
#ifndef MACHINE_UUID
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
#ifndef UUID
#define UUID "00000000-0000-0000-0000-000000000000"
#endif
@ -122,7 +122,7 @@
#define MSG_INVALID_EXTRUDER "Invalid extruder"
#define MSG_INVALID_SOLENOID "Invalid solenoid"
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" UUID "\n"
#define MSG_COUNT_X " Count X: "
#define MSG_ERR_KILLED "Printer halted. kill() called!"
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"

View File

@ -125,11 +125,11 @@
#define MSG_END_MINUTE "minutes"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_AN_H

View File

@ -126,11 +126,11 @@
#define MSG_END_MINUTE "минути"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Делта Калибровка"
#define MSG_DELTA_CALIBRATE_X "Калибровка X"
#define MSG_DELTA_CALIBRATE_Y "Калибровка Y"
#define MSG_DELTA_CALIBRATE_Z "Калибровка Z"
#define MSG_DELTA_CALIBRATE_CENTER "Калибровка Център"
#define MSG_DELTA_CALIBRATE "Делта Калибровка"
#define MSG_DELTA_CALIBRATE_X "Калибровка X"
#define MSG_DELTA_CALIBRATE_Y "Калибровка Y"
#define MSG_DELTA_CALIBRATE_Z "Калибровка Z"
#define MSG_DELTA_CALIBRATE_CENTER "Калибровка Център"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_BG_H

View File

@ -126,11 +126,11 @@
#define MSG_END_MINUTE "minutes"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_CA_H

View File

@ -8,135 +8,135 @@
#ifndef LANGUAGE_CN_H
#define LANGUAGE_CN_H
#define MAPPER_NON // For direct asci codes
#define DISPLAY_CHARSET_ISO10646_CN
#define MAPPER_NON // For direct asci codes
#define DISPLAY_CHARSET_ISO10646_CN
#define WELCOME_MSG "\xa4\xa5\xa6\xa7"
#define MSG_SD_INSERTED "\xa8\xa9\xaa\xab"
#define MSG_SD_REMOVED "\xa8\xa9\xac\xad"
#define MSG_MAIN "\xae\xaf\xb0"
#define MSG_AUTOSTART "\xb1\xb2\xb3\xb4"
#define MSG_DISABLE_STEPPERS "\xb5\xb6\xb7\xb8\xb9\xba"
#define MSG_AUTO_HOME "\xbb\xbc\xbd"
#define MSG_SET_HOME_OFFSETS "\xbe\xbf\xbb\xbc\xbd\xc0\xc1"
#define MSG_SET_ORIGIN "\xbe\xbf\xbc\xbd"
#define MSG_PREHEAT_PLA "\xc3\xc4 PLA"
#define MSG_PREHEAT_PLA_N MSG_PREHEAT_PLA " "
#define MSG_PREHEAT_PLA_ALL MSG_PREHEAT_PLA " \xc5\xc6"
#define MSG_PREHEAT_PLA_BEDONLY MSG_PREHEAT_PLA " \xc4\xc7"
#define MSG_PREHEAT_PLA_SETTINGS MSG_PREHEAT_PLA " \xbe\xbf"
#define MSG_PREHEAT_ABS "\xc3\xc4 ABS"
#define MSG_PREHEAT_ABS_N MSG_PREHEAT_ABS " "
#define MSG_PREHEAT_ABS_ALL MSG_PREHEAT_ABS " \xc5\xc6"
#define MSG_PREHEAT_ABS_BEDONLY MSG_PREHEAT_ABS " \xbe\xc6"
#define MSG_PREHEAT_ABS_SETTINGS MSG_PREHEAT_ABS " \xbe\xbf"
#define MSG_COOLDOWN "\xc8\xc9"
#define MSG_SWITCH_PS_ON "\xb9\xcb\xca\xb3"
#define MSG_SWITCH_PS_OFF "\xb9\xcb\xb5\xb6"
#define MSG_EXTRUDE "\xcc\xad"
#define MSG_RETRACT "\xbb\xcd"
#define MSG_MOVE_AXIS "\xc1\xb2\xce"
#define MSG_LEVEL_BED "\xcf\xe0\xc4\xc7"
#define MSG_MOVE_X "\xc1\xb2 X"
#define MSG_MOVE_Y "\xc1\xb2 Y"
#define MSG_MOVE_Z "\xc1\xb2 Z"
#define MSG_MOVE_E "\xcc\xad\xba"
#define MSG_MOVE_01MM "\xc1\xb2 0.1mm"
#define MSG_MOVE_1MM "\xc1\xb2 1mm"
#define MSG_MOVE_10MM "\xc1\xb2 10mm"
#define MSG_SPEED "\xd1\xd2"
#define MSG_NOZZLE "\xd3\xd4"
#define MSG_BED "\xc4\xc7"
#define MSG_FAN_SPEED "\xd5\xd6\xd1\xd2"
#define MSG_FLOW "\xcc\xad\xd1\xd2"
#define MSG_CONTROL "\xd8\xd9"
#define MSG_MIN LCD_STR_THERMOMETER " \xda\xdb"
#define MSG_MAX LCD_STR_THERMOMETER " \xda\xdc"
#define MSG_FACTOR LCD_STR_THERMOMETER " \xdd\xde"
#define MSG_AUTOTEMP "\xb1\xb2\xd8\xc9"
#define MSG_ON "\xb3 " // intentional space to shift wide symbol to the left
#define MSG_OFF "\xb5 " // intentional space to shift wide symbol to the left
#define MSG_PID_P "PID-P"
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "x"
#define MSG_Y "y"
#define MSG_Z "z"
#define MSG_E "e"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
#define MSG_A_RETRACT "A-retract"
#define MSG_A_TRAVEL "A-travel"
#define MSG_XSTEPS "Xsteps/mm"
#define MSG_YSTEPS "Ysteps/mm"
#define MSG_ZSTEPS "Zsteps/mm"
#define MSG_ESTEPS "Esteps/mm"
#define MSG_TEMPERATURE "\xc9\xd2"
#define MSG_MOTION "\xdf\xb2"
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#define MSG_FILAMENT_DIAM "Fil. Dia."
#define MSG_CONTRAST "LCD contrast"
#define MSG_STORE_EPROM "Store memory"
#define MSG_LOAD_EPROM "Load memory"
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
#define MSG_REFRESH "Refresh"
#define MSG_WATCH "\xec\xed\xee\xef"
#define MSG_PREPARE "\xa4\xa5"
#define MSG_TUNE "\xcf\xf0"
#define MSG_PAUSE_PRINT "\xf1\xf2\xca\xf3"
#define MSG_RESUME_PRINT "\xf4\xf5\xca\xf3"
#define MSG_STOP_PRINT "\xf2\xf6\xca\xf3"
#define MSG_CARD_MENU "\xaf\xb0"
#define MSG_NO_CARD "\xf9\xa8"
#define MSG_DWELL "Sleep..."
#define MSG_USERWAIT "Wait for user..."
#define MSG_RESUMING "Resuming print"
#define MSG_PRINT_ABORTED "Print aborted"
#define MSG_NO_MOVE "No move."
#define MSG_KILLED "KILLED. "
#define MSG_STOPPED "STOPPED. "
#define MSG_CONTROL_RETRACT "Retract mm"
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
#define MSG_CONTROL_RETRACTF "Retract V"
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
#define MSG_AUTORETRACT "AutoRetr."
#define MSG_FILAMENTCHANGE "Change filament"
#define MSG_INIT_SDCARD "Init. SD card"
#define MSG_CNG_SDCARD "Change SD card"
#define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_HEATING_FAILED_LCD "Heating failed"
#define MSG_ERR_REDUNDANT_TEMP "Err: REDUNDANT TEMP ERROR"
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#define MSG_ERR_MAXTEMP "Err: MAXTEMP"
#define MSG_ERR_MINTEMP "Err: MINTEMP"
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#define MSG_END_HOUR "hours"
#define MSG_END_MINUTE "minutes"
#define WELCOME_MSG "\xa4\xa5\xa6\xa7"
#define MSG_SD_INSERTED "\xa8\xa9\xaa\xab"
#define MSG_SD_REMOVED "\xa8\xa9\xac\xad"
#define MSG_MAIN "\xae\xaf\xb0"
#define MSG_AUTOSTART "\xb1\xb2\xb3\xb4"
#define MSG_DISABLE_STEPPERS "\xb5\xb6\xb7\xb8\xb9\xba"
#define MSG_AUTO_HOME "\xbb\xbc\xbd"
#define MSG_SET_HOME_OFFSETS "\xbe\xbf\xbb\xbc\xbd\xc0\xc1"
#define MSG_SET_ORIGIN "\xbe\xbf\xbc\xbd"
#define MSG_PREHEAT_PLA "\xc3\xc4 PLA"
#define MSG_PREHEAT_PLA_N MSG_PREHEAT_PLA " "
#define MSG_PREHEAT_PLA_ALL MSG_PREHEAT_PLA " \xc5\xc6"
#define MSG_PREHEAT_PLA_BEDONLY MSG_PREHEAT_PLA " \xc4\xc7"
#define MSG_PREHEAT_PLA_SETTINGS MSG_PREHEAT_PLA " \xbe\xbf"
#define MSG_PREHEAT_ABS "\xc3\xc4 ABS"
#define MSG_PREHEAT_ABS_N MSG_PREHEAT_ABS " "
#define MSG_PREHEAT_ABS_ALL MSG_PREHEAT_ABS " \xc5\xc6"
#define MSG_PREHEAT_ABS_BEDONLY MSG_PREHEAT_ABS " \xbe\xc6"
#define MSG_PREHEAT_ABS_SETTINGS MSG_PREHEAT_ABS " \xbe\xbf"
#define MSG_COOLDOWN "\xc8\xc9"
#define MSG_SWITCH_PS_ON "\xb9\xcb\xca\xb3"
#define MSG_SWITCH_PS_OFF "\xb9\xcb\xb5\xb6"
#define MSG_EXTRUDE "\xcc\xad"
#define MSG_RETRACT "\xbb\xcd"
#define MSG_MOVE_AXIS "\xc1\xb2\xce"
#define MSG_LEVEL_BED "\xcf\xe0\xc4\xc7"
#define MSG_MOVE_X "\xc1\xb2 X"
#define MSG_MOVE_Y "\xc1\xb2 Y"
#define MSG_MOVE_Z "\xc1\xb2 Z"
#define MSG_MOVE_E "\xcc\xad\xba"
#define MSG_MOVE_01MM "\xc1\xb2 0.1mm"
#define MSG_MOVE_1MM "\xc1\xb2 1mm"
#define MSG_MOVE_10MM "\xc1\xb2 10mm"
#define MSG_SPEED "\xd1\xd2"
#define MSG_NOZZLE "\xd3\xd4"
#define MSG_BED "\xc4\xc7"
#define MSG_FAN_SPEED "\xd5\xd6\xd1\xd2"
#define MSG_FLOW "\xcc\xad\xd1\xd2"
#define MSG_CONTROL "\xd8\xd9"
#define MSG_MIN LCD_STR_THERMOMETER " \xda\xdb"
#define MSG_MAX LCD_STR_THERMOMETER " \xda\xdc"
#define MSG_FACTOR LCD_STR_THERMOMETER " \xdd\xde"
#define MSG_AUTOTEMP "\xb1\xb2\xd8\xc9"
#define MSG_ON "\xb3 " // intentional space to shift wide symbol to the left
#define MSG_OFF "\xb5 " // intentional space to shift wide symbol to the left
#define MSG_PID_P "PID-P"
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "x"
#define MSG_Y "y"
#define MSG_Z "z"
#define MSG_E "e"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
#define MSG_A_RETRACT "A-retract"
#define MSG_A_TRAVEL "A-travel"
#define MSG_XSTEPS "Xsteps/mm"
#define MSG_YSTEPS "Ysteps/mm"
#define MSG_ZSTEPS "Zsteps/mm"
#define MSG_ESTEPS "Esteps/mm"
#define MSG_TEMPERATURE "\xc9\xd2"
#define MSG_MOTION "\xdf\xb2"
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#define MSG_FILAMENT_DIAM "Fil. Dia."
#define MSG_CONTRAST "LCD contrast"
#define MSG_STORE_EPROM "Store memory"
#define MSG_LOAD_EPROM "Load memory"
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
#define MSG_REFRESH "Refresh"
#define MSG_WATCH "\xec\xed\xee\xef"
#define MSG_PREPARE "\xa4\xa5"
#define MSG_TUNE "\xcf\xf0"
#define MSG_PAUSE_PRINT "\xf1\xf2\xca\xf3"
#define MSG_RESUME_PRINT "\xf4\xf5\xca\xf3"
#define MSG_STOP_PRINT "\xf2\xf6\xca\xf3"
#define MSG_CARD_MENU "\xaf\xb0"
#define MSG_NO_CARD "\xf9\xa8"
#define MSG_DWELL "Sleep..."
#define MSG_USERWAIT "Wait for user..."
#define MSG_RESUMING "Resuming print"
#define MSG_PRINT_ABORTED "Print aborted"
#define MSG_NO_MOVE "No move."
#define MSG_KILLED "KILLED. "
#define MSG_STOPPED "STOPPED. "
#define MSG_CONTROL_RETRACT "Retract mm"
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
#define MSG_CONTROL_RETRACTF "Retract V"
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
#define MSG_AUTORETRACT "AutoRetr."
#define MSG_FILAMENTCHANGE "Change filament"
#define MSG_INIT_SDCARD "Init. SD card"
#define MSG_CNG_SDCARD "Change SD card"
#define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_HEATING_FAILED_LCD "Heating failed"
#define MSG_ERR_REDUNDANT_TEMP "Err: REDUNDANT TEMP ERROR"
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#define MSG_ERR_MAXTEMP "Err: MAXTEMP"
#define MSG_ERR_MINTEMP "Err: MINTEMP"
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#define MSG_END_HOUR "hours"
#define MSG_END_MINUTE "minutes"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_CN_H

View File

@ -131,11 +131,11 @@
#define MSG_ENDSTOP_ABORT "Endstop abort"
#ifdef DELTA_CALIBRATION_MENU
#define MSG_DELTA_CALIBRATE "Delta Kalibrering"
#define MSG_DELTA_CALIBRATE_X "Kalibrer X"
#define MSG_DELTA_CALIBRATE_Y "Kalibrer Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibrer Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibrerings Center"
#define MSG_DELTA_CALIBRATE "Delta Kalibrering"
#define MSG_DELTA_CALIBRATE_X "Kalibrer X"
#define MSG_DELTA_CALIBRATE_Y "Kalibrer Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibrer Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibrerings Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_DA_H

View File

@ -128,11 +128,11 @@
#define MSG_BED_DONE "Bett aufgeheizt"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta kalibrieren"
#define MSG_DELTA_CALIBRATE_X "Kalibriere X"
#define MSG_DELTA_CALIBRATE_Y "Kalibriere Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibriere Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibriere Mitte"
#define MSG_DELTA_CALIBRATE "Delta kalibrieren"
#define MSG_DELTA_CALIBRATE_X "Kalibriere X"
#define MSG_DELTA_CALIBRATE_Y "Kalibriere Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibriere Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibriere Mitte"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_DE_H

View File

@ -19,451 +19,448 @@
#ifndef WELCOME_MSG
#define WELCOME_MSG MACHINE_NAME " ready."
#define WELCOME_MSG MACHINE_NAME " ready."
#endif
#ifndef MSG_SD_INSERTED
#define MSG_SD_INSERTED "Card inserted"
#define MSG_SD_INSERTED "Card inserted"
#endif
#ifndef MSG_SD_REMOVED
#define MSG_SD_REMOVED "Card removed"
#define MSG_SD_REMOVED "Card removed"
#endif
#ifndef MSG_MAIN
#define MSG_MAIN "Main"
#define MSG_MAIN "Main"
#endif
#ifndef MSG_AUTOSTART
#define MSG_AUTOSTART "Autostart"
#define MSG_AUTOSTART "Autostart"
#endif
#ifndef MSG_DISABLE_STEPPERS
#define MSG_DISABLE_STEPPERS "Disable steppers"
#define MSG_DISABLE_STEPPERS "Disable steppers"
#endif
#ifndef MSG_AUTO_HOME
#define MSG_AUTO_HOME "Auto home"
#define MSG_AUTO_HOME "Auto home"
#endif
#ifndef MSG_SET_HOME_OFFSETS
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#define MSG_SET_HOME_OFFSETS "Set home offsets"
#endif
#ifndef MSG_SET_ORIGIN
#define MSG_SET_ORIGIN "Set origin"
#define MSG_SET_ORIGIN "Set origin"
#endif
#ifndef MSG_PREHEAT_PLA
#define MSG_PREHEAT_PLA "Preheat PLA"
#define MSG_PREHEAT_PLA "Preheat PLA"
#endif
#ifndef MSG_PREHEAT_PLA_N
#define MSG_PREHEAT_PLA_N MSG_PREHEAT_PLA " "
#define MSG_PREHEAT_PLA_N MSG_PREHEAT_PLA " "
#endif
#ifndef MSG_PREHEAT_PLA_ALL
#define MSG_PREHEAT_PLA_ALL MSG_PREHEAT_PLA " All"
#define MSG_PREHEAT_PLA_ALL MSG_PREHEAT_PLA " All"
#endif
#ifndef MSG_PREHEAT_PLA_BEDONLY
#define MSG_PREHEAT_PLA_BEDONLY MSG_PREHEAT_PLA " Bed"
#define MSG_PREHEAT_PLA_BEDONLY MSG_PREHEAT_PLA " Bed"
#endif
#ifndef MSG_PREHEAT_PLA_SETTINGS
#define MSG_PREHEAT_PLA_SETTINGS MSG_PREHEAT_PLA " conf"
#define MSG_PREHEAT_PLA_SETTINGS MSG_PREHEAT_PLA " conf"
#endif
#ifndef MSG_PREHEAT_ABS
#define MSG_PREHEAT_ABS "Preheat ABS"
#define MSG_PREHEAT_ABS "Preheat ABS"
#endif
#ifndef MSG_PREHEAT_ABS_N
#define MSG_PREHEAT_ABS_N MSG_PREHEAT_ABS " "
#define MSG_PREHEAT_ABS_N MSG_PREHEAT_ABS " "
#endif
#ifndef MSG_PREHEAT_ABS_ALL
#define MSG_PREHEAT_ABS_ALL MSG_PREHEAT_ABS " All"
#define MSG_PREHEAT_ABS_ALL MSG_PREHEAT_ABS " All"
#endif
#ifndef MSG_PREHEAT_ABS_BEDONLY
#define MSG_PREHEAT_ABS_BEDONLY MSG_PREHEAT_ABS " Bed"
#define MSG_PREHEAT_ABS_BEDONLY MSG_PREHEAT_ABS " Bed"
#endif
#ifndef MSG_PREHEAT_ABS_SETTINGS
#define MSG_PREHEAT_ABS_SETTINGS MSG_PREHEAT_ABS " conf"
#define MSG_PREHEAT_ABS_SETTINGS MSG_PREHEAT_ABS " conf"
#endif
#ifndef MSG_H1
#define MSG_H1 "1"
#define MSG_H1 "1"
#endif
#ifndef MSG_H2
#define MSG_H2 "2"
#define MSG_H2 "2"
#endif
#ifndef MSG_H3
#define MSG_H3 "3"
#define MSG_H3 "3"
#endif
#ifndef MSG_H4
#define MSG_H4 "4"
#define MSG_H4 "4"
#endif
#ifndef MSG_COOLDOWN
#define MSG_COOLDOWN "Cooldown"
#define MSG_COOLDOWN "Cooldown"
#endif
#ifndef MSG_SWITCH_PS_ON
#define MSG_SWITCH_PS_ON "Switch power on"
#define MSG_SWITCH_PS_ON "Switch power on"
#endif
#ifndef MSG_SWITCH_PS_OFF
#define MSG_SWITCH_PS_OFF "Switch power off"
#define MSG_SWITCH_PS_OFF "Switch power off"
#endif
#ifndef MSG_EXTRUDE
#define MSG_EXTRUDE "Extrude"
#define MSG_EXTRUDE "Extrude"
#endif
#ifndef MSG_RETRACT
#define MSG_RETRACT "Retract"
#define MSG_RETRACT "Retract"
#endif
#ifndef MSG_MOVE_AXIS
#define MSG_MOVE_AXIS "Move axis"
#define MSG_MOVE_AXIS "Move axis"
#endif
#ifndef MSG_LEVEL_BED
#define MSG_LEVEL_BED "Level bed"
#define MSG_LEVEL_BED "Level bed"
#endif
#ifndef MSG_MOVE_X
#define MSG_MOVE_X "Move X"
#define MSG_MOVE_X "Move X"
#endif
#ifndef MSG_MOVE_Y
#define MSG_MOVE_Y "Move Y"
#define MSG_MOVE_Y "Move Y"
#endif
#ifndef MSG_MOVE_Z
#define MSG_MOVE_Z "Move Z"
#define MSG_MOVE_Z "Move Z"
#endif
#ifndef MSG_MOVE_E
#define MSG_MOVE_E "Extruder"
#define MSG_MOVE_E "Extruder"
#endif
#ifndef MSG_MOVE_E1
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E1 "1"
#endif
#ifndef MSG_MOVE_E2
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E2 "2"
#endif
#ifndef MSG_MOVE_E3
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E3 "3"
#endif
#ifndef MSG_MOVE_E4
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_E4 "4"
#endif
#ifndef MSG_MOVE_01MM
#define MSG_MOVE_01MM "Move 0.1mm"
#define MSG_MOVE_01MM "Move 0.1mm"
#endif
#ifndef MSG_MOVE_1MM
#define MSG_MOVE_1MM "Move 1mm"
#define MSG_MOVE_1MM "Move 1mm"
#endif
#ifndef MSG_MOVE_10MM
#define MSG_MOVE_10MM "Move 10mm"
#define MSG_MOVE_10MM "Move 10mm"
#endif
#ifndef MSG_SPEED
#define MSG_SPEED "Speed"
#define MSG_SPEED "Speed"
#endif
#ifndef MSG_NOZZLE
#define MSG_NOZZLE "Nozzle"
#define MSG_NOZZLE "Nozzle"
#endif
#ifndef MSG_N1
#define MSG_N1 " 1"
#define MSG_N1 " 1"
#endif
#ifndef MSG_N2
#define MSG_N2 " 2"
#define MSG_N2 " 2"
#endif
#ifndef MSG_N3
#define MSG_N3 " 3"
#define MSG_N3 " 3"
#endif
#ifndef MSG_N4
#define MSG_N4 " 4"
#define MSG_N4 " 4"
#endif
#ifndef MSG_BED
#define MSG_BED "Bed"
#define MSG_BED "Bed"
#endif
#ifndef MSG_FAN_SPEED
#define MSG_FAN_SPEED "Fan speed"
#define MSG_FAN_SPEED "Fan speed"
#endif
#ifndef MSG_FLOW
#define MSG_FLOW "Flow"
#define MSG_FLOW "Flow"
#endif
#ifndef MSG_CONTROL
#define MSG_CONTROL "Control"
#define MSG_CONTROL "Control"
#endif
#ifndef MSG_MIN
#define MSG_MIN " " LCD_STR_THERMOMETER " Min"
#define MSG_MIN " " LCD_STR_THERMOMETER " Min"
#endif
#ifndef MSG_MAX
#define MSG_MAX " " LCD_STR_THERMOMETER " Max"
#define MSG_MAX " " LCD_STR_THERMOMETER " Max"
#endif
#ifndef MSG_FACTOR
#define MSG_FACTOR " " LCD_STR_THERMOMETER " Fact"
#define MSG_FACTOR " " LCD_STR_THERMOMETER " Fact"
#endif
#ifndef MSG_AUTOTEMP
#define MSG_AUTOTEMP "Autotemp"
#define MSG_AUTOTEMP "Autotemp"
#endif
#ifndef MSG_ON
#define MSG_ON "On "
#define MSG_ON "On "
#endif
#ifndef MSG_OFF
#define MSG_OFF "Off"
#define MSG_OFF "Off"
#endif
#ifndef MSG_PID_P
#define MSG_PID_P "PID-P"
#define MSG_PID_P "PID-P"
#endif
#ifndef MSG_PID_I
#define MSG_PID_I "PID-I"
#define MSG_PID_I "PID-I"
#endif
#ifndef MSG_PID_D
#define MSG_PID_D "PID-D"
#define MSG_PID_D "PID-D"
#endif
#ifndef MSG_PID_C
#define MSG_PID_C "PID-C"
#define MSG_PID_C "PID-C"
#endif
#ifndef MSG_E1
#define MSG_E1 " E1"
#define MSG_E1 " E1"
#endif
#ifndef MSG_E2
#define MSG_E2 " E2"
#define MSG_E2 " E2"
#endif
#ifndef MSG_E3
#define MSG_E3 " E3"
#define MSG_E3 " E3"
#endif
#ifndef MSG_E4
#define MSG_E4 " E4"
#define MSG_E4 " E4"
#endif
#ifndef MSG_ACC
#define MSG_ACC "Accel"
#define MSG_ACC "Accel"
#endif
#ifndef MSG_VXY_JERK
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VXY_JERK "Vxy-jerk"
#endif
#ifndef MSG_VZ_JERK
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#endif
#ifndef MSG_VE_JERK
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VE_JERK "Ve-jerk"
#endif
#ifndef MSG_VMAX
#define MSG_VMAX "Vmax "
#define MSG_VMAX "Vmax "
#endif
#ifndef MSG_X
#define MSG_X "x"
#define MSG_X "x"
#endif
#ifndef MSG_Y
#define MSG_Y "y"
#define MSG_Y "y"
#endif
#ifndef MSG_Z
#define MSG_Z "z"
#define MSG_Z "z"
#endif
#ifndef MSG_E
#define MSG_E "e"
#define MSG_E "e"
#endif
#ifndef MSG_VMIN
#define MSG_VMIN "Vmin"
#define MSG_VMIN "Vmin"
#endif
#ifndef MSG_VTRAV_MIN
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_VTRAV_MIN "VTrav min"
#endif
#ifndef MSG_AMAX
#define MSG_AMAX "Amax "
#define MSG_AMAX "Amax "
#endif
#ifndef MSG_A_RETRACT
#define MSG_A_RETRACT "A-retract"
#define MSG_A_RETRACT "A-retract"
#endif
#ifndef MSG_A_TRAVEL
#define MSG_A_TRAVEL "A-travel"
#define MSG_A_TRAVEL "A-travel"
#endif
#ifndef MSG_XSTEPS
#define MSG_XSTEPS "Xsteps/mm"
#define MSG_XSTEPS "Xsteps/mm"
#endif
#ifndef MSG_YSTEPS
#define MSG_YSTEPS "Ysteps/mm"
#define MSG_YSTEPS "Ysteps/mm"
#endif
#ifndef MSG_ZSTEPS
#define MSG_ZSTEPS "Zsteps/mm"
#define MSG_ZSTEPS "Zsteps/mm"
#endif
#ifndef MSG_ESTEPS
#define MSG_ESTEPS "Esteps/mm"
#define MSG_ESTEPS "Esteps/mm"
#endif
#ifndef MSG_TEMPERATURE
#define MSG_TEMPERATURE "Temperature"
#define MSG_TEMPERATURE "Temperature"
#endif
#ifndef MSG_MOTION
#define MSG_MOTION "Motion"
#define MSG_MOTION "Motion"
#endif
#ifndef MSG_VOLUMETRIC
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC "Filament"
#endif
#ifndef MSG_VOLUMETRIC_ENABLED
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#endif
#ifndef MSG_FILAMENT_DIAM
#define MSG_FILAMENT_DIAM "Fil. Dia."
#define MSG_FILAMENT_DIAM "Fil. Dia."
#endif
#ifndef MSG_DIAM_E1
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E1 " 1"
#endif
#ifndef MSG_DIAM_E2
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E2 " 2"
#endif
#ifndef MSG_DIAM_E3
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E3 " 3"
#endif
#ifndef MSG_DIAM_E4
#define MSG_DIAM_E4 " 4"
#define MSG_DIAM_E4 " 4"
#endif
#ifndef MSG_CONTRAST
#define MSG_CONTRAST "LCD contrast"
#define MSG_CONTRAST "LCD contrast"
#endif
#ifndef MSG_STORE_EPROM
#define MSG_STORE_EPROM "Store memory"
#define MSG_STORE_EPROM "Store memory"
#endif
#ifndef MSG_LOAD_EPROM
#define MSG_LOAD_EPROM "Load memory"
#define MSG_LOAD_EPROM "Load memory"
#endif
#ifndef MSG_RESTORE_FAILSAFE
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
#endif
#ifndef MSG_REFRESH
#define MSG_REFRESH "Refresh"
#define MSG_REFRESH "Refresh"
#endif
#ifndef MSG_WATCH
#define MSG_WATCH "Info screen"
#define MSG_WATCH "Info screen"
#endif
#ifndef MSG_PREPARE
#define MSG_PREPARE "Prepare"
#define MSG_PREPARE "Prepare"
#endif
#ifndef MSG_TUNE
#define MSG_TUNE "Tune"
#define MSG_TUNE "Tune"
#endif
#ifndef MSG_PAUSE_PRINT
#define MSG_PAUSE_PRINT "Pause print"
#define MSG_PAUSE_PRINT "Pause print"
#endif
#ifndef MSG_RESUME_PRINT
#define MSG_RESUME_PRINT "Resume print"
#define MSG_RESUME_PRINT "Resume print"
#endif
#ifndef MSG_STOP_PRINT
#define MSG_STOP_PRINT "Stop print"
#define MSG_STOP_PRINT "Stop print"
#endif
#ifndef MSG_CARD_MENU
#define MSG_CARD_MENU "Print from SD"
#define MSG_CARD_MENU "Print from SD"
#endif
#ifndef MSG_NO_CARD
#define MSG_NO_CARD "No SD card"
#define MSG_NO_CARD "No SD card"
#endif
#ifndef MSG_DWELL
#define MSG_DWELL "Sleep..."
#define MSG_DWELL "Sleep..."
#endif
#ifndef MSG_USERWAIT
#define MSG_USERWAIT "Wait for user..."
#define MSG_USERWAIT "Wait for user..."
#endif
#ifndef MSG_RESUMING
#define MSG_RESUMING "Resuming print"
#define MSG_RESUMING "Resuming print"
#endif
#ifndef MSG_PRINT_ABORTED
#define MSG_PRINT_ABORTED "Print aborted"
#define MSG_PRINT_ABORTED "Print aborted"
#endif
#ifndef MSG_NO_MOVE
#define MSG_NO_MOVE "No move."
#define MSG_NO_MOVE "No move."
#endif
#ifndef MSG_KILLED
#define MSG_KILLED "KILLED. "
#define MSG_KILLED "KILLED. "
#endif
#ifndef MSG_STOPPED
#define MSG_STOPPED "STOPPED. "
#define MSG_STOPPED "STOPPED. "
#endif
#ifndef MSG_CONTROL_RETRACT
#define MSG_CONTROL_RETRACT "Retract mm"
#define MSG_CONTROL_RETRACT "Retract mm"
#endif
#ifndef MSG_CONTROL_RETRACT_SWAP
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
#endif
#ifndef MSG_CONTROL_RETRACTF
#define MSG_CONTROL_RETRACTF "Retract V"
#define MSG_CONTROL_RETRACTF "Retract V"
#endif
#ifndef MSG_CONTROL_RETRACT_ZLIFT
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
#endif
#ifndef MSG_CONTROL_RETRACT_RECOVER
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
#endif
#ifndef MSG_CONTROL_RETRACT_RECOVER_SWAP
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
#endif
#ifndef MSG_CONTROL_RETRACT_RECOVERF
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
#endif
#ifndef MSG_AUTORETRACT
#define MSG_AUTORETRACT "AutoRetr."
#define MSG_AUTORETRACT "AutoRetr."
#endif
#ifndef MSG_FILAMENTCHANGE
#define MSG_FILAMENTCHANGE "Change filament"
#define MSG_FILAMENTCHANGE "Change filament"
#endif
#ifndef MSG_INIT_SDCARD
#define MSG_INIT_SDCARD "Init. SD card"
#define MSG_INIT_SDCARD "Init. SD card"
#endif
#ifndef MSG_CNG_SDCARD
#define MSG_CNG_SDCARD "Change SD card"
#define MSG_CNG_SDCARD "Change SD card"
#endif
#ifndef MSG_ZPROBE_OUT
#define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_ZPROBE_OUT "Z probe out. bed"
#endif
#ifndef MSG_POSITION_UNKNOWN
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#endif
#ifndef MSG_ZPROBE_ZOFFSET
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#endif
#ifndef MSG_BABYSTEP_X
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_X "Babystep X"
#endif
#ifndef MSG_BABYSTEP_Y
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Y "Babystep Y"
#endif
#ifndef MSG_BABYSTEP_Z
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_BABYSTEP_Z "Babystep Z"
#endif
#ifndef MSG_ENDSTOP_ABORT
#define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_ENDSTOP_ABORT "Endstop abort"
#endif
#ifndef MSG_HEATING_FAILED_LCD
#define MSG_HEATING_FAILED_LCD "Heating failed"
#define MSG_HEATING_FAILED_LCD "Heating failed"
#endif
#ifndef MSG_ERR_REDUNDANT_TEMP
#define MSG_ERR_REDUNDANT_TEMP "Err: REDUNDANT TEMP ERROR"
#define MSG_ERR_REDUNDANT_TEMP "Err: REDUNDANT TEMP ERROR"
#endif
#ifndef MSG_THERMAL_RUNAWAY
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#endif
#ifndef MSG_ERR_MAXTEMP
#define MSG_ERR_MAXTEMP "Err: MAXTEMP"
#define MSG_ERR_MAXTEMP "Err: MAXTEMP"
#endif
#ifndef MSG_ERR_MINTEMP
#define MSG_ERR_MINTEMP "Err: MINTEMP"
#define MSG_ERR_MINTEMP "Err: MINTEMP"
#endif
#ifndef MSG_ERR_MAXTEMP_BED
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#endif
#ifndef MSG_ERR_MINTEMP_BED
#define MSG_ERR_MINTEMP_BED "Err: MINTEMP BED"
#define MSG_ERR_MINTEMP_BED "Err: MINTEMP BED"
#endif
#ifndef MSG_END_HOUR
#define MSG_END_HOUR "hours"
#define MSG_END_HOUR "hours"
#endif
#ifndef MSG_END_MINUTE
#define MSG_END_MINUTE "minutes"
#define MSG_END_MINUTE "minutes"
#endif
#ifndef MSG_HEATING
#define MSG_HEATING "Heating..."
#define MSG_HEATING "Heating..."
#endif
#ifndef MSG_HEATING_COMPLETE
#define MSG_HEATING_COMPLETE "Heating done."
#define MSG_HEATING_COMPLETE "Heating done."
#endif
#ifndef MSG_BED_HEATING
#define MSG_BED_HEATING "Bed Heating."
#define MSG_BED_HEATING "Bed Heating."
#endif
#ifndef MSG_BED_DONE
#define MSG_BED_DONE "Bed done."
#define MSG_BED_DONE "Bed done."
#endif
#ifndef MSG_DELTA_CALIBRATE
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#endif
#ifndef MSG_DELTA_CALIBRATE_X
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#endif
#ifndef MSG_DELTA_CALIBRATE_Y
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#endif
#ifndef MSG_DELTA_CALIBRATE_Z
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#endif
#ifndef MSG_DELTA_CALIBRATE_CENTER
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif
#if ENABLED(DELTA_CALIBRATION_MENU)
#ifndef MSG_DELTA_CALIBRATE
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#endif
#ifndef MSG_DELTA_CALIBRATE_X
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#endif
#ifndef MSG_DELTA_CALIBRATE_Y
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#endif
#ifndef MSG_DELTA_CALIBRATE_Z
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#endif
#ifndef MSG_DELTA_CALIBRATE_CENTER
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_EN_H

View File

@ -125,11 +125,11 @@
#define MSG_END_MINUTE "minutos"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Calibracion Delta"
#define MSG_DELTA_CALIBRATE_X "Calibrar X"
#define MSG_DELTA_CALIBRATE_Y "Calibrar Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrar Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrar Centro"
#define MSG_DELTA_CALIBRATE "Calibracion Delta"
#define MSG_DELTA_CALIBRATE_X "Calibrar X"
#define MSG_DELTA_CALIBRATE_Y "Calibrar Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrar Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrar Centro"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_ES_H

View File

@ -125,11 +125,11 @@
#define MSG_END_MINUTE "minutes"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_EU_H

View File

@ -125,11 +125,11 @@
#define MSG_END_MINUTE "minutes"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Kalibrointi"
#define MSG_DELTA_CALIBRATE_X "Kalibroi X"
#define MSG_DELTA_CALIBRATE_Y "Kalibroi Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibroi Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibroi Center"
#define MSG_DELTA_CALIBRATE "Delta Kalibrointi"
#define MSG_DELTA_CALIBRATE_X "Kalibroi X"
#define MSG_DELTA_CALIBRATE_Y "Kalibroi Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibroi Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibroi Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_FI_H

View File

@ -127,11 +127,11 @@
#define MSG_END_MINUTE "minutes"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_FR_H

View File

@ -125,11 +125,11 @@
#define MSG_END_MINUTE "minuti"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Calibraz. Delta"
#define MSG_DELTA_CALIBRATE_X "Calibra X"
#define MSG_DELTA_CALIBRATE_Y "Calibra Y"
#define MSG_DELTA_CALIBRATE_Z "Calibra Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibra Center"
#define MSG_DELTA_CALIBRATE "Calibraz. Delta"
#define MSG_DELTA_CALIBRATE_X "Calibra X"
#define MSG_DELTA_CALIBRATE_Y "Calibra Y"
#define MSG_DELTA_CALIBRATE_Z "Calibra Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibra Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_IT_H

View File

@ -136,11 +136,11 @@
*/
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_KANA_H

View File

@ -131,11 +131,11 @@
#define MSG_END_MINUTE "minutes"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_KANA_UTF_H

View File

@ -125,11 +125,11 @@
#define MSG_END_MINUTE "minutes"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibratie"
#define MSG_DELTA_CALIBRATE_X "Kalibreer X"
#define MSG_DELTA_CALIBRATE_Y "Kalibreer Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibreer Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibreer Midden"
#define MSG_DELTA_CALIBRATE "Delta Calibratie"
#define MSG_DELTA_CALIBRATE_X "Kalibreer X"
#define MSG_DELTA_CALIBRATE_Y "Kalibreer Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibreer Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibreer Midden"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_NL_H

View File

@ -126,11 +126,11 @@
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_PL_H

View File

@ -13,7 +13,7 @@
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " pronto."
#define WELCOME_MSG MACHINE_NAME " pronto."
#define MSG_SD_INSERTED "Cartao inserido"
#define MSG_SD_REMOVED "Cartao removido"
#define MSG_MAIN " Menu principal"
@ -125,11 +125,11 @@
#define MSG_END_MINUTE "minutos"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_PT_BR_H

View File

@ -125,11 +125,11 @@
#define MSG_END_MINUTE "minutos"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Delta Calibracao"
#define MSG_DELTA_CALIBRATE_X "Calibrar X"
#define MSG_DELTA_CALIBRATE_Y "Calibrar Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrar Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrar Centro"
#define MSG_DELTA_CALIBRATE "Delta Calibracao"
#define MSG_DELTA_CALIBRATE_X "Calibrar X"
#define MSG_DELTA_CALIBRATE_Y "Calibrar Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrar Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrar Centro"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_PT_H

View File

@ -126,11 +126,11 @@
#define MSG_END_MINUTE "минут"
#if ENABLED(DELTA_CALIBRATION_MENU)
#define MSG_DELTA_CALIBRATE "Калибровка Delta"
#define MSG_DELTA_CALIBRATE_X "Калибровать X"
#define MSG_DELTA_CALIBRATE_Y "Калибровать Y"
#define MSG_DELTA_CALIBRATE_Z "Калибровать Z"
#define MSG_DELTA_CALIBRATE_CENTER "Калибровать Center"
#define MSG_DELTA_CALIBRATE "Калибровка Delta"
#define MSG_DELTA_CALIBRATE_X "Калибровать X"
#define MSG_DELTA_CALIBRATE_Y "Калибровать Y"
#define MSG_DELTA_CALIBRATE_Z "Калибровать Z"
#define MSG_DELTA_CALIBRATE_CENTER "Калибровать Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_RU_H

View File

@ -5,7 +5,7 @@
mesh_bed_leveling mbl;
mesh_bed_leveling::mesh_bed_leveling() { reset(); }
void mesh_bed_leveling::reset() {
active = 0;
for (int y = 0; y < MESH_NUM_Y_POINTS; y++)

View File

@ -9,45 +9,45 @@
public:
uint8_t active;
float z_values[MESH_NUM_Y_POINTS][MESH_NUM_X_POINTS];
mesh_bed_leveling();
void reset();
float get_x(int i) { return MESH_MIN_X + MESH_X_DIST * i; }
float get_y(int i) { return MESH_MIN_Y + MESH_Y_DIST * i; }
void set_z(int ix, int iy, float z) { z_values[iy][ix] = z; }
int select_x_index(float x) {
int i = 1;
while (x > get_x(i) && i < MESH_NUM_X_POINTS-1) i++;
while (x > get_x(i) && i < MESH_NUM_X_POINTS - 1) i++;
return i - 1;
}
int select_y_index(float y) {
int i = 1;
while (y > get_y(i) && i < MESH_NUM_Y_POINTS - 1) i++;
return i - 1;
}
float calc_z0(float a0, float a1, float z1, float a2, float z2) {
float delta_z = (z2 - z1)/(a2 - a1);
float delta_z = (z2 - z1) / (a2 - a1);
float delta_a = a0 - a1;
return z1 + delta_a * delta_z;
}
float get_z(float x0, float y0) {
int x_index = select_x_index(x0);
int y_index = select_y_index(y0);
float z1 = calc_z0(x0,
get_x(x_index), z_values[y_index][x_index],
get_x(x_index+1), z_values[y_index][x_index+1]);
get_x(x_index + 1), z_values[y_index][x_index + 1]);
float z2 = calc_z0(x0,
get_x(x_index), z_values[y_index+1][x_index],
get_x(x_index+1), z_values[y_index+1][x_index+1]);
get_x(x_index), z_values[y_index + 1][x_index],
get_x(x_index + 1), z_values[y_index + 1][x_index + 1]);
float z0 = calc_z0(y0,
get_y(y_index), z1,
get_y(y_index+1), z2);
get_y(y_index + 1), z2);
return z0;
}
};

View File

@ -207,7 +207,7 @@
#endif
#if ENABLED(DISABLE_XMIN_ENDSTOP)
#undef X_MIN_PIN
#undef X_MIN_PIN
#define X_MIN_PIN -1
#endif
@ -226,7 +226,7 @@
#endif
#if ENABLED(DISABLE_ZMIN_ENDSTOP)
#undef Z_MIN_PIN
#undef Z_MIN_PIN
#define Z_MIN_PIN -1
#endif
@ -243,13 +243,13 @@
#endif
#define SENSITIVE_PINS { 0, 1, \
X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, \
Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, \
Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, Z_MIN_PROBE_PIN, \
PS_ON_PIN, HEATER_BED_PIN, FAN_PIN, \
_E0_PINS _E1_PINS _E2_PINS _E3_PINS \
analogInputToDigitalPin(TEMP_BED_PIN) \
}
X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, \
Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, \
Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, Z_MIN_PROBE_PIN, \
PS_ON_PIN, HEATER_BED_PIN, FAN_PIN, \
_E0_PINS _E1_PINS _E2_PINS _E3_PINS \
analogInputToDigitalPin(TEMP_BED_PIN) \
}
#define HAS_DIGIPOTSS (DIGIPOTSS_PIN >= 0)

View File

@ -53,7 +53,7 @@
#define SDSS 20
#if DISABLED(SDSUPPORT)
// these pins are defined in the SD library if building with SD support
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 9
#define MISO_PIN 11
#define MOSI_PIN 10

View File

@ -15,10 +15,10 @@
#define EXTRUDER_3_AUTO_FAN_PIN 5
//
//This section is to swap the MIN and MAX pins because the X3 Pro comes with only
//MIN endstops soldered onto the board. Delta code wants the homing endstops to be
//MIN endstops soldered onto the board. Delta code wants the homing endstops to be
//the MAX so I swapped them here.
//
#if ENABLED(DELTA)
#if ENABLED(DELTA)
#undef X_MIN_PIN
#undef X_MAX_PIN
#undef Y_MIN_PIN
@ -32,14 +32,14 @@
#define Y_MAX_PIN 14
#define Z_MIN_PIN 19
#define Z_MAX_PIN 18
#endif
#endif
//
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
//#undef Z_MIN_PIN
//#define Z_MIN_PIN 15
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
//#undef Z_MIN_PIN
//#define Z_MIN_PIN 15
// Define a pin to use as the signal pin on Arduino for the Z probe endstop.
#define Z_MIN_PROBE_PIN 19
#endif
#endif
//
#define E2_STEP_PIN 23
#define E2_DIR_PIN 25
@ -74,32 +74,32 @@
//
//These Servo pins are for when they are defined. Tested for usage with bed leveling
//on a Delta with 1 servo. Running through the Z servo endstop in code.
//on a Delta with 1 servo. Running through the Z servo endstop in code.
//Physical wire attachment was done on EXT1 on the GND, 5V, and D47 pins.
//
#define SERVO0_PIN 47
//LCD Pins//
#if ENABLED(VIKI2) || ENABLED(miniVIKI)
#if ENABLED(VIKI2) || ENABLED(miniVIKI)
#define BEEPER_PIN 33
// Pins for DOGM SPI LCD Support
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 44
#define DOGLCD_CS 45
#define LCD_SCREEN_ROT_180
//The encoder and click button
//The encoder and click button
#define BTN_EN1 22
#define BTN_EN2 7
#define BTN_ENC 39 //the click switch
#define SDSS 53
#define SD_DETECT_PIN 49
#define KILL_PIN 31
#endif
#if ENABLED(TEMP_STAT_LEDS)
#define KILL_PIN 31
#endif
#if ENABLED(TEMP_STAT_LEDS)
#define STAT_LED_RED 32
#define STAT_LED_BLUE 35
#endif
#endif

View File

@ -57,7 +57,7 @@
#define SD_DETECT_PIN 12
#if DISABLED(SDSUPPORT)
// these pins are defined in the SD library if building with SD support
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 21
#define MISO_PIN 23
#define MOSI_PIN 22

View File

@ -37,9 +37,9 @@
#define E0_ENABLE_PIN 13
#define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder)
#define TEMP_1_PIN -1
#define TEMP_1_PIN -1
#define TEMP_2_PIN -1
#define TEMP_BED_PIN 5 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
#define TEMP_BED_PIN 5 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
#define SDPOWER -1
#define SDSS 4
#define HEATER_2_PIN -1

View File

@ -3,7 +3,7 @@
*
* These Pins are assigned for the modified GEN7 Board from Alfons3.
* Please review the pins and adjust them for your needs.
*/
*/
#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__)
#error Oops! Make sure you have 'Gen7' selected from the 'Tools -> Boards' menu.

View File

@ -25,7 +25,7 @@
#define Y_DIR_PIN 66 // A12
#define Y_ENABLE_PIN 64//A10
#define Y_MIN_PIN 38
#define Y_MAX_PIN 41
#define Y_MAX_PIN 41
#define Z_STEP_PIN 68 // A14
#define Z_DIR_PIN 69 // A15
@ -81,24 +81,24 @@
#endif
#if ENABLED(MINIPANEL)
#define BEEPER_PIN 46
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 47
#define DOGLCD_CS 45
#define LCD_PIN_BL 44 // backlight LED on PA3
#define KILL_PIN 12
// GLCD features
//#define LCD_CONTRAST 190
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
//The encoder and click button
#define BTN_EN1 48
#define BTN_EN2 11
#define BTN_ENC 10 //the click switch
//not connected to a pin
#define SD_DETECT_PIN 49
#define BEEPER_PIN 46
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 47
#define DOGLCD_CS 45
#define LCD_PIN_BL 44 // backlight LED on PA3
#define KILL_PIN 12
// GLCD features
//#define LCD_CONTRAST 190
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
//The encoder and click button
#define BTN_EN1 48
#define BTN_EN2 11
#define BTN_ENC 10 //the click switch
//not connected to a pin
#define SD_DETECT_PIN 49
#endif //Minipanel

View File

@ -23,17 +23,17 @@
#define X_DIR_PIN 57
#define X_ENABLE_PIN 59
#define X_MIN_PIN 37
#define X_MAX_PIN 40 // put to -1 to disable
#define X_MAX_PIN 40 // put to -1 to disable
#define Y_STEP_PIN 5
#define Y_DIR_PIN 17
#define Y_STEP_PIN 5
#define Y_DIR_PIN 17
#define Y_ENABLE_PIN 4
#define Y_MIN_PIN 41
#define Y_MAX_PIN 38 // put to -1 to disable
#define Z_STEP_PIN 16
#define Z_STEP_PIN 16
#define Z_DIR_PIN 11
#define Z_ENABLE_PIN 3
#define Z_ENABLE_PIN 3
#define Z_MIN_PIN 18
#define Z_MAX_PIN 19 // put to -1 to disable
@ -91,4 +91,4 @@
#define BLEN_B 1
#define BLEN_A 0
#define SD_DETECT_PIN -1 // Megatronics doesn't use this
#define SD_DETECT_PIN -1 // Megatronics doesn't use this

View File

@ -19,7 +19,7 @@
#undef E0_MS2_PIN
#undef E1_MS1_PIN
#undef E1_MS2_PIN
#define X_STEP_PIN 37
#define X_DIR_PIN 48
#define X_MIN_PIN 12

View File

@ -88,26 +88,26 @@
#define SDSS 40 //use SD card on Panelolu2 (Teensyduino pin mapping)
#endif // LCD_I2C_PANELOLU2
//not connected to a pin
#define SD_DETECT_PIN -1
#define SD_DETECT_PIN -1
#endif // ULTRA_LCD && NEWPANEL
#if ENABLED(VIKI2) || ENABLED(miniVIKI)
#define BEEPER_PIN 32 //FastIO
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 42 //Non-FastIO
#define DOGLCD_CS 43 //Non-FastIO
#define LCD_SCREEN_ROT_180
//The encoder and click button (FastIO Pins)
#define BTN_EN1 26
#define BTN_EN2 27
#define BTN_ENC 47 //the click switch
#define BEEPER_PIN 32 //FastIO
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 42 //Non-FastIO
#define DOGLCD_CS 43 //Non-FastIO
#define LCD_SCREEN_ROT_180
#define SDSS 45
#define SD_DETECT_PIN -1 // FastIO (Manual says 72 I'm not certain cause I can't test)
//The encoder and click button (FastIO Pins)
#define BTN_EN1 26
#define BTN_EN2 27
#define BTN_ENC 47 //the click switch
#if ENABLED(TEMP_STAT_LEDS)
#define STAT_LED_RED 12 //Non-FastIO
#define STAT_LED_BLUE 10 //Non-FastIO
#endif
#define SDSS 45
#define SD_DETECT_PIN -1 // FastIO (Manual says 72 I'm not certain cause I can't test)
#if ENABLED(TEMP_STAT_LEDS)
#define STAT_LED_RED 12 //Non-FastIO
#define STAT_LED_BLUE 10 //Non-FastIO
#endif
#endif

View File

@ -28,7 +28,7 @@
#undef E0_MS2_PIN
#undef E1_MS1_PIN
#undef E1_MS2_PIN
#define X_STEP_PIN 37
#define X_DIR_PIN 48
#define X_MIN_PIN 12
@ -89,7 +89,7 @@
#define SDPOWER -1
#define SDSS 53
#define LED_PIN 13
#define FAN_PIN 8
#define FAN_PIN 8
/**********************************************************
Fan Pins
@ -161,26 +161,26 @@
#endif // ULTRA_LCD
#if ENABLED(VIKI2) || ENABLED(miniVIKI)
#define BEEPER_PIN 44
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 70
#define DOGLCD_CS 71
#define LCD_SCREEN_ROT_180
//The encoder and click button
#define BTN_EN1 85
#define BTN_EN2 84
#define BTN_ENC 83 //the click switch
#define BEEPER_PIN 44
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 70
#define DOGLCD_CS 71
#define LCD_SCREEN_ROT_180
#define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board
//The encoder and click button
#define BTN_EN1 85
#define BTN_EN2 84
#define BTN_ENC 83 //the click switch
#define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board
#if ENABLED(TEMP_STAT_LEDS)
#define STAT_LED_RED 22
#define STAT_LED_BLUE 32
#define STAT_LED_RED 22
#define STAT_LED_BLUE 32
#endif
#endif // VIKI2/miniVIKI
#if ENABLED(FILAMENT_SENSOR)
//Filip added pin for Filament sensor analog input
//Filip added pin for Filament sensor analog input
#define FILWIDTH_PIN 3
#endif

View File

@ -170,26 +170,26 @@
#define DOGLCD_A0 27
#define LCD_PIN_BL 33
#elif ENABLED(MINIPANEL)
#define BEEPER_PIN 42
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 44
#define DOGLCD_CS 66
#define LCD_PIN_BL 65 // backlight LED on A11/D65
#define SDSS 53
#define KILL_PIN 64
// GLCD features
//#define LCD_CONTRAST 190
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
//The encoder and click button
#define BTN_EN1 40
#define BTN_EN2 63
#define BTN_ENC 59 //the click switch
//not connected to a pin
#define SD_DETECT_PIN 49
#define BEEPER_PIN 42
// Pins for DOGM SPI LCD Support
#define DOGLCD_A0 44
#define DOGLCD_CS 66
#define LCD_PIN_BL 65 // backlight LED on A11/D65
#define SDSS 53
#define KILL_PIN 64
// GLCD features
//#define LCD_CONTRAST 190
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
//The encoder and click button
#define BTN_EN1 40
#define BTN_EN2 63
#define BTN_ENC 59 //the click switch
//not connected to a pin
#define SD_DETECT_PIN 49
#else

View File

@ -95,9 +95,9 @@
#define LCD_PINS_D4 17 //SCK (CLK) clock
#define BEEPER_PIN 27 // Pin 27 is taken by LED_PIN, but Melzi LED does nothing with Marlin so this can be used for BEEPER_PIN. You can use this pin with M42 instead of BEEPER_PIN.
#else // Sanguinololu 1.3
#define LCD_PINS_RS 4
#define LCD_PINS_ENABLE 17
#define LCD_PINS_D4 30
#define LCD_PINS_RS 4
#define LCD_PINS_ENABLE 17
#define LCD_PINS_D4 30
#define LCD_PINS_D5 29
#define LCD_PINS_D6 28
#define LCD_PINS_D7 27
@ -110,7 +110,7 @@
#define LCD_CONTRAST 1
#endif
// Uncomment screen orientation
#define LCD_SCREEN_ROT_0
//#define LCD_SCREEN_ROT_90

View File

@ -46,7 +46,7 @@
#define TEMP_2_PIN -1
#if DISABLED(SDSUPPORT)
// these pins are defined in the SD library if building with SD support
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 9
#define MISO_PIN 11
#define MOSI_PIN 10

View File

@ -11,32 +11,32 @@
*
* USB
* GND GND |-----#####-----| +5V ATX +5SB
* ATX PS_ON PWM 27 |b7 ##### b6| 26 PWM* Stepper Enable
* PWM 0 |d0 b5| 25 PWM*
* PWM 1 |d1 b4| 24 PWM
* ATX PS_ON PWM 27 |b7 ##### b6| 26 PWM* Stepper Enable
* PWM 0 |d0 b5| 25 PWM*
* PWM 1 |d1 b4| 24 PWM
* X_MIN 2 |d2 b3| 23 MISO_PIN
* Y_MIN 3 |d3 b2| 22 MOSI_PIN
* Z_MIN 4 |d4 * * b1| 21 SCK_PIN
* 5 |d5 e e b0| 20 SDSS
* LED 6 |d6 5 4 e7| 19
* 7 |d7 e6| 18
* LCD RS 8 |e0 | GND
* LCD EN 9 |e1 a4 a0 R| AREF
* LCD D4 10 |c0 a5 a1 f0| 38 A0 ENC_1
* Z_MIN 4 |d4 * * b1| 21 SCK_PIN
* 5 |d5 e e b0| 20 SDSS
* LED 6 |d6 5 4 e7| 19
* 7 |d7 e6| 18
* LCD RS 8 |e0 | GND
* LCD EN 9 |e1 a4 a0 R| AREF
* LCD D4 10 |c0 a5 a1 f0| 38 A0 ENC_1
* LCD D5 11 |c1 a6 a2 f1| 39 A1 ENC_2
* LCD D6 12 |c2 a7 a3 f2| 40 A2 ENC_CLK
* LCD D6 13 |c3 f3| 41 A3
* Bed Heat PWM 14 |c4 V G R f4| 42 A4
* Extruder Heat PWM 15 |c5 c n S f5| 43 A5
* LCD D6 13 |c3 f3| 41 A3
* Bed Heat PWM 14 |c4 V G R f4| 42 A4
* Extruder Heat PWM 15 |c5 c n S f5| 43 A5
* Fan PWM 16 |c6 c d T f6| 44 A6 Bed TC
* 17 |c7 * * * f7| 45 A7 Extruder TC * 4.7k * +5
* -----------------
* 17 |c7 * * * f7| 45 A7 Extruder TC * 4.7k * +5
* -----------------
*
* Interior E4: 36, INT4
* Interior E5: 37, INT5
* Interior PA0-7: 28-35 -- Printrboard and Teensylu use these pins for step & direction:
* T++ PA Signal Marlin
*
*
* Z STEP 32 a4 a0 28 X STEP
* Z DIR 33 a5 a1 29 X DIR
* E STEP 34 a6 a2 30 Y STEP
@ -56,7 +56,7 @@
#define X_STEP_PIN 28 // 0 Marlin
#define X_DIR_PIN 29 // 1 Marlin
#define X_ENABLE_PIN 26
#define X_ENABLE_PIN 26
#define Y_STEP_PIN 30 // 2 Marlin
#define Y_DIR_PIN 31 // 3
@ -86,7 +86,7 @@
#define TEMP_2_PIN -1
#define SDPOWER -1
#define SD_DETECT_PIN -1
#define SD_DETECT_PIN -1
#define SDSS 20 // 8
#define LED_PIN 6
#define PS_ON_PIN 27
@ -94,7 +94,7 @@
#define ALARM_PIN -1
#if DISABLED(SDSUPPORT)
// these pins are defined in the SD library if building with SD support
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 21 // 9
#define MISO_PIN 23 // 11
#define MOSI_PIN 22 // 10

View File

@ -61,7 +61,7 @@
#define ALARM_PIN -1
#if DISABLED(SDSUPPORT)
// these pins are defined in the SD library if building with SD support
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 9
#define MISO_PIN 11
#define MOSI_PIN 10
@ -78,7 +78,7 @@
#define SDSS 40 //use SD card on Panelolu2 (Teensyduino pin mapping)
#endif // LCD_I2C_PANELOLU2
#define SD_DETECT_PIN -1
#define SD_DETECT_PIN -1
#endif // ULTRA_LCD && NEWPANEL

View File

@ -118,7 +118,7 @@ uint8_t g_uc_extruder_last_move[EXTRUDERS] = { 0 };
// Old direction bits. Used for speed calculations
static unsigned char old_direction_bits = 0;
// Segment times (in µs). Used for speed calculations
static long axis_segment_time[2][3] = { {MAX_FREQ_TIME+1,0,0}, {MAX_FREQ_TIME+1,0,0} };
static long axis_segment_time[2][3] = { {MAX_FREQ_TIME + 1, 0, 0}, {MAX_FREQ_TIME + 1, 0, 0} };
#endif
#if ENABLED(FILAMENT_SENSOR)
@ -157,7 +157,7 @@ FORCE_INLINE float intersection_distance(float initial_rate, float final_rate, f
// Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors.
void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exit_factor) {
void calculate_trapezoid_for_block(block_t* block, float entry_factor, float exit_factor) {
unsigned long initial_rate = ceil(block->nominal_rate * entry_factor); // (step/min)
unsigned long final_rate = ceil(block->nominal_rate * exit_factor); // (step/min)
@ -182,17 +182,17 @@ void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exi
plateau_steps = 0;
}
#if ENABLED(ADVANCE)
volatile long initial_advance = block->advance * entry_factor * entry_factor;
volatile long final_advance = block->advance * exit_factor * exit_factor;
#endif // ADVANCE
#if ENABLED(ADVANCE)
volatile long initial_advance = block->advance * entry_factor * entry_factor;
volatile long final_advance = block->advance * exit_factor * exit_factor;
#endif // ADVANCE
// block->accelerate_until = accelerate_steps;
// block->decelerate_after = accelerate_steps+plateau_steps;
CRITICAL_SECTION_START; // Fill variables used by the stepper in a critical section
if (!block->busy) { // Don't update variables if block is busy.
block->accelerate_until = accelerate_steps;
block->decelerate_after = accelerate_steps+plateau_steps;
block->decelerate_after = accelerate_steps + plateau_steps;
block->initial_rate = initial_rate;
block->final_rate = final_rate;
#if ENABLED(ADVANCE)
@ -219,7 +219,7 @@ FORCE_INLINE float max_allowable_speed(float acceleration, float target_velocity
// The kernel called by planner_recalculate() when scanning the plan from last to first entry.
void planner_reverse_pass_kernel(block_t *previous, block_t *current, block_t *next) {
void planner_reverse_pass_kernel(block_t* previous, block_t* current, block_t* next) {
if (!current) return;
UNUSED(previous);
@ -233,7 +233,7 @@ void planner_reverse_pass_kernel(block_t *previous, block_t *current, block_t *n
// for max allowable speed if block is decelerating and nominal length is false.
if (!current->nominal_length_flag && current->max_entry_speed > next->entry_speed) {
current->entry_speed = min(current->max_entry_speed,
max_allowable_speed(-current->acceleration, next->entry_speed, current->millimeters));
max_allowable_speed(-current->acceleration, next->entry_speed, current->millimeters));
}
else {
current->entry_speed = current->max_entry_speed;
@ -256,11 +256,11 @@ void planner_reverse_pass() {
if (BLOCK_MOD(block_buffer_head - tail + BLOCK_BUFFER_SIZE) > 3) { // moves queued
block_index = BLOCK_MOD(block_buffer_head - 3);
block_t *block[3] = { NULL, NULL, NULL };
block_t* block[3] = { NULL, NULL, NULL };
while (block_index != tail) {
block_index = prev_block_index(block_index);
block[2]= block[1];
block[1]= block[0];
block[2] = block[1];
block[1] = block[0];
block[0] = &block_buffer[block_index];
planner_reverse_pass_kernel(block[0], block[1], block[2]);
}
@ -268,7 +268,7 @@ void planner_reverse_pass() {
}
// The kernel called by planner_recalculate() when scanning the plan from first to last entry.
void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *next) {
void planner_forward_pass_kernel(block_t* previous, block_t* current, block_t* next) {
if (!previous) return;
UNUSED(next);
@ -279,8 +279,7 @@ void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *n
if (!previous->nominal_length_flag) {
if (previous->entry_speed < current->entry_speed) {
double entry_speed = min(current->entry_speed,
max_allowable_speed(-previous->acceleration, previous->entry_speed, previous->millimeters));
max_allowable_speed(-previous->acceleration, previous->entry_speed, previous->millimeters));
// Check for junction speed change
if (current->entry_speed != entry_speed) {
current->entry_speed = entry_speed;
@ -294,7 +293,7 @@ void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *n
// implements the forward pass.
void planner_forward_pass() {
uint8_t block_index = block_buffer_tail;
block_t *block[3] = { NULL, NULL, NULL };
block_t* block[3] = { NULL, NULL, NULL };
while (block_index != block_buffer_head) {
block[0] = block[1];
@ -311,8 +310,8 @@ void planner_forward_pass() {
// updating the blocks.
void planner_recalculate_trapezoids() {
int8_t block_index = block_buffer_tail;
block_t *current;
block_t *next = NULL;
block_t* current;
block_t* next = NULL;
while (block_index != block_buffer_head) {
current = next;
@ -326,7 +325,7 @@ void planner_recalculate_trapezoids() {
current->recalculate_flag = false; // Reset current only to ensure next trapezoid is computed
}
}
block_index = next_block_index( block_index );
block_index = next_block_index(block_index);
}
// Last/newest block in buffer. Exit speed is set with MINIMUM_PLANNER_SPEED. Always recalculated.
if (next) {
@ -362,7 +361,7 @@ void planner_recalculate() {
void plan_init() {
block_buffer_head = block_buffer_tail = 0;
memset(position, 0, sizeof(position)); // clear position
for (int i=0; i<NUM_AXIS; i++) previous_speed[i] = 0.0;
for (int i = 0; i < NUM_AXIS; i++) previous_speed[i] = 0.0;
previous_nominal_speed = 0.0;
}
@ -378,7 +377,7 @@ void plan_init() {
uint8_t block_index = block_buffer_tail;
while (block_index != block_buffer_head) {
block_t *block = &block_buffer[block_index];
block_t* block = &block_buffer[block_index];
if (block->steps[X_AXIS] || block->steps[Y_AXIS] || block->steps[Z_AXIS]) {
float se = (float)block->steps[E_AXIS] / block->step_event_count * block->nominal_speed; // mm/sec;
if (se > high) high = se;
@ -395,7 +394,7 @@ void plan_init() {
oldt = t;
setTargetHotend0(t);
}
#endif
#endif //AUTOTEMP
void check_axes_activity() {
unsigned char axis_active[NUM_AXIS] = { 0 },
@ -405,7 +404,7 @@ void check_axes_activity() {
tail_e_to_p_pressure = EtoPPressure;
#endif
block_t *block;
block_t* block;
if (blocks_queued()) {
uint8_t block_index = block_buffer_tail;
@ -417,7 +416,7 @@ void check_axes_activity() {
#endif
while (block_index != block_buffer_head) {
block = &block_buffer[block_index];
for (int i=0; i<NUM_AXIS; i++) if (block->steps[i]) axis_active[i]++;
for (int i = 0; i < NUM_AXIS; i++) if (block->steps[i]) axis_active[i]++;
block_index = next_block_index(block_index);
}
}
@ -465,10 +464,10 @@ void check_axes_activity() {
#if ENABLED(BARICUDA)
#if HAS_HEATER_1
analogWrite(HEATER_1_PIN,tail_valve_pressure);
analogWrite(HEATER_1_PIN, tail_valve_pressure);
#endif
#if HAS_HEATER_2
analogWrite(HEATER_2_PIN,tail_e_to_p_pressure);
analogWrite(HEATER_2_PIN, tail_e_to_p_pressure);
#endif
#endif
}
@ -479,9 +478,9 @@ float junction_deviation = 0.1;
// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
// calculation the caller must also provide the physical length of the line in millimeters.
#if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING)
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t extruder)
void plan_buffer_line(float x, float y, float z, const float& e, float feed_rate, const uint8_t extruder)
#else
void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t extruder)
void plan_buffer_line(const float& x, const float& y, const float& z, const float& e, float feed_rate, const uint8_t extruder)
#endif // AUTO_BED_LEVELING_FEATURE
{
// Calculate the buffer head after we push this byte
@ -536,7 +535,7 @@ float junction_deviation = 0.1;
#endif
// Prepare to set up new block
block_t *block = &block_buffer[block_buffer_head];
block_t* block = &block_buffer[block_buffer_head];
// Mark block as not busy (Not executed by the stepper interrupt)
block->busy = false;
@ -626,7 +625,7 @@ float junction_deviation = 0.1;
if (block->steps[E_AXIS]) {
if (DISABLE_INACTIVE_EXTRUDER) { //enable only selected extruder
for (int i=0; i<EXTRUDERS; i++)
for (int i = 0; i < EXTRUDERS; i++)
if (g_uc_extruder_last_move[i] > 0) g_uc_extruder_last_move[i]--;
switch(extruder) {
@ -883,9 +882,9 @@ float junction_deviation = 0.1;
// Compute path unit vector
double unit_vec[3];
unit_vec[X_AXIS] = delta_mm[X_AXIS]*inverse_millimeters;
unit_vec[Y_AXIS] = delta_mm[Y_AXIS]*inverse_millimeters;
unit_vec[Z_AXIS] = delta_mm[Z_AXIS]*inverse_millimeters;
unit_vec[X_AXIS] = delta_mm[X_AXIS] * inverse_millimeters;
unit_vec[Y_AXIS] = delta_mm[Y_AXIS] * inverse_millimeters;
unit_vec[Z_AXIS] = delta_mm[Z_AXIS] * inverse_millimeters;
// Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
// Let a circle be tangent to both previous and current path line segments, where the junction
@ -903,18 +902,17 @@ float junction_deviation = 0.1;
// Compute cosine of angle between previous and current path. (prev_unit_vec is negative)
// NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity.
double cos_theta = - previous_unit_vec[X_AXIS] * unit_vec[X_AXIS]
- previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS]
- previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ;
- previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS]
- previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ;
// Skip and use default max junction speed for 0 degree acute junction.
if (cos_theta < 0.95) {
vmax_junction = min(previous_nominal_speed,block->nominal_speed);
vmax_junction = min(previous_nominal_speed, block->nominal_speed);
// Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds.
if (cos_theta > -0.95) {
// Compute maximum junction velocity based on maximum acceleration and junction deviation
double sin_theta_d2 = sqrt(0.5*(1.0-cos_theta)); // Trig half angle identity. Always positive.
double sin_theta_d2 = sqrt(0.5 * (1.0 - cos_theta)); // Trig half angle identity. Always positive.
vmax_junction = min(vmax_junction,
sqrt(block->acceleration * junction_deviation * sin_theta_d2/(1.0-sin_theta_d2)) );
sqrt(block->acceleration * junction_deviation * sin_theta_d2 / (1.0 - sin_theta_d2)));
}
}
}
@ -1018,9 +1016,9 @@ float junction_deviation = 0.1;
#endif // AUTO_BED_LEVELING_FEATURE && !DELTA
#if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING)
void plan_set_position(float x, float y, float z, const float &e)
void plan_set_position(float x, float y, float z, const float& e)
#else
void plan_set_position(const float &x, const float &y, const float &z, const float &e)
void plan_set_position(const float& x, const float& y, const float& z, const float& e)
#endif // AUTO_BED_LEVELING_FEATURE || MESH_BED_LEVELING
{
#if ENABLED(MESH_BED_LEVELING)
@ -1036,10 +1034,10 @@ float junction_deviation = 0.1;
st_set_position(nx, ny, nz, ne);
previous_nominal_speed = 0.0; // Resets planner junction speeds. Assumes start from rest.
for (int i=0; i<NUM_AXIS; i++) previous_speed[i] = 0.0;
for (int i = 0; i < NUM_AXIS; i++) previous_speed[i] = 0.0;
}
void plan_set_e_position(const float &e) {
void plan_set_e_position(const float& e) {
position[E_AXIS] = lround(e * axis_steps_per_unit[E_AXIS]);
st_set_e_position(position[E_AXIS]);
}

View File

@ -18,7 +18,7 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
// This module is to be considered a sub-module of stepper.c. Please don't include
// This module is to be considered a sub-module of stepper.c. Please don't include
// this file from any other module.
#ifndef PLANNER_H
@ -26,7 +26,7 @@
#include "Marlin.h"
// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in
// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in
// the source g-code and may never actually be reached if acceleration management is active.
typedef struct {
// Fields used by the bresenham algorithm for tracing the line
@ -46,7 +46,7 @@ typedef struct {
// Fields used by the motion planner to manage acceleration
// float speed_x, speed_y, speed_z, speed_e; // Nominal mm/sec for each axis
float nominal_speed; // The nominal speed for this block in mm/sec
float nominal_speed; // The nominal speed for this block in mm/sec
float entry_speed; // Entry speed at previous-current junction in mm/sec
float max_entry_speed; // Maximum allowable junction entry speed in mm/sec
float millimeters; // The total travel of this block in mm
@ -55,8 +55,8 @@ typedef struct {
unsigned char nominal_length_flag; // Planner flag for nominal speed always reached
// Settings for the trapezoid generator
unsigned long nominal_rate; // The nominal step rate for this block in step_events/sec
unsigned long initial_rate; // The jerk-adjusted step rate at start of block
unsigned long nominal_rate; // The nominal step rate for this block in step_events/sec
unsigned long initial_rate; // The jerk-adjusted step rate at start of block
unsigned long final_rate; // The minimal rate at exit
unsigned long acceleration_st; // acceleration steps/sec^2
unsigned long fan_speed;
@ -69,7 +69,7 @@ typedef struct {
#define BLOCK_MOD(n) ((n)&(BLOCK_BUFFER_SIZE-1))
// Initialize the motion plan subsystem
// Initialize the motion plan subsystem
void plan_init();
void check_axes_activity();
@ -97,23 +97,23 @@ FORCE_INLINE uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block
* Add a new linear movement to the buffer. x, y, z are the signed, absolute target position in
* millimeters. Feed rate specifies the (target) speed of the motion.
*/
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t extruder);
void plan_buffer_line(float x, float y, float z, const float& e, float feed_rate, const uint8_t extruder);
/**
* Set the planner positions. Used for G92 instructions.
* Multiplies by axis_steps_per_unit[] to set stepper positions.
* Clears previous speed values.
*/
void plan_set_position(float x, float y, float z, const float &e);
void plan_set_position(float x, float y, float z, const float& e);
#else
void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t extruder);
void plan_set_position(const float &x, const float &y, const float &z, const float &e);
void plan_buffer_line(const float& x, const float& y, const float& z, const float& e, float feed_rate, const uint8_t extruder);
void plan_set_position(const float& x, const float& y, const float& z, const float& e);
#endif // AUTO_BED_LEVELING_FEATURE || MESH_BED_LEVELING
void plan_set_e_position(const float &e);
void plan_set_e_position(const float& e);
//===========================================================================
//============================= public variables ============================
@ -142,7 +142,7 @@ extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
extern block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instructions
extern volatile unsigned char block_buffer_head; // Index of the next block to be pushed
extern volatile unsigned char block_buffer_tail;
extern volatile unsigned char block_buffer_tail;
// Returns true if the buffer has a queued block, false otherwise
FORCE_INLINE bool blocks_queued() { return (block_buffer_head != block_buffer_tail); }
@ -155,9 +155,9 @@ FORCE_INLINE void plan_discard_current_block() {
}
// Gets the current block. Returns NULL if buffer empty
FORCE_INLINE block_t *plan_get_current_block() {
FORCE_INLINE block_t* plan_get_current_block() {
if (blocks_queued()) {
block_t *block = &block_buffer[block_buffer_tail];
block_t* block = &block_buffer[block_buffer_tail];
block->busy = true;
return block;
}

File diff suppressed because it is too large Load Diff

View File

@ -2,21 +2,21 @@
#if ENABLED(AUTO_BED_LEVELING_GRID)
void daxpy ( int n, double da, double dx[], int incx, double dy[], int incy );
double ddot ( int n, double dx[], int incx, double dy[], int incy );
double dnrm2 ( int n, double x[], int incx );
void dqrank ( double a[], int lda, int m, int n, double tol, int *kr,
int jpvt[], double qraux[] );
void dqrdc ( double a[], int lda, int n, int p, double qraux[], int jpvt[],
double work[], int job );
int dqrls ( double a[], int lda, int m, int n, double tol, int *kr, double b[],
double x[], double rsd[], int jpvt[], double qraux[], int itask );
void dqrlss ( double a[], int lda, int m, int n, int kr, double b[], double x[],
double rsd[], int jpvt[], double qraux[] );
int dqrsl ( double a[], int lda, int n, int k, double qraux[], double y[],
double qy[], double qty[], double b[], double rsd[], double ab[], int job );
void dscal ( int n, double sa, double x[], int incx );
void dswap ( int n, double x[], int incx, double y[], int incy );
void qr_solve ( double x[], int m, int n, double a[], double b[] );
void daxpy(int n, double da, double dx[], int incx, double dy[], int incy);
double ddot(int n, double dx[], int incx, double dy[], int incy);
double dnrm2(int n, double x[], int incx);
void dqrank(double a[], int lda, int m, int n, double tol, int* kr,
int jpvt[], double qraux[]);
void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[],
double work[], int job);
int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[],
double x[], double rsd[], int jpvt[], double qraux[], int itask);
void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[],
double rsd[], int jpvt[], double qraux[]);
int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[],
double qy[], double qty[], double b[], double rsd[], double ab[], int job);
void dscal(int n, double sa, double x[], int incx);
void dswap(int n, double x[], int incx, double y[], int incy);
void qr_solve(double x[], int m, int n, double a[], double b[]);
#endif

View File

@ -43,7 +43,7 @@
detach() - Stops an attached servos from pulsing its i/o pin.
*/
#include "Configuration.h"
#include "Configuration.h"
#if HAS_SERVOS
@ -76,23 +76,23 @@ uint8_t ServoCount = 0; // the total number
/************ static functions common to all instances ***********************/
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA) {
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t* TCNTn, volatile uint16_t* OCRnA) {
if (Channel[timer] < 0)
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
else {
if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive)
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive)
digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
}
Channel[timer]++; // increment to the next channel
if (SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
*OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated
digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
*OCRnA = *TCNTn + SERVO(timer, Channel[timer]).ticks;
if (SERVO(timer, Channel[timer]).Pin.isActive) // check if activated
digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high
}
else {
// finished all channels so wait for the refresh period to expire before starting over
if ( ((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL) ) // allow a few ticks to ensure the next OCR1A not missed
if (((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL)) // allow a few ticks to ensure the next OCR1A not missed
*OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL);
else
*OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed
@ -159,7 +159,7 @@ static void initISR(timer16_Sequence_t timer) {
TCNT3 = 0; // clear the timer count
#ifdef __AVR_ATmega128__
TIFR |= _BV(OCF3A); // clear any pending interrupts;
ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt
ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt
#else
TIFR3 = _BV(OCF3A); // clear any pending interrupts;
TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt
@ -219,8 +219,8 @@ static void finISR(timer16_Sequence_t timer) {
static boolean isTimerActive(timer16_Sequence_t timer) {
// returns true if any servo is active on this timer
for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
if (SERVO(timer,channel).Pin.isActive)
for (uint8_t channel = 0; channel < SERVOS_PER_TIMER; channel++) {
if (SERVO(timer, channel).Pin.isActive)
return true;
}
return false;
@ -230,7 +230,7 @@ static boolean isTimerActive(timer16_Sequence_t timer) {
/****************** end of static functions ******************************/
Servo::Servo() {
if ( ServoCount < MAX_SERVOS) {
if (ServoCount < MAX_SERVOS) {
this->servoIndex = ServoCount++; // assign a servo index to this instance
servo_info[this->servoIndex].ticks = usToTicks(DEFAULT_PULSE_WIDTH); // store default values - 12 Aug 2009
}
@ -285,7 +285,7 @@ void Servo::writeMicroseconds(int value) {
else if (value > SERVO_MAX())
value = SERVO_MAX();
value = value - TRIM_DURATION;
value = value - TRIM_DURATION;
value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009
uint8_t oldSREG = SREG;
@ -296,7 +296,7 @@ void Servo::writeMicroseconds(int value) {
}
// return the value as degrees
int Servo::read() { return map( this->readMicroseconds()+1, SERVO_MIN(), SERVO_MAX(), 0, 180); }
int Servo::read() { return map(this->readMicroseconds() + 1, SERVO_MIN(), SERVO_MAX(), 0, 180); }
int Servo::readMicroseconds() {
return (this->servoIndex == INVALID_SERVO) ? 0 : ticksToUs(servo_info[this->servoIndex].ticks) + TRIM_DURATION;

View File

@ -105,8 +105,8 @@
#define INVALID_SERVO 255 // flag indicating an invalid servo index
typedef struct {
uint8_t nbr :6 ; // a pin number from 0 to 63
uint8_t isActive :1 ; // true if this channel is enabled, pin not pulsed if false
uint8_t nbr : 6 ; // a pin number from 0 to 63
uint8_t isActive : 1 ; // true if this channel is enabled, pin not pulsed if false
} ServoPin_t;
typedef struct {

View File

@ -6,145 +6,145 @@
#if F_CPU == 16000000
const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {\
{ 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135},
{ 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32},
{ 484, 28}, { 456, 25}, { 431, 23}, { 408, 20}, { 388, 19}, { 369, 16}, { 353, 16}, { 337, 14},
{ 323, 13}, { 310, 11}, { 299, 11}, { 288, 11}, { 277, 9}, { 268, 9}, { 259, 8}, { 251, 8},
{ 243, 8}, { 235, 7}, { 228, 6}, { 222, 6}, { 216, 6}, { 210, 6}, { 204, 5}, { 199, 5},
{ 194, 5}, { 189, 4}, { 185, 4}, { 181, 4}, { 177, 4}, { 173, 4}, { 169, 4}, { 165, 3},
{ 162, 3}, { 159, 4}, { 155, 3}, { 152, 3}, { 149, 2}, { 147, 3}, { 144, 3}, { 141, 2},
{ 139, 3}, { 136, 2}, { 134, 2}, { 132, 3}, { 129, 2}, { 127, 2}, { 125, 2}, { 123, 2},
{ 121, 2}, { 119, 1}, { 118, 2}, { 116, 2}, { 114, 1}, { 113, 2}, { 111, 2}, { 109, 1},
{ 108, 2}, { 106, 1}, { 105, 2}, { 103, 1}, { 102, 1}, { 101, 1}, { 100, 2}, { 98, 1},
{ 97, 1}, { 96, 1}, { 95, 2}, { 93, 1}, { 92, 1}, { 91, 1}, { 90, 1}, { 89, 1},
{ 88, 1}, { 87, 1}, { 86, 1}, { 85, 1}, { 84, 1}, { 83, 0}, { 83, 1}, { 82, 1},
{ 81, 1}, { 80, 1}, { 79, 1}, { 78, 0}, { 78, 1}, { 77, 1}, { 76, 1}, { 75, 0},
{ 75, 1}, { 74, 1}, { 73, 1}, { 72, 0}, { 72, 1}, { 71, 1}, { 70, 0}, { 70, 1},
{ 69, 0}, { 69, 1}, { 68, 1}, { 67, 0}, { 67, 1}, { 66, 0}, { 66, 1}, { 65, 0},
{ 65, 1}, { 64, 1}, { 63, 0}, { 63, 1}, { 62, 0}, { 62, 1}, { 61, 0}, { 61, 1},
{ 60, 0}, { 60, 0}, { 60, 1}, { 59, 0}, { 59, 1}, { 58, 0}, { 58, 1}, { 57, 0},
{ 57, 1}, { 56, 0}, { 56, 0}, { 56, 1}, { 55, 0}, { 55, 1}, { 54, 0}, { 54, 0},
{ 54, 1}, { 53, 0}, { 53, 0}, { 53, 1}, { 52, 0}, { 52, 0}, { 52, 1}, { 51, 0},
{ 51, 0}, { 51, 1}, { 50, 0}, { 50, 0}, { 50, 1}, { 49, 0}, { 49, 0}, { 49, 1},
{ 48, 0}, { 48, 0}, { 48, 1}, { 47, 0}, { 47, 0}, { 47, 0}, { 47, 1}, { 46, 0},
{ 46, 0}, { 46, 1}, { 45, 0}, { 45, 0}, { 45, 0}, { 45, 1}, { 44, 0}, { 44, 0},
{ 44, 0}, { 44, 1}, { 43, 0}, { 43, 0}, { 43, 0}, { 43, 1}, { 42, 0}, { 42, 0},
{ 42, 0}, { 42, 1}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 1}, { 40, 0},
{ 40, 0}, { 40, 0}, { 40, 0}, { 40, 1}, { 39, 0}, { 39, 0}, { 39, 0}, { 39, 0},
{ 39, 1}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 1}, { 37, 0}, { 37, 0},
{ 37, 0}, { 37, 0}, { 37, 0}, { 37, 1}, { 36, 0}, { 36, 0}, { 36, 0}, { 36, 0},
{ 36, 1}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 1},
{ 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0},
{ 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0},
{ 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0},
{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
{ 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135},
{ 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32},
{ 484, 28}, { 456, 25}, { 431, 23}, { 408, 20}, { 388, 19}, { 369, 16}, { 353, 16}, { 337, 14},
{ 323, 13}, { 310, 11}, { 299, 11}, { 288, 11}, { 277, 9}, { 268, 9}, { 259, 8}, { 251, 8},
{ 243, 8}, { 235, 7}, { 228, 6}, { 222, 6}, { 216, 6}, { 210, 6}, { 204, 5}, { 199, 5},
{ 194, 5}, { 189, 4}, { 185, 4}, { 181, 4}, { 177, 4}, { 173, 4}, { 169, 4}, { 165, 3},
{ 162, 3}, { 159, 4}, { 155, 3}, { 152, 3}, { 149, 2}, { 147, 3}, { 144, 3}, { 141, 2},
{ 139, 3}, { 136, 2}, { 134, 2}, { 132, 3}, { 129, 2}, { 127, 2}, { 125, 2}, { 123, 2},
{ 121, 2}, { 119, 1}, { 118, 2}, { 116, 2}, { 114, 1}, { 113, 2}, { 111, 2}, { 109, 1},
{ 108, 2}, { 106, 1}, { 105, 2}, { 103, 1}, { 102, 1}, { 101, 1}, { 100, 2}, { 98, 1},
{ 97, 1}, { 96, 1}, { 95, 2}, { 93, 1}, { 92, 1}, { 91, 1}, { 90, 1}, { 89, 1},
{ 88, 1}, { 87, 1}, { 86, 1}, { 85, 1}, { 84, 1}, { 83, 0}, { 83, 1}, { 82, 1},
{ 81, 1}, { 80, 1}, { 79, 1}, { 78, 0}, { 78, 1}, { 77, 1}, { 76, 1}, { 75, 0},
{ 75, 1}, { 74, 1}, { 73, 1}, { 72, 0}, { 72, 1}, { 71, 1}, { 70, 0}, { 70, 1},
{ 69, 0}, { 69, 1}, { 68, 1}, { 67, 0}, { 67, 1}, { 66, 0}, { 66, 1}, { 65, 0},
{ 65, 1}, { 64, 1}, { 63, 0}, { 63, 1}, { 62, 0}, { 62, 1}, { 61, 0}, { 61, 1},
{ 60, 0}, { 60, 0}, { 60, 1}, { 59, 0}, { 59, 1}, { 58, 0}, { 58, 1}, { 57, 0},
{ 57, 1}, { 56, 0}, { 56, 0}, { 56, 1}, { 55, 0}, { 55, 1}, { 54, 0}, { 54, 0},
{ 54, 1}, { 53, 0}, { 53, 0}, { 53, 1}, { 52, 0}, { 52, 0}, { 52, 1}, { 51, 0},
{ 51, 0}, { 51, 1}, { 50, 0}, { 50, 0}, { 50, 1}, { 49, 0}, { 49, 0}, { 49, 1},
{ 48, 0}, { 48, 0}, { 48, 1}, { 47, 0}, { 47, 0}, { 47, 0}, { 47, 1}, { 46, 0},
{ 46, 0}, { 46, 1}, { 45, 0}, { 45, 0}, { 45, 0}, { 45, 1}, { 44, 0}, { 44, 0},
{ 44, 0}, { 44, 1}, { 43, 0}, { 43, 0}, { 43, 0}, { 43, 1}, { 42, 0}, { 42, 0},
{ 42, 0}, { 42, 1}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 1}, { 40, 0},
{ 40, 0}, { 40, 0}, { 40, 0}, { 40, 1}, { 39, 0}, { 39, 0}, { 39, 0}, { 39, 0},
{ 39, 1}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 1}, { 37, 0}, { 37, 0},
{ 37, 0}, { 37, 0}, { 37, 0}, { 37, 1}, { 36, 0}, { 36, 0}, { 36, 0}, { 36, 0},
{ 36, 1}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 1},
{ 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0},
{ 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0},
{ 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0},
{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
};
const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {\
{ 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894},
{ 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657},
{ 12500, 596}, { 11904, 541}, { 11363, 494}, { 10869, 453}, { 10416, 416}, { 10000, 385}, { 9615, 356}, { 9259, 331},
{ 8928, 308}, { 8620, 287}, { 8333, 269}, { 8064, 252}, { 7812, 237}, { 7575, 223}, { 7352, 210}, { 7142, 198},
{ 6944, 188}, { 6756, 178}, { 6578, 168}, { 6410, 160}, { 6250, 153}, { 6097, 145}, { 5952, 139}, { 5813, 132},
{ 5681, 126}, { 5555, 121}, { 5434, 115}, { 5319, 111}, { 5208, 106}, { 5102, 102}, { 5000, 99}, { 4901, 94},
{ 4807, 91}, { 4716, 87}, { 4629, 84}, { 4545, 81}, { 4464, 79}, { 4385, 75}, { 4310, 73}, { 4237, 71},
{ 4166, 68}, { 4098, 66}, { 4032, 64}, { 3968, 62}, { 3906, 60}, { 3846, 59}, { 3787, 56}, { 3731, 55},
{ 3676, 53}, { 3623, 52}, { 3571, 50}, { 3521, 49}, { 3472, 48}, { 3424, 46}, { 3378, 45}, { 3333, 44},
{ 3289, 43}, { 3246, 41}, { 3205, 41}, { 3164, 39}, { 3125, 39}, { 3086, 38}, { 3048, 36}, { 3012, 36},
{ 2976, 35}, { 2941, 35}, { 2906, 33}, { 2873, 33}, { 2840, 32}, { 2808, 31}, { 2777, 30}, { 2747, 30},
{ 2717, 29}, { 2688, 29}, { 2659, 28}, { 2631, 27}, { 2604, 27}, { 2577, 26}, { 2551, 26}, { 2525, 25},
{ 2500, 25}, { 2475, 25}, { 2450, 23}, { 2427, 24}, { 2403, 23}, { 2380, 22}, { 2358, 22}, { 2336, 22},
{ 2314, 21}, { 2293, 21}, { 2272, 20}, { 2252, 20}, { 2232, 20}, { 2212, 20}, { 2192, 19}, { 2173, 18},
{ 2155, 19}, { 2136, 18}, { 2118, 18}, { 2100, 17}, { 2083, 17}, { 2066, 17}, { 2049, 17}, { 2032, 16},
{ 2016, 16}, { 2000, 16}, { 1984, 16}, { 1968, 15}, { 1953, 16}, { 1937, 14}, { 1923, 15}, { 1908, 15},
{ 1893, 14}, { 1879, 14}, { 1865, 14}, { 1851, 13}, { 1838, 14}, { 1824, 13}, { 1811, 13}, { 1798, 13},
{ 1785, 12}, { 1773, 13}, { 1760, 12}, { 1748, 12}, { 1736, 12}, { 1724, 12}, { 1712, 12}, { 1700, 11},
{ 1689, 12}, { 1677, 11}, { 1666, 11}, { 1655, 11}, { 1644, 11}, { 1633, 10}, { 1623, 11}, { 1612, 10},
{ 1602, 10}, { 1592, 10}, { 1582, 10}, { 1572, 10}, { 1562, 10}, { 1552, 9}, { 1543, 10}, { 1533, 9},
{ 1524, 9}, { 1515, 9}, { 1506, 9}, { 1497, 9}, { 1488, 9}, { 1479, 9}, { 1470, 9}, { 1461, 8},
{ 1453, 8}, { 1445, 9}, { 1436, 8}, { 1428, 8}, { 1420, 8}, { 1412, 8}, { 1404, 8}, { 1396, 8},
{ 1388, 7}, { 1381, 8}, { 1373, 7}, { 1366, 8}, { 1358, 7}, { 1351, 7}, { 1344, 8}, { 1336, 7},
{ 1329, 7}, { 1322, 7}, { 1315, 7}, { 1308, 6}, { 1302, 7}, { 1295, 7}, { 1288, 6}, { 1282, 7},
{ 1275, 6}, { 1269, 7}, { 1262, 6}, { 1256, 6}, { 1250, 7}, { 1243, 6}, { 1237, 6}, { 1231, 6},
{ 1225, 6}, { 1219, 6}, { 1213, 6}, { 1207, 6}, { 1201, 5}, { 1196, 6}, { 1190, 6}, { 1184, 5},
{ 1179, 6}, { 1173, 5}, { 1168, 6}, { 1162, 5}, { 1157, 5}, { 1152, 6}, { 1146, 5}, { 1141, 5},
{ 1136, 5}, { 1131, 5}, { 1126, 5}, { 1121, 5}, { 1116, 5}, { 1111, 5}, { 1106, 5}, { 1101, 5},
{ 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4},
{ 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4},
{ 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4},
{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
{ 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894},
{ 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657},
{ 12500, 596}, { 11904, 541}, { 11363, 494}, { 10869, 453}, { 10416, 416}, { 10000, 385}, { 9615, 356}, { 9259, 331},
{ 8928, 308}, { 8620, 287}, { 8333, 269}, { 8064, 252}, { 7812, 237}, { 7575, 223}, { 7352, 210}, { 7142, 198},
{ 6944, 188}, { 6756, 178}, { 6578, 168}, { 6410, 160}, { 6250, 153}, { 6097, 145}, { 5952, 139}, { 5813, 132},
{ 5681, 126}, { 5555, 121}, { 5434, 115}, { 5319, 111}, { 5208, 106}, { 5102, 102}, { 5000, 99}, { 4901, 94},
{ 4807, 91}, { 4716, 87}, { 4629, 84}, { 4545, 81}, { 4464, 79}, { 4385, 75}, { 4310, 73}, { 4237, 71},
{ 4166, 68}, { 4098, 66}, { 4032, 64}, { 3968, 62}, { 3906, 60}, { 3846, 59}, { 3787, 56}, { 3731, 55},
{ 3676, 53}, { 3623, 52}, { 3571, 50}, { 3521, 49}, { 3472, 48}, { 3424, 46}, { 3378, 45}, { 3333, 44},
{ 3289, 43}, { 3246, 41}, { 3205, 41}, { 3164, 39}, { 3125, 39}, { 3086, 38}, { 3048, 36}, { 3012, 36},
{ 2976, 35}, { 2941, 35}, { 2906, 33}, { 2873, 33}, { 2840, 32}, { 2808, 31}, { 2777, 30}, { 2747, 30},
{ 2717, 29}, { 2688, 29}, { 2659, 28}, { 2631, 27}, { 2604, 27}, { 2577, 26}, { 2551, 26}, { 2525, 25},
{ 2500, 25}, { 2475, 25}, { 2450, 23}, { 2427, 24}, { 2403, 23}, { 2380, 22}, { 2358, 22}, { 2336, 22},
{ 2314, 21}, { 2293, 21}, { 2272, 20}, { 2252, 20}, { 2232, 20}, { 2212, 20}, { 2192, 19}, { 2173, 18},
{ 2155, 19}, { 2136, 18}, { 2118, 18}, { 2100, 17}, { 2083, 17}, { 2066, 17}, { 2049, 17}, { 2032, 16},
{ 2016, 16}, { 2000, 16}, { 1984, 16}, { 1968, 15}, { 1953, 16}, { 1937, 14}, { 1923, 15}, { 1908, 15},
{ 1893, 14}, { 1879, 14}, { 1865, 14}, { 1851, 13}, { 1838, 14}, { 1824, 13}, { 1811, 13}, { 1798, 13},
{ 1785, 12}, { 1773, 13}, { 1760, 12}, { 1748, 12}, { 1736, 12}, { 1724, 12}, { 1712, 12}, { 1700, 11},
{ 1689, 12}, { 1677, 11}, { 1666, 11}, { 1655, 11}, { 1644, 11}, { 1633, 10}, { 1623, 11}, { 1612, 10},
{ 1602, 10}, { 1592, 10}, { 1582, 10}, { 1572, 10}, { 1562, 10}, { 1552, 9}, { 1543, 10}, { 1533, 9},
{ 1524, 9}, { 1515, 9}, { 1506, 9}, { 1497, 9}, { 1488, 9}, { 1479, 9}, { 1470, 9}, { 1461, 8},
{ 1453, 8}, { 1445, 9}, { 1436, 8}, { 1428, 8}, { 1420, 8}, { 1412, 8}, { 1404, 8}, { 1396, 8},
{ 1388, 7}, { 1381, 8}, { 1373, 7}, { 1366, 8}, { 1358, 7}, { 1351, 7}, { 1344, 8}, { 1336, 7},
{ 1329, 7}, { 1322, 7}, { 1315, 7}, { 1308, 6}, { 1302, 7}, { 1295, 7}, { 1288, 6}, { 1282, 7},
{ 1275, 6}, { 1269, 7}, { 1262, 6}, { 1256, 6}, { 1250, 7}, { 1243, 6}, { 1237, 6}, { 1231, 6},
{ 1225, 6}, { 1219, 6}, { 1213, 6}, { 1207, 6}, { 1201, 5}, { 1196, 6}, { 1190, 6}, { 1184, 5},
{ 1179, 6}, { 1173, 5}, { 1168, 6}, { 1162, 5}, { 1157, 5}, { 1152, 6}, { 1146, 5}, { 1141, 5},
{ 1136, 5}, { 1131, 5}, { 1126, 5}, { 1121, 5}, { 1116, 5}, { 1111, 5}, { 1106, 5}, { 1101, 5},
{ 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4},
{ 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4},
{ 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4},
{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
};
#elif F_CPU == 20000000
const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
{62500, 54055}, {8445, 3917}, {4528, 1434}, {3094, 745}, {2349, 456}, {1893, 307}, {1586, 222}, {1364, 167},
{1197, 131}, {1066, 105}, {961, 86}, {875, 72}, {803, 61}, {742, 53}, {689, 45}, {644, 40},
{604, 35}, {569, 32}, {537, 28}, {509, 25}, {484, 23}, {461, 21}, {440, 19}, {421, 17},
{404, 16}, {388, 15}, {373, 14}, {359, 13}, {346, 12}, {334, 11}, {323, 10}, {313, 10},
{303, 9}, {294, 9}, {285, 8}, {277, 7}, {270, 8}, {262, 7}, {255, 6}, {249, 6},
{243, 6}, {237, 6}, {231, 5}, {226, 5}, {221, 5}, {216, 5}, {211, 4}, {207, 5},
{202, 4}, {198, 4}, {194, 4}, {190, 3}, {187, 4}, {183, 3}, {180, 3}, {177, 4},
{173, 3}, {170, 3}, {167, 2}, {165, 3}, {162, 3}, {159, 2}, {157, 3}, {154, 2},
{152, 3}, {149, 2}, {147, 2}, {145, 2}, {143, 2}, {141, 2}, {139, 2}, {137, 2},
{135, 2}, {133, 2}, {131, 2}, {129, 1}, {128, 2}, {126, 2}, {124, 1}, {123, 2},
{121, 1}, {120, 2}, {118, 1}, {117, 1}, {116, 2}, {114, 1}, {113, 1}, {112, 2},
{110, 1}, {109, 1}, {108, 1}, {107, 2}, {105, 1}, {104, 1}, {103, 1}, {102, 1},
{101, 1}, {100, 1}, {99, 1}, {98, 1}, {97, 1}, {96, 1}, {95, 1}, {94, 1},
{93, 1}, {92, 1}, {91, 0}, {91, 1}, {90, 1}, {89, 1}, {88, 1}, {87, 0},
{87, 1}, {86, 1}, {85, 1}, {84, 0}, {84, 1}, {83, 1}, {82, 1}, {81, 0},
{81, 1}, {80, 1}, {79, 0}, {79, 1}, {78, 0}, {78, 1}, {77, 1}, {76, 0},
{76, 1}, {75, 0}, {75, 1}, {74, 1}, {73, 0}, {73, 1}, {72, 0}, {72, 1},
{71, 0}, {71, 1}, {70, 0}, {70, 1}, {69, 0}, {69, 1}, {68, 0}, {68, 1},
{67, 0}, {67, 1}, {66, 0}, {66, 1}, {65, 0}, {65, 0}, {65, 1}, {64, 0},
{64, 1}, {63, 0}, {63, 1}, {62, 0}, {62, 0}, {62, 1}, {61, 0}, {61, 1},
{60, 0}, {60, 0}, {60, 1}, {59, 0}, {59, 0}, {59, 1}, {58, 0}, {58, 0},
{58, 1}, {57, 0}, {57, 0}, {57, 1}, {56, 0}, {56, 0}, {56, 1}, {55, 0},
{55, 0}, {55, 1}, {54, 0}, {54, 0}, {54, 1}, {53, 0}, {53, 0}, {53, 0},
{53, 1}, {52, 0}, {52, 0}, {52, 1}, {51, 0}, {51, 0}, {51, 0}, {51, 1},
{50, 0}, {50, 0}, {50, 0}, {50, 1}, {49, 0}, {49, 0}, {49, 0}, {49, 1},
{48, 0}, {48, 0}, {48, 0}, {48, 1}, {47, 0}, {47, 0}, {47, 0}, {47, 1},
{46, 0}, {46, 0}, {46, 0}, {46, 0}, {46, 1}, {45, 0}, {45, 0}, {45, 0},
{45, 1}, {44, 0}, {44, 0}, {44, 0}, {44, 0}, {44, 1}, {43, 0}, {43, 0},
{43, 0}, {43, 0}, {43, 1}, {42, 0}, {42, 0}, {42, 0}, {42, 0}, {42, 0},
{42, 1}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 1}, {40, 0},
{40, 0}, {40, 0}, {40, 0}, {40, 1}, {39, 0}, {39, 0}, {39, 0}, {39, 0},
{39, 0}, {39, 0}, {39, 1}, {38, 0}, {38, 0}, {38, 0}, {38, 0}, {38, 0},
{62500, 54055}, {8445, 3917}, {4528, 1434}, {3094, 745}, {2349, 456}, {1893, 307}, {1586, 222}, {1364, 167},
{1197, 131}, {1066, 105}, {961, 86}, {875, 72}, {803, 61}, {742, 53}, {689, 45}, {644, 40},
{604, 35}, {569, 32}, {537, 28}, {509, 25}, {484, 23}, {461, 21}, {440, 19}, {421, 17},
{404, 16}, {388, 15}, {373, 14}, {359, 13}, {346, 12}, {334, 11}, {323, 10}, {313, 10},
{303, 9}, {294, 9}, {285, 8}, {277, 7}, {270, 8}, {262, 7}, {255, 6}, {249, 6},
{243, 6}, {237, 6}, {231, 5}, {226, 5}, {221, 5}, {216, 5}, {211, 4}, {207, 5},
{202, 4}, {198, 4}, {194, 4}, {190, 3}, {187, 4}, {183, 3}, {180, 3}, {177, 4},
{173, 3}, {170, 3}, {167, 2}, {165, 3}, {162, 3}, {159, 2}, {157, 3}, {154, 2},
{152, 3}, {149, 2}, {147, 2}, {145, 2}, {143, 2}, {141, 2}, {139, 2}, {137, 2},
{135, 2}, {133, 2}, {131, 2}, {129, 1}, {128, 2}, {126, 2}, {124, 1}, {123, 2},
{121, 1}, {120, 2}, {118, 1}, {117, 1}, {116, 2}, {114, 1}, {113, 1}, {112, 2},
{110, 1}, {109, 1}, {108, 1}, {107, 2}, {105, 1}, {104, 1}, {103, 1}, {102, 1},
{101, 1}, {100, 1}, {99, 1}, {98, 1}, {97, 1}, {96, 1}, {95, 1}, {94, 1},
{93, 1}, {92, 1}, {91, 0}, {91, 1}, {90, 1}, {89, 1}, {88, 1}, {87, 0},
{87, 1}, {86, 1}, {85, 1}, {84, 0}, {84, 1}, {83, 1}, {82, 1}, {81, 0},
{81, 1}, {80, 1}, {79, 0}, {79, 1}, {78, 0}, {78, 1}, {77, 1}, {76, 0},
{76, 1}, {75, 0}, {75, 1}, {74, 1}, {73, 0}, {73, 1}, {72, 0}, {72, 1},
{71, 0}, {71, 1}, {70, 0}, {70, 1}, {69, 0}, {69, 1}, {68, 0}, {68, 1},
{67, 0}, {67, 1}, {66, 0}, {66, 1}, {65, 0}, {65, 0}, {65, 1}, {64, 0},
{64, 1}, {63, 0}, {63, 1}, {62, 0}, {62, 0}, {62, 1}, {61, 0}, {61, 1},
{60, 0}, {60, 0}, {60, 1}, {59, 0}, {59, 0}, {59, 1}, {58, 0}, {58, 0},
{58, 1}, {57, 0}, {57, 0}, {57, 1}, {56, 0}, {56, 0}, {56, 1}, {55, 0},
{55, 0}, {55, 1}, {54, 0}, {54, 0}, {54, 1}, {53, 0}, {53, 0}, {53, 0},
{53, 1}, {52, 0}, {52, 0}, {52, 1}, {51, 0}, {51, 0}, {51, 0}, {51, 1},
{50, 0}, {50, 0}, {50, 0}, {50, 1}, {49, 0}, {49, 0}, {49, 0}, {49, 1},
{48, 0}, {48, 0}, {48, 0}, {48, 1}, {47, 0}, {47, 0}, {47, 0}, {47, 1},
{46, 0}, {46, 0}, {46, 0}, {46, 0}, {46, 1}, {45, 0}, {45, 0}, {45, 0},
{45, 1}, {44, 0}, {44, 0}, {44, 0}, {44, 0}, {44, 1}, {43, 0}, {43, 0},
{43, 0}, {43, 0}, {43, 1}, {42, 0}, {42, 0}, {42, 0}, {42, 0}, {42, 0},
{42, 1}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 1}, {40, 0},
{40, 0}, {40, 0}, {40, 0}, {40, 1}, {39, 0}, {39, 0}, {39, 0}, {39, 0},
{39, 0}, {39, 0}, {39, 1}, {38, 0}, {38, 0}, {38, 0}, {38, 0}, {38, 0},
};
const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
{62500, 10417}, {52083, 7441}, {44642, 5580}, {39062, 4340}, {34722, 3472}, {31250, 2841}, {28409, 2368}, {26041, 2003},
{24038, 1717}, {22321, 1488}, {20833, 1302}, {19531, 1149}, {18382, 1021}, {17361, 914}, {16447, 822}, {15625, 745},
{14880, 676}, {14204, 618}, {13586, 566}, {13020, 520}, {12500, 481}, {12019, 445}, {11574, 414}, {11160, 385},
{10775, 359}, {10416, 336}, {10080, 315}, {9765, 296}, {9469, 278}, {9191, 263}, {8928, 248}, {8680, 235},
{8445, 222}, {8223, 211}, {8012, 200}, {7812, 191}, {7621, 181}, {7440, 173}, {7267, 165}, {7102, 158},
{6944, 151}, {6793, 145}, {6648, 138}, {6510, 133}, {6377, 127}, {6250, 123}, {6127, 118}, {6009, 113},
{5896, 109}, {5787, 106}, {5681, 101}, {5580, 98}, {5482, 95}, {5387, 91}, {5296, 88}, {5208, 86},
{5122, 82}, {5040, 80}, {4960, 78}, {4882, 75}, {4807, 73}, {4734, 70}, {4664, 69}, {4595, 67},
{4528, 64}, {4464, 63}, {4401, 61}, {4340, 60}, {4280, 58}, {4222, 56}, {4166, 55}, {4111, 53},
{4058, 52}, {4006, 51}, {3955, 49}, {3906, 48}, {3858, 48}, {3810, 45}, {3765, 45}, {3720, 44},
{3676, 43}, {3633, 42}, {3591, 40}, {3551, 40}, {3511, 39}, {3472, 38}, {3434, 38}, {3396, 36},
{3360, 36}, {3324, 35}, {3289, 34}, {3255, 34}, {3221, 33}, {3188, 32}, {3156, 31}, {3125, 31},
{3094, 31}, {3063, 30}, {3033, 29}, {3004, 28}, {2976, 28}, {2948, 28}, {2920, 27}, {2893, 27},
{2866, 26}, {2840, 25}, {2815, 25}, {2790, 25}, {2765, 24}, {2741, 24}, {2717, 24}, {2693, 23},
{2670, 22}, {2648, 22}, {2626, 22}, {2604, 22}, {2582, 21}, {2561, 21}, {2540, 20}, {2520, 20},
{2500, 20}, {2480, 20}, {2460, 19}, {2441, 19}, {2422, 19}, {2403, 18}, {2385, 18}, {2367, 18},
{2349, 17}, {2332, 18}, {2314, 17}, {2297, 16}, {2281, 17}, {2264, 16}, {2248, 16}, {2232, 16},
{2216, 16}, {2200, 15}, {2185, 15}, {2170, 15}, {2155, 15}, {2140, 15}, {2125, 14}, {2111, 14},
{2097, 14}, {2083, 14}, {2069, 14}, {2055, 13}, {2042, 13}, {2029, 13}, {2016, 13}, {2003, 13},
{1990, 13}, {1977, 12}, {1965, 12}, {1953, 13}, {1940, 11}, {1929, 12}, {1917, 12}, {1905, 12},
{1893, 11}, {1882, 11}, {1871, 11}, {1860, 11}, {1849, 11}, {1838, 11}, {1827, 11}, {1816, 10},
{1806, 11}, {1795, 10}, {1785, 10}, {1775, 10}, {1765, 10}, {1755, 10}, {1745, 9}, {1736, 10},
{1726, 9}, {1717, 10}, {1707, 9}, {1698, 9}, {1689, 9}, {1680, 9}, {1671, 9}, {1662, 9},
{1653, 9}, {1644, 8}, {1636, 9}, {1627, 8}, {1619, 9}, {1610, 8}, {1602, 8}, {1594, 8},
{1586, 8}, {1578, 8}, {1570, 8}, {1562, 8}, {1554, 7}, {1547, 8}, {1539, 8}, {1531, 7},
{1524, 8}, {1516, 7}, {1509, 7}, {1502, 7}, {1495, 7}, {1488, 7}, {1481, 7}, {1474, 7},
{1467, 7}, {1460, 7}, {1453, 7}, {1446, 6}, {1440, 7}, {1433, 7}, {1426, 6}, {1420, 6},
{1414, 7}, {1407, 6}, {1401, 6}, {1395, 7}, {1388, 6}, {1382, 6}, {1376, 6}, {1370, 6},
{1364, 6}, {1358, 6}, {1352, 6}, {1346, 5}, {1341, 6}, {1335, 6}, {1329, 5}, {1324, 6},
{1318, 5}, {1313, 6}, {1307, 5}, {1302, 6}, {1296, 5}, {1291, 5}, {1286, 6}, {1280, 5},
{1275, 5}, {1270, 5}, {1265, 5}, {1260, 5}, {1255, 5}, {1250, 5}, {1245, 5}, {1240, 5},
{1235, 5}, {1230, 5}, {1225, 5}, {1220, 5}, {1215, 4}, {1211, 5}, {1206, 5}, {1201, 5},
{62500, 10417}, {52083, 7441}, {44642, 5580}, {39062, 4340}, {34722, 3472}, {31250, 2841}, {28409, 2368}, {26041, 2003},
{24038, 1717}, {22321, 1488}, {20833, 1302}, {19531, 1149}, {18382, 1021}, {17361, 914}, {16447, 822}, {15625, 745},
{14880, 676}, {14204, 618}, {13586, 566}, {13020, 520}, {12500, 481}, {12019, 445}, {11574, 414}, {11160, 385},
{10775, 359}, {10416, 336}, {10080, 315}, {9765, 296}, {9469, 278}, {9191, 263}, {8928, 248}, {8680, 235},
{8445, 222}, {8223, 211}, {8012, 200}, {7812, 191}, {7621, 181}, {7440, 173}, {7267, 165}, {7102, 158},
{6944, 151}, {6793, 145}, {6648, 138}, {6510, 133}, {6377, 127}, {6250, 123}, {6127, 118}, {6009, 113},
{5896, 109}, {5787, 106}, {5681, 101}, {5580, 98}, {5482, 95}, {5387, 91}, {5296, 88}, {5208, 86},
{5122, 82}, {5040, 80}, {4960, 78}, {4882, 75}, {4807, 73}, {4734, 70}, {4664, 69}, {4595, 67},
{4528, 64}, {4464, 63}, {4401, 61}, {4340, 60}, {4280, 58}, {4222, 56}, {4166, 55}, {4111, 53},
{4058, 52}, {4006, 51}, {3955, 49}, {3906, 48}, {3858, 48}, {3810, 45}, {3765, 45}, {3720, 44},
{3676, 43}, {3633, 42}, {3591, 40}, {3551, 40}, {3511, 39}, {3472, 38}, {3434, 38}, {3396, 36},
{3360, 36}, {3324, 35}, {3289, 34}, {3255, 34}, {3221, 33}, {3188, 32}, {3156, 31}, {3125, 31},
{3094, 31}, {3063, 30}, {3033, 29}, {3004, 28}, {2976, 28}, {2948, 28}, {2920, 27}, {2893, 27},
{2866, 26}, {2840, 25}, {2815, 25}, {2790, 25}, {2765, 24}, {2741, 24}, {2717, 24}, {2693, 23},
{2670, 22}, {2648, 22}, {2626, 22}, {2604, 22}, {2582, 21}, {2561, 21}, {2540, 20}, {2520, 20},
{2500, 20}, {2480, 20}, {2460, 19}, {2441, 19}, {2422, 19}, {2403, 18}, {2385, 18}, {2367, 18},
{2349, 17}, {2332, 18}, {2314, 17}, {2297, 16}, {2281, 17}, {2264, 16}, {2248, 16}, {2232, 16},
{2216, 16}, {2200, 15}, {2185, 15}, {2170, 15}, {2155, 15}, {2140, 15}, {2125, 14}, {2111, 14},
{2097, 14}, {2083, 14}, {2069, 14}, {2055, 13}, {2042, 13}, {2029, 13}, {2016, 13}, {2003, 13},
{1990, 13}, {1977, 12}, {1965, 12}, {1953, 13}, {1940, 11}, {1929, 12}, {1917, 12}, {1905, 12},
{1893, 11}, {1882, 11}, {1871, 11}, {1860, 11}, {1849, 11}, {1838, 11}, {1827, 11}, {1816, 10},
{1806, 11}, {1795, 10}, {1785, 10}, {1775, 10}, {1765, 10}, {1755, 10}, {1745, 9}, {1736, 10},
{1726, 9}, {1717, 10}, {1707, 9}, {1698, 9}, {1689, 9}, {1680, 9}, {1671, 9}, {1662, 9},
{1653, 9}, {1644, 8}, {1636, 9}, {1627, 8}, {1619, 9}, {1610, 8}, {1602, 8}, {1594, 8},
{1586, 8}, {1578, 8}, {1570, 8}, {1562, 8}, {1554, 7}, {1547, 8}, {1539, 8}, {1531, 7},
{1524, 8}, {1516, 7}, {1509, 7}, {1502, 7}, {1495, 7}, {1488, 7}, {1481, 7}, {1474, 7},
{1467, 7}, {1460, 7}, {1453, 7}, {1446, 6}, {1440, 7}, {1433, 7}, {1426, 6}, {1420, 6},
{1414, 7}, {1407, 6}, {1401, 6}, {1395, 7}, {1388, 6}, {1382, 6}, {1376, 6}, {1370, 6},
{1364, 6}, {1358, 6}, {1352, 6}, {1346, 5}, {1341, 6}, {1335, 6}, {1329, 5}, {1324, 6},
{1318, 5}, {1313, 6}, {1307, 5}, {1302, 6}, {1296, 5}, {1291, 5}, {1286, 6}, {1280, 5},
{1275, 5}, {1270, 5}, {1265, 5}, {1260, 5}, {1255, 5}, {1250, 5}, {1245, 5}, {1240, 5},
{1235, 5}, {1230, 5}, {1225, 5}, {1220, 5}, {1215, 4}, {1211, 5}, {1206, 5}, {1201, 5},
};
#endif

View File

@ -37,7 +37,7 @@
//===========================================================================
//============================= public variables ============================
//===========================================================================
block_t *current_block; // A pointer to the block currently being traced
block_t* current_block; // A pointer to the block currently being traced
//===========================================================================
@ -50,8 +50,8 @@ static unsigned char out_bits = 0; // The next stepping-bits to be output
static unsigned int cleaning_buffer_counter;
#if ENABLED(Z_DUAL_ENDSTOPS)
static bool performing_homing = false,
locked_z_motor = false,
static bool performing_homing = false,
locked_z_motor = false,
locked_z2_motor = false;
#endif
@ -81,7 +81,7 @@ static volatile char endstop_hit_bits = 0; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_
#else
static uint16_t
#endif
old_endstop_bits = 0; // use X_MIN, X_MAX... Z_MAX, Z_MIN_PROBE, Z2_MIN, Z2_MAX
old_endstop_bits = 0; // use X_MIN, X_MAX... Z_MAX, Z_MIN_PROBE, Z2_MIN, Z2_MAX
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
bool abort_on_endstop_hit = false;
@ -163,24 +163,24 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
// r27 to store the byte 1 of the 24 bit result
#define MultiU16X8toH16(intRes, charIn1, intIn2) \
asm volatile ( \
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
"movw %A0, r0 \n\t" \
"mul %A1, %A2 \n\t" \
"add %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"lsr r0 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
: \
"d" (charIn1), \
"d" (intIn2) \
: \
"r26" \
)
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
"movw %A0, r0 \n\t" \
"mul %A1, %A2 \n\t" \
"add %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"lsr r0 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
: \
"d" (charIn1), \
"d" (intIn2) \
: \
"r26" \
)
// intRes = longIn1 * longIn2 >> 24
// uses:
@ -194,49 +194,49 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
//
#define MultiU24X32toH16(intRes, longIn1, longIn2) \
asm volatile ( \
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
"mov r27, r1 \n\t" \
"mul %B1, %C2 \n\t" \
"movw %A0, r0 \n\t" \
"mul %C1, %C2 \n\t" \
"add %B0, r0 \n\t" \
"mul %C1, %B2 \n\t" \
"add %A0, r0 \n\t" \
"adc %B0, r1 \n\t" \
"mul %A1, %C2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %B1, %B2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %C1, %A2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %B1, %A2 \n\t" \
"add r27, r1 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"lsr r27 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"mul %D2, %A1 \n\t" \
"add %A0, r0 \n\t" \
"adc %B0, r1 \n\t" \
"mul %D2, %B1 \n\t" \
"add %B0, r0 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
: \
"d" (longIn1), \
"d" (longIn2) \
: \
"r26" , "r27" \
)
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
"mov r27, r1 \n\t" \
"mul %B1, %C2 \n\t" \
"movw %A0, r0 \n\t" \
"mul %C1, %C2 \n\t" \
"add %B0, r0 \n\t" \
"mul %C1, %B2 \n\t" \
"add %A0, r0 \n\t" \
"adc %B0, r1 \n\t" \
"mul %A1, %C2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %B1, %B2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %C1, %A2 \n\t" \
"add r27, r0 \n\t" \
"adc %A0, r1 \n\t" \
"adc %B0, r26 \n\t" \
"mul %B1, %A2 \n\t" \
"add r27, r1 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"lsr r27 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"mul %D2, %A1 \n\t" \
"add %A0, r0 \n\t" \
"adc %B0, r1 \n\t" \
"mul %D2, %B1 \n\t" \
"add %B0, r0 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
: \
"d" (longIn1), \
"d" (longIn2) \
: \
"r26" , "r27" \
)
// Some useful constants
@ -288,7 +288,7 @@ void enable_endstops(bool check) { check_endstops = check; }
// Check endstops
inline void update_endstops() {
#if ENABLED(Z_DUAL_ENDSTOPS)
uint16_t
#else
@ -316,7 +316,7 @@ inline void update_endstops() {
_ENDSTOP_HIT(AXIS); \
step_events_completed = current_block->step_event_count; \
}
#if ENABLED(COREXY)
// Head direction in -X axis for CoreXY bots.
// If DeltaX == -DeltaY, the movement is only in Y axis
@ -328,7 +328,7 @@ inline void update_endstops() {
if ((current_block->steps[A_AXIS] != current_block->steps[C_AXIS]) || (TEST(out_bits, A_AXIS) == TEST(out_bits, C_AXIS))) {
if (TEST(out_bits, X_HEAD))
#else
if (TEST(out_bits, X_AXIS)) // stepping along -X axis (regular Cartesian bot)
if (TEST(out_bits, X_AXIS)) // stepping along -X axis (regular Cartesian bot)
#endif
{ // -direction
#if ENABLED(DUAL_X_CARRIAGE)
@ -391,11 +391,11 @@ inline void update_endstops() {
#if ENABLED(Z_DUAL_ENDSTOPS)
SET_ENDSTOP_BIT(Z, MIN);
#if HAS_Z2_MIN
SET_ENDSTOP_BIT(Z2, MIN);
#else
COPY_BIT(current_endstop_bits, Z_MIN, Z2_MIN);
#endif
#if HAS_Z2_MIN
SET_ENDSTOP_BIT(Z2, MIN);
#else
COPY_BIT(current_endstop_bits, Z_MIN, Z2_MIN);
#endif
byte z_test = TEST_ENDSTOP(Z_MIN) << 0 + TEST_ENDSTOP(Z2_MIN) << 1; // bit 0 for Z, bit 1 for Z2
@ -408,14 +408,14 @@ inline void update_endstops() {
#else // !Z_DUAL_ENDSTOPS
UPDATE_ENDSTOP(Z, MIN);
#endif // !Z_DUAL_ENDSTOPS
#endif // Z_MIN_PIN
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
UPDATE_ENDSTOP(Z, MIN_PROBE);
if (TEST_ENDSTOP(Z_MIN_PROBE))
{
if (TEST_ENDSTOP(Z_MIN_PROBE)) {
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
endstop_hit_bits |= BIT(Z_MIN_PROBE);
}
@ -427,11 +427,11 @@ inline void update_endstops() {
#if ENABLED(Z_DUAL_ENDSTOPS)
SET_ENDSTOP_BIT(Z, MAX);
#if HAS_Z2_MAX
SET_ENDSTOP_BIT(Z2, MAX);
#else
COPY_BIT(current_endstop_bits, Z_MAX, Z2_MAX);
#endif
#if HAS_Z2_MAX
SET_ENDSTOP_BIT(Z2, MAX);
#else
COPY_BIT(current_endstop_bits, Z_MAX, Z2_MAX);
#endif
byte z_test = TEST_ENDSTOP(Z_MAX) << 0 + TEST_ENDSTOP(Z2_MAX) << 1; // bit 0 for Z, bit 1 for Z2
@ -451,7 +451,7 @@ inline void update_endstops() {
}
#if ENABLED(COREXZ)
}
#endif
#endif
old_endstop_bits = current_endstop_bits;
}
@ -495,17 +495,17 @@ FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
if (step_rate < (F_CPU / 500000)) step_rate = (F_CPU / 500000);
step_rate -= (F_CPU / 500000); // Correct for minimal speed
if (step_rate >= (8 * 256)) { // higher step rate
unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate >> 8)][0];
unsigned char tmp_step_rate = (step_rate & 0x00ff);
unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
unsigned short gain = (unsigned short)pgm_read_word_near(table_address + 2);
MultiU16X8toH16(timer, tmp_step_rate, gain);
timer = (unsigned short)pgm_read_word_near(table_address) - timer;
}
else { // lower step rates
unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
table_address += ((step_rate)>>1) & 0xfffc;
table_address += ((step_rate) >> 1) & 0xfffc;
timer = (unsigned short)pgm_read_word_near(table_address);
timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
timer -= (((unsigned short)pgm_read_word_near(table_address + 2) * (unsigned char)(step_rate & 0x0007)) >> 3);
}
if (timer < 100) { timer = 100; MYSERIAL.print(MSG_STEPPER_TOO_HIGH); MYSERIAL.println(step_rate); }//(20kHz this should never happen)
return timer;
@ -536,7 +536,7 @@ void set_stepper_direction() {
Y_APPLY_DIR(!INVERT_Y_DIR, 0);
count_direction[Y_AXIS] = 1;
}
if (TEST(out_bits, Z_AXIS)) { // C_AXIS
Z_APPLY_DIR(INVERT_Z_DIR, 0);
count_direction[Z_AXIS] = -1;
@ -545,7 +545,7 @@ void set_stepper_direction() {
Z_APPLY_DIR(!INVERT_Z_DIR, 0);
count_direction[Z_AXIS] = 1;
}
#if DISABLED(ADVANCE)
if (TEST(out_bits, E_AXIS)) {
REV_E_DIR();
@ -566,7 +566,7 @@ FORCE_INLINE void trapezoid_generator_reset() {
out_bits = current_block->direction_bits;
set_stepper_direction();
}
#if ENABLED(ADVANCE)
advance = current_block->initial_advance;
final_advance = current_block->final_advance;
@ -704,16 +704,18 @@ ISR(TIMER1_COMPA_vect) {
timer = calc_timer(acc_step_rate);
OCR1A = timer;
acceleration_time += timer;
#if ENABLED(ADVANCE)
for(int8_t i=0; i < step_loops; i++) {
for (int8_t i = 0; i < step_loops; i++) {
advance += advance_rate;
}
//if (advance > current_block->advance) advance = current_block->advance;
// Do E steps + advance steps
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
old_advance = advance >>8;
e_steps[current_block->active_extruder] += ((advance >> 8) - old_advance);
old_advance = advance >> 8;
#endif
#endif //ADVANCE
}
else if (step_events_completed > (unsigned long)current_block->decelerate_after) {
MultiU24X32toH16(step_rate, deceleration_time, current_block->acceleration_rate);
@ -734,13 +736,13 @@ ISR(TIMER1_COMPA_vect) {
OCR1A = timer;
deceleration_time += timer;
#if ENABLED(ADVANCE)
for(int8_t i=0; i < step_loops; i++) {
for (int8_t i = 0; i < step_loops; i++) {
advance -= advance_rate;
}
if (advance < final_advance) advance = final_advance;
// Do E steps + advance steps
e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
old_advance = advance >>8;
e_steps[current_block->active_extruder] += ((advance >> 8) - old_advance);
old_advance = advance >> 8;
#endif //ADVANCE
}
else {
@ -749,7 +751,7 @@ ISR(TIMER1_COMPA_vect) {
step_loops = step_loops_nominal;
}
OCR1A = (OCR1A < (TCNT1 +16)) ? (TCNT1 + 16) : OCR1A;
OCR1A = (OCR1A < (TCNT1 + 16)) ? (TCNT1 + 16) : OCR1A;
// If current block is finished, reset pointer
if (step_events_completed >= current_block->step_event_count) {
@ -763,12 +765,11 @@ ISR(TIMER1_COMPA_vect) {
unsigned char old_OCR0A;
// Timer interrupt for E. e_steps is set in the main routine;
// Timer 0 is shared with millies
ISR(TIMER0_COMPA_vect)
{
ISR(TIMER0_COMPA_vect) {
old_OCR0A += 52; // ~10kHz interrupt (250000 / 26 = 9615kHz)
OCR0A = old_OCR0A;
// Set E direction (Depends on E direction + advance)
for(unsigned char i=0; i<4;i++) {
for (unsigned char i = 0; i < 4; i++) {
if (e_steps[0] != 0) {
E0_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[0] < 0) {
@ -782,52 +783,51 @@ ISR(TIMER1_COMPA_vect) {
E0_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
#if EXTRUDERS > 1
if (e_steps[1] != 0) {
E1_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[1] < 0) {
E1_DIR_WRITE(INVERT_E1_DIR);
e_steps[1]++;
E1_STEP_WRITE(!INVERT_E_STEP_PIN);
#if EXTRUDERS > 1
if (e_steps[1] != 0) {
E1_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[1] < 0) {
E1_DIR_WRITE(INVERT_E1_DIR);
e_steps[1]++;
E1_STEP_WRITE(!INVERT_E_STEP_PIN);
}
else if (e_steps[1] > 0) {
E1_DIR_WRITE(!INVERT_E1_DIR);
e_steps[1]--;
E1_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
else if (e_steps[1] > 0) {
E1_DIR_WRITE(!INVERT_E1_DIR);
e_steps[1]--;
E1_STEP_WRITE(!INVERT_E_STEP_PIN);
#endif
#if EXTRUDERS > 2
if (e_steps[2] != 0) {
E2_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[2] < 0) {
E2_DIR_WRITE(INVERT_E2_DIR);
e_steps[2]++;
E2_STEP_WRITE(!INVERT_E_STEP_PIN);
}
else if (e_steps[2] > 0) {
E2_DIR_WRITE(!INVERT_E2_DIR);
e_steps[2]--;
E2_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
}
#endif
#if EXTRUDERS > 2
if (e_steps[2] != 0) {
E2_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[2] < 0) {
E2_DIR_WRITE(INVERT_E2_DIR);
e_steps[2]++;
E2_STEP_WRITE(!INVERT_E_STEP_PIN);
#endif
#if EXTRUDERS > 3
if (e_steps[3] != 0) {
E3_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[3] < 0) {
E3_DIR_WRITE(INVERT_E3_DIR);
e_steps[3]++;
E3_STEP_WRITE(!INVERT_E_STEP_PIN);
}
else if (e_steps[3] > 0) {
E3_DIR_WRITE(!INVERT_E3_DIR);
e_steps[3]--;
E3_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
else if (e_steps[2] > 0) {
E2_DIR_WRITE(!INVERT_E2_DIR);
e_steps[2]--;
E2_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
#endif
#if EXTRUDERS > 3
if (e_steps[3] != 0) {
E3_STEP_WRITE(INVERT_E_STEP_PIN);
if (e_steps[3] < 0) {
E3_DIR_WRITE(INVERT_E3_DIR);
e_steps[3]++;
E3_STEP_WRITE(!INVERT_E_STEP_PIN);
}
else if (e_steps[3] > 0) {
E3_DIR_WRITE(!INVERT_E3_DIR);
e_steps[3]--;
E3_STEP_WRITE(!INVERT_E_STEP_PIN);
}
}
#endif
#endif
}
}
#endif // ADVANCE
@ -1032,15 +1032,14 @@ void st_init() {
TCCR1A &= ~BIT(WGM10);
// output mode = 00 (disconnected)
TCCR1A &= ~(3<<COM1A0);
TCCR1A &= ~(3<<COM1B0);
TCCR1A &= ~(3 << COM1A0);
TCCR1A &= ~(3 << COM1B0);
// Set the timer pre-scaler
// Generally we use a divider of 8, resulting in a 2MHz timer
// frequency on a 16MHz MCU. If you are going to change this, be
// sure to regenerate speed_lookuptable.h with
// create_speed_lookuptable.py
TCCR1B = (TCCR1B & ~(0x07<<CS10)) | (2<<CS10);
TCCR1B = (TCCR1B & ~(0x07 << CS10)) | (2 << CS10);
OCR1A = 0x4000;
TCNT1 = 0;
@ -1057,7 +1056,7 @@ void st_init() {
enable_endstops(true); // Start with endstops active. After homing they can be disabled
sei();
set_stepper_direction(); // Init directions to out_bits = 0
}
@ -1067,7 +1066,7 @@ void st_init() {
*/
void st_synchronize() { while (blocks_queued()) idle(); }
void st_set_position(const long &x, const long &y, const long &z, const long &e) {
void st_set_position(const long& x, const long& y, const long& z, const long& e) {
CRITICAL_SECTION_START;
count_position[X_AXIS] = x;
count_position[Y_AXIS] = y;
@ -1076,7 +1075,7 @@ void st_set_position(const long &x, const long &y, const long &z, const long &e)
CRITICAL_SECTION_END;
}
void st_set_e_position(const long &e) {
void st_set_e_position(const long& e) {
CRITICAL_SECTION_START;
count_position[E_AXIS] = e;
CRITICAL_SECTION_END;
@ -1126,7 +1125,7 @@ void quickStop() {
_APPLY_DIR(AXIS, old_pin); \
}
switch(axis) {
switch (axis) {
case X_AXIS:
BABYSTEP_AXIS(x, X, false);
@ -1135,7 +1134,7 @@ void quickStop() {
case Y_AXIS:
BABYSTEP_AXIS(y, Y, false);
break;
case Z_AXIS: {
#if DISABLED(DELTA)
@ -1153,16 +1152,16 @@ void quickStop() {
old_y_dir_pin = Y_DIR_READ,
old_z_dir_pin = Z_DIR_READ;
//setup new step
X_DIR_WRITE(INVERT_X_DIR^z_direction);
Y_DIR_WRITE(INVERT_Y_DIR^z_direction);
Z_DIR_WRITE(INVERT_Z_DIR^z_direction);
//perform step
X_DIR_WRITE(INVERT_X_DIR ^ z_direction);
Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction);
Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction);
//perform step
X_STEP_WRITE(!INVERT_X_STEP_PIN);
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
delayMicroseconds(2);
X_STEP_WRITE(INVERT_X_STEP_PIN);
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
X_STEP_WRITE(INVERT_X_STEP_PIN);
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
Z_STEP_WRITE(INVERT_Z_STEP_PIN);
//get old pin state back.
X_DIR_WRITE(old_x_dir_pin);
@ -1172,7 +1171,7 @@ void quickStop() {
#endif
} break;
default: break;
}
}
@ -1182,10 +1181,10 @@ void quickStop() {
// From Arduino DigitalPotControl example
void digitalPotWrite(int address, int value) {
#if HAS_DIGIPOTSS
digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip
digitalWrite(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip
SPI.transfer(address); // send in the address and value via SPI:
SPI.transfer(value);
digitalWrite(DIGIPOTSS_PIN,HIGH); // take the SS pin high to de-select the chip:
digitalWrite(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip:
//delay(10);
#else
UNUSED(address);
@ -1202,7 +1201,7 @@ void digipot_init() {
pinMode(DIGIPOTSS_PIN, OUTPUT);
for (int i = 0; i <= 4; i++) {
//digitalPotWrite(digipot_ch[i], digipot_motor_current[i]);
digipot_current(i,digipot_motor_current[i]);
digipot_current(i, digipot_motor_current[i]);
}
#endif
#ifdef MOTOR_CURRENT_PWM_XY_PIN
@ -1222,7 +1221,7 @@ void digipot_current(uint8_t driver, int current) {
const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
digitalPotWrite(digipot_ch[driver], current);
#elif defined(MOTOR_CURRENT_PWM_XY_PIN)
switch(driver) {
switch (driver) {
case 0: analogWrite(MOTOR_CURRENT_PWM_XY_PIN, 255L * current / MOTOR_CURRENT_PWM_RANGE); break;
case 1: analogWrite(MOTOR_CURRENT_PWM_Z_PIN, 255L * current / MOTOR_CURRENT_PWM_RANGE); break;
case 2: analogWrite(MOTOR_CURRENT_PWM_E_PIN, 255L * current / MOTOR_CURRENT_PWM_RANGE); break;
@ -1235,19 +1234,19 @@ void digipot_current(uint8_t driver, int current) {
void microstep_init() {
#if HAS_MICROSTEPS_E1
pinMode(E1_MS1_PIN,OUTPUT);
pinMode(E1_MS2_PIN,OUTPUT);
pinMode(E1_MS1_PIN, OUTPUT);
pinMode(E1_MS2_PIN, OUTPUT);
#endif
#if HAS_MICROSTEPS
pinMode(X_MS1_PIN,OUTPUT);
pinMode(X_MS2_PIN,OUTPUT);
pinMode(Y_MS1_PIN,OUTPUT);
pinMode(Y_MS2_PIN,OUTPUT);
pinMode(Z_MS1_PIN,OUTPUT);
pinMode(Z_MS2_PIN,OUTPUT);
pinMode(E0_MS1_PIN,OUTPUT);
pinMode(E0_MS2_PIN,OUTPUT);
pinMode(X_MS1_PIN, OUTPUT);
pinMode(X_MS2_PIN, OUTPUT);
pinMode(Y_MS1_PIN, OUTPUT);
pinMode(Y_MS2_PIN, OUTPUT);
pinMode(Z_MS1_PIN, OUTPUT);
pinMode(Z_MS2_PIN, OUTPUT);
pinMode(E0_MS1_PIN, OUTPUT);
pinMode(E0_MS2_PIN, OUTPUT);
const uint8_t microstep_modes[] = MICROSTEP_MODES;
for (uint16_t i = 0; i < COUNT(microstep_modes); i++)
microstep_mode(i, microstep_modes[i]);
@ -1255,7 +1254,7 @@ void microstep_init() {
}
void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
if (ms1 >= 0) switch(driver) {
if (ms1 >= 0) switch (driver) {
case 0: digitalWrite(X_MS1_PIN, ms1); break;
case 1: digitalWrite(Y_MS1_PIN, ms1); break;
case 2: digitalWrite(Z_MS1_PIN, ms1); break;
@ -1264,7 +1263,7 @@ void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
case 4: digitalWrite(E1_MS1_PIN, ms1); break;
#endif
}
if (ms2 >= 0) switch(driver) {
if (ms2 >= 0) switch (driver) {
case 0: digitalWrite(X_MS2_PIN, ms2); break;
case 1: digitalWrite(Y_MS2_PIN, ms2); break;
case 2: digitalWrite(Z_MS2_PIN, ms2); break;
@ -1276,12 +1275,12 @@ void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) {
}
void microstep_mode(uint8_t driver, uint8_t stepping_mode) {
switch(stepping_mode) {
case 1: microstep_ms(driver,MICROSTEP1); break;
case 2: microstep_ms(driver,MICROSTEP2); break;
case 4: microstep_ms(driver,MICROSTEP4); break;
case 8: microstep_ms(driver,MICROSTEP8); break;
case 16: microstep_ms(driver,MICROSTEP16); break;
switch (stepping_mode) {
case 1: microstep_ms(driver, MICROSTEP1); break;
case 2: microstep_ms(driver, MICROSTEP2); break;
case 4: microstep_ms(driver, MICROSTEP4); break;
case 8: microstep_ms(driver, MICROSTEP8); break;
case 16: microstep_ms(driver, MICROSTEP16); break;
}
}

View File

@ -19,7 +19,7 @@
*/
#ifndef stepper_h
#define stepper_h
#define stepper_h
#include "planner.h"
#include "stepper_indirection.h"
@ -42,7 +42,7 @@
#define E_STEP_WRITE(v) { if(extruder_duplication_enabled) { E0_STEP_WRITE(v); E1_STEP_WRITE(v); } else if(current_block->active_extruder == 1) { E1_STEP_WRITE(v); } else { E0_STEP_WRITE(v); }}
#define NORM_E_DIR() { if(extruder_duplication_enabled) { E0_DIR_WRITE(!INVERT_E0_DIR); E1_DIR_WRITE(!INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { E1_DIR_WRITE(!INVERT_E1_DIR); } else { E0_DIR_WRITE(!INVERT_E0_DIR); }}
#define REV_E_DIR() { if(extruder_duplication_enabled) { E0_DIR_WRITE(INVERT_E0_DIR); E1_DIR_WRITE(INVERT_E1_DIR); } else if(current_block->active_extruder == 1) { E1_DIR_WRITE(INVERT_E1_DIR); } else { E0_DIR_WRITE(INVERT_E0_DIR); }}
#endif
#endif
#else
#define E_STEP_WRITE(v) E0_STEP_WRITE(v)
#define NORM_E_DIR() E0_DIR_WRITE(!INVERT_E0_DIR)
@ -60,8 +60,8 @@ void st_init();
void st_synchronize();
// Set current position in steps
void st_set_position(const long &x, const long &y, const long &z, const long &e);
void st_set_e_position(const long &e);
void st_set_position(const long& x, const long& y, const long& z, const long& e);
void st_set_e_position(const long& e);
// Get current position in steps
long st_get_position(uint8_t axis);
@ -73,7 +73,7 @@ float st_get_position_mm(AxisEnum axis);
// to notify the subsystem that it is time to go to work.
void st_wake_up();
void checkHitEndstops(); //call from somewhere to create an serial error message with the locations the endstops where hit, in case they were triggered
void endstops_hit_on_purpose(); //avoid creation of the message, i.e. after homing and before a routine call of checkHitEndstops();
@ -83,7 +83,7 @@ void checkStepperErrors(); //Print errors detected by the stepper
void finishAndDisableSteppers();
extern block_t *current_block; // A pointer to the block currently being traced
extern block_t* current_block; // A pointer to the block currently being traced
void quickStop();
@ -102,7 +102,7 @@ void microstep_readings();
#endif
#if ENABLED(BABYSTEPPING)
void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention
void babystep(const uint8_t axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif
#endif

View File

@ -1,5 +1,5 @@
/*
stepper_indirection.c - stepper motor driver indirection
stepper_indirection.c - stepper motor driver indirection
to allow some stepper functions to be done via SPI/I2c instead of direct pin manipulation
Part of Marlin
@ -29,78 +29,77 @@
// Stepper objects of TMC steppers used
#if ENABLED(X_IS_TMC)
TMC26XStepper stepperX(200,X_ENABLE_PIN,X_STEP_PIN,X_DIR_PIN,X_MAX_CURRENT,X_SENSE_RESISTOR);
TMC26XStepper stepperX(200, X_ENABLE_PIN, X_STEP_PIN, X_DIR_PIN, X_MAX_CURRENT, X_SENSE_RESISTOR);
#endif
#if ENABLED(X2_IS_TMC)
TMC26XStepper stepperX2(200,X2_ENABLE_PIN,X2_STEP_PIN,X2_DIR_PIN,X2_MAX_CURRENT,X2_SENSE_RESISTOR);
TMC26XStepper stepperX2(200, X2_ENABLE_PIN, X2_STEP_PIN, X2_DIR_PIN, X2_MAX_CURRENT, X2_SENSE_RESISTOR);
#endif
#if ENABLED(Y_IS_TMC)
TMC26XStepper stepperY(200,Y_ENABLE_PIN,Y_STEP_PIN,Y_DIR_PIN,Y_MAX_CURRENT,Y_SENSE_RESISTOR);
TMC26XStepper stepperY(200, Y_ENABLE_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_MAX_CURRENT, Y_SENSE_RESISTOR);
#endif
#if ENABLED(Y2_IS_TMC)
TMC26XStepper stepperY2(200,Y2_ENABLE_PIN,Y2_STEP_PIN,Y2_DIR_PIN,Y2_MAX_CURRENT,Y2_SENSE_RESISTOR);
TMC26XStepper stepperY2(200, Y2_ENABLE_PIN, Y2_STEP_PIN, Y2_DIR_PIN, Y2_MAX_CURRENT, Y2_SENSE_RESISTOR);
#endif
#if ENABLED(Z_IS_TMC)
TMC26XStepper stepperZ(200,Z_ENABLE_PIN,Z_STEP_PIN,Z_DIR_PIN,Z_MAX_CURRENT,Z_SENSE_RESISTOR);
TMC26XStepper stepperZ(200, Z_ENABLE_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_MAX_CURRENT, Z_SENSE_RESISTOR);
#endif
#if ENABLED(Z2_IS_TMC)
TMC26XStepper stepperZ2(200,Z2_ENABLE_PIN,Z2_STEP_PIN,Z2_DIR_PIN,Z2_MAX_CURRENT,Z2_SENSE_RESISTOR);
TMC26XStepper stepperZ2(200, Z2_ENABLE_PIN, Z2_STEP_PIN, Z2_DIR_PIN, Z2_MAX_CURRENT, Z2_SENSE_RESISTOR);
#endif
#if ENABLED(E0_IS_TMC)
TMC26XStepper stepperE0(200,E0_ENABLE_PIN,E0_STEP_PIN,E0_DIR_PIN,E0_MAX_CURRENT,E0_SENSE_RESISTOR);
TMC26XStepper stepperE0(200, E0_ENABLE_PIN, E0_STEP_PIN, E0_DIR_PIN, E0_MAX_CURRENT, E0_SENSE_RESISTOR);
#endif
#if ENABLED(E1_IS_TMC)
TMC26XStepper stepperE1(200,E1_ENABLE_PIN,E1_STEP_PIN,E1_DIR_PIN,E1_MAX_CURRENT,E1_SENSE_RESISTOR);
TMC26XStepper stepperE1(200, E1_ENABLE_PIN, E1_STEP_PIN, E1_DIR_PIN, E1_MAX_CURRENT, E1_SENSE_RESISTOR);
#endif
#if ENABLED(E2_IS_TMC)
TMC26XStepper stepperE2(200,E2_ENABLE_PIN,E2_STEP_PIN,E2_DIR_PIN,E2_MAX_CURRENT,E2_SENSE_RESISTOR);
TMC26XStepper stepperE2(200, E2_ENABLE_PIN, E2_STEP_PIN, E2_DIR_PIN, E2_MAX_CURRENT, E2_SENSE_RESISTOR);
#endif
#if ENABLED(E3_IS_TMC)
TMC26XStepper stepperE3(200,E3_ENABLE_PIN,E3_STEP_PIN,E3_DIR_PIN,E3_MAX_CURRENT,E3_SENSE_RESISTOR);
#endif
TMC26XStepper stepperE3(200, E3_ENABLE_PIN, E3_STEP_PIN, E3_DIR_PIN, E3_MAX_CURRENT, E3_SENSE_RESISTOR);
#endif
#if ENABLED(HAVE_TMCDRIVER)
void tmc_init()
{
void tmc_init() {
#if ENABLED(X_IS_TMC)
stepperX.setMicrosteps(X_MICROSTEPS);
stepperX.start();
stepperX.setMicrosteps(X_MICROSTEPS);
stepperX.start();
#endif
#if ENABLED(X2_IS_TMC)
stepperX2.setMicrosteps(X2_MICROSTEPS);
stepperX2.start();
stepperX2.setMicrosteps(X2_MICROSTEPS);
stepperX2.start();
#endif
#if ENABLED(Y_IS_TMC)
stepperY.setMicrosteps(Y_MICROSTEPS);
stepperY.start();
stepperY.setMicrosteps(Y_MICROSTEPS);
stepperY.start();
#endif
#if ENABLED(Y2_IS_TMC)
stepperY2.setMicrosteps(Y2_MICROSTEPS);
stepperY2.start();
stepperY2.setMicrosteps(Y2_MICROSTEPS);
stepperY2.start();
#endif
#if ENABLED(Z_IS_TMC)
stepperZ.setMicrosteps(Z_MICROSTEPS);
stepperZ.start();
stepperZ.setMicrosteps(Z_MICROSTEPS);
stepperZ.start();
#endif
#if ENABLED(Z2_IS_TMC)
stepperZ2.setMicrosteps(Z2_MICROSTEPS);
stepperZ2.start();
stepperZ2.setMicrosteps(Z2_MICROSTEPS);
stepperZ2.start();
#endif
#if ENABLED(E0_IS_TMC)
stepperE0.setMicrosteps(E0_MICROSTEPS);
stepperE0.start();
stepperE0.setMicrosteps(E0_MICROSTEPS);
stepperE0.start();
#endif
#if ENABLED(E1_IS_TMC)
stepperE1.setMicrosteps(E1_MICROSTEPS);
stepperE1.start();
stepperE1.setMicrosteps(E1_MICROSTEPS);
stepperE1.start();
#endif
#if ENABLED(E2_IS_TMC)
stepperE2.setMicrosteps(E2_MICROSTEPS);
stepperE2.start();
stepperE2.setMicrosteps(E2_MICROSTEPS);
stepperE2.start();
#endif
#if ENABLED(E3_IS_TMC)
stepperE3.setMicrosteps(E3_MICROSTEPS);
stepperE3.start();
stepperE3.setMicrosteps(E3_MICROSTEPS);
stepperE3.start();
#endif
}
#endif
@ -108,117 +107,116 @@ void tmc_init()
// L6470 Driver objects and inits
#if ENABLED(HAVE_L6470DRIVER)
#include <SPI.h>
#include <L6470.h>
#include <SPI.h>
#include <L6470.h>
#endif
// L6470 Stepper objects
#if ENABLED(X_IS_L6470)
L6470 stepperX(X_ENABLE_PIN);
#endif
#if ENABLED(X2_IS_L6470)
L6470 stepperX2(X2_ENABLE_PIN);
#endif
#if ENABLED(Y_IS_L6470)
L6470 stepperY(Y_ENABLE_PIN);
#endif
#if ENABLED(Y2_IS_L6470)
L6470 stepperY2(Y2_ENABLE_PIN);
#endif
#if ENABLED(Z_IS_L6470)
L6470 stepperZ(Z_ENABLE_PIN);
#endif
#if ENABLED(Z2_IS_L6470)
L6470 stepperZ2(Z2_ENABLE_PIN);
#endif
#if ENABLED(E0_IS_L6470)
L6470 stepperE0(E0_ENABLE_PIN);
#endif
#if ENABLED(E1_IS_L6470)
L6470 stepperE1(E1_ENABLE_PIN);
#endif
#if ENABLED(E2_IS_L6470)
L6470 stepperE2(E2_ENABLE_PIN);
#endif
#if ENABLED(E3_IS_L6470)
L6470 stepperE3(E3_ENABLE_PIN);
#endif
#if ENABLED(X_IS_L6470)
L6470 stepperX(X_ENABLE_PIN);
#endif
#if ENABLED(X2_IS_L6470)
L6470 stepperX2(X2_ENABLE_PIN);
#endif
#if ENABLED(Y_IS_L6470)
L6470 stepperY(Y_ENABLE_PIN);
#endif
#if ENABLED(Y2_IS_L6470)
L6470 stepperY2(Y2_ENABLE_PIN);
#endif
#if ENABLED(Z_IS_L6470)
L6470 stepperZ(Z_ENABLE_PIN);
#endif
#if ENABLED(Z2_IS_L6470)
L6470 stepperZ2(Z2_ENABLE_PIN);
#endif
#if ENABLED(E0_IS_L6470)
L6470 stepperE0(E0_ENABLE_PIN);
#endif
#if ENABLED(E1_IS_L6470)
L6470 stepperE1(E1_ENABLE_PIN);
#endif
#if ENABLED(E2_IS_L6470)
L6470 stepperE2(E2_ENABLE_PIN);
#endif
#if ENABLED(E3_IS_L6470)
L6470 stepperE3(E3_ENABLE_PIN);
#endif
// init routine
#if ENABLED(HAVE_L6470DRIVER)
void L6470_init()
{
void L6470_init() {
#if ENABLED(X_IS_L6470)
stepperX.init(X_K_VAL);
stepperX.softFree();
stepperX.setMicroSteps(X_MICROSTEPS);
stepperX.init(X_K_VAL);
stepperX.softFree();
stepperX.setMicroSteps(X_MICROSTEPS);
stepperX.setOverCurrent(X_OVERCURRENT); //set overcurrent protection
stepperX.setStallCurrent(X_STALLCURRENT);
#endif
#if ENABLED(X2_IS_L6470)
stepperX2.init(X2_K_VAL);
stepperX2.softFree();
stepperX2.setMicroSteps(X2_MICROSTEPS);
stepperX2.init(X2_K_VAL);
stepperX2.softFree();
stepperX2.setMicroSteps(X2_MICROSTEPS);
stepperX2.setOverCurrent(X2_OVERCURRENT); //set overcurrent protection
stepperX2.setStallCurrent(X2_STALLCURRENT);
#endif
#if ENABLED(Y_IS_L6470)
stepperY.init(Y_K_VAL);
stepperY.softFree();
stepperY.setMicroSteps(Y_MICROSTEPS);
stepperY.init(Y_K_VAL);
stepperY.softFree();
stepperY.setMicroSteps(Y_MICROSTEPS);
stepperY.setOverCurrent(Y_OVERCURRENT); //set overcurrent protection
stepperY.setStallCurrent(Y_STALLCURRENT);
#endif
#if ENABLED(Y2_IS_L6470)
stepperY2.init(Y2_K_VAL);
stepperY2.softFree();
stepperY2.setMicroSteps(Y2_MICROSTEPS);
stepperY2.init(Y2_K_VAL);
stepperY2.softFree();
stepperY2.setMicroSteps(Y2_MICROSTEPS);
stepperY2.setOverCurrent(Y2_OVERCURRENT); //set overcurrent protection
stepperY2.setStallCurrent(Y2_STALLCURRENT);
#endif
#if ENABLED(Z_IS_L6470)
stepperZ.init(Z_K_VAL);
stepperZ.softFree();
stepperZ.setMicroSteps(Z_MICROSTEPS);
stepperZ.init(Z_K_VAL);
stepperZ.softFree();
stepperZ.setMicroSteps(Z_MICROSTEPS);
stepperZ.setOverCurrent(Z_OVERCURRENT); //set overcurrent protection
stepperZ.setStallCurrent(Z_STALLCURRENT);
#endif
#if ENABLED(Z2_IS_L6470)
stepperZ2.init(Z2_K_VAL);
stepperZ2.softFree();
stepperZ2.setMicroSteps(Z2_MICROSTEPS);
stepperZ2.init(Z2_K_VAL);
stepperZ2.softFree();
stepperZ2.setMicroSteps(Z2_MICROSTEPS);
stepperZ2.setOverCurrent(Z2_OVERCURRENT); //set overcurrent protection
stepperZ2.setStallCurrent(Z2_STALLCURRENT);
#endif
#if ENABLED(E0_IS_L6470)
stepperE0.init(E0_K_VAL);
stepperE0.softFree();
stepperE0.setMicroSteps(E0_MICROSTEPS);
stepperE0.init(E0_K_VAL);
stepperE0.softFree();
stepperE0.setMicroSteps(E0_MICROSTEPS);
stepperE0.setOverCurrent(E0_OVERCURRENT); //set overcurrent protection
stepperE0.setStallCurrent(E0_STALLCURRENT);
#endif
#if ENABLED(E1_IS_L6470)
stepperE1.init(E1_K_VAL);
stepperE1.softFree();
stepperE1.setMicroSteps(E1_MICROSTEPS);
stepperE1.init(E1_K_VAL);
stepperE1.softFree();
stepperE1.setMicroSteps(E1_MICROSTEPS);
stepperE1.setOverCurrent(E1_OVERCURRENT); //set overcurrent protection
stepperE1.setStallCurrent(E1_STALLCURRENT);
#endif
#if ENABLED(E2_IS_L6470)
stepperE2.init(E2_K_VAL);
stepperE2.softFree();
stepperE2.setMicroSteps(E2_MICROSTEPS);
stepperE2.init(E2_K_VAL);
stepperE2.softFree();
stepperE2.setMicroSteps(E2_MICROSTEPS);
stepperE2.setOverCurrent(E2_OVERCURRENT); //set overcurrent protection
stepperE2.setStallCurrent(E2_STALLCURRENT);
#endif
#if ENABLED(E3_IS_L6470)
stepperE3.init(E3_K_VAL);
stepperE3.softFree();
stepperE3.setMicroSteps(E3_MICROSTEPS);
stepperE3.init(E3_K_VAL);
stepperE3.softFree();
stepperE3.setMicroSteps(E3_MICROSTEPS);
stepperE3.setOverCurrent(E3_OVERCURRENT); //set overcurrent protection
stepperE3.setStallCurrent(E3_STALLCURRENT);
#endif
#endif
}
#endif

View File

@ -155,339 +155,339 @@
#define E3_ENABLE_READ READ(E3_ENABLE_PIN)
//////////////////////////////////
// Pin redefines for TMC drivers.
// Pin redefines for TMC drivers.
// TMC26X drivers have step and dir on normal pins, but everything else via SPI
//////////////////////////////////
#if ENABLED(HAVE_TMCDRIVER)
#include <SPI.h>
#include <TMC26XStepper.h>
#include <SPI.h>
#include <TMC26XStepper.h>
void tmc_init();
#if ENABLED(X_IS_TMC)
extern TMC26XStepper stepperX;
#undef X_ENABLE_INIT
#define X_ENABLE_INIT ((void)0)
#undef X_ENABLE_WRITE
#define X_ENABLE_WRITE(STATE) stepperX.setEnabled(STATE)
#undef X_ENABLE_READ
#define X_ENABLE_READ stepperX.isEnabled()
#endif
#if ENABLED(X2_IS_TMC)
extern TMC26XStepper stepperX2;
#undef X2_ENABLE_INIT
#define X2_ENABLE_INIT ((void)0)
#undef X2_ENABLE_WRITE
#define X2_ENABLE_WRITE(STATE) stepperX2.setEnabled(STATE)
#undef X2_ENABLE_READ
#define X2_ENABLE_READ stepperX2.isEnabled()
#endif
#if ENABLED(Y_IS_TMC)
extern TMC26XStepper stepperY;
#undef Y_ENABLE_INIT
#define Y_ENABLE_INIT ((void)0)
#undef Y_ENABLE_WRITE
#define Y_ENABLE_WRITE(STATE) stepperY.setEnabled(STATE)
#undef Y_ENABLE_READ
#define Y_ENABLE_READ stepperY.isEnabled()
#endif
#if ENABLED(Y2_IS_TMC)
extern TMC26XStepper stepperY2;
#undef Y2_ENABLE_INIT
#define Y2_ENABLE_INIT ((void)0)
#undef Y2_ENABLE_WRITE
#define Y2_ENABLE_WRITE(STATE) stepperY2.setEnabled(STATE)
#undef Y2_ENABLE_READ
#define Y2_ENABLE_READ stepperY2.isEnabled()
#endif
#if ENABLED(Z_IS_TMC)
extern TMC26XStepper stepperZ;
#undef Z_ENABLE_INIT
#define Z_ENABLE_INIT ((void)0)
#undef Z_ENABLE_WRITE
#define Z_ENABLE_WRITE(STATE) stepperZ.setEnabled(STATE)
#undef Z_ENABLE_READ
#define Z_ENABLE_READ stepperZ.isEnabled()
#endif
#if ENABLED(Z2_IS_TMC)
extern TMC26XStepper stepperZ2;
#undef Z2_ENABLE_INIT
#define Z2_ENABLE_INIT ((void)0)
#undef Z2_ENABLE_WRITE
#define Z2_ENABLE_WRITE(STATE) stepperZ2.setEnabled(STATE)
#undef Z2_ENABLE_READ
#define Z2_ENABLE_READ stepperZ2.isEnabled()
#endif
#if ENABLED(E0_IS_TMC)
extern TMC26XStepper stepperE0;
#undef E0_ENABLE_INIT
#define E0_ENABLE_INIT ((void)0)
#undef E0_ENABLE_WRITE
#define E0_ENABLE_WRITE(STATE) stepperE0.setEnabled(STATE)
#undef E0_ENABLE_READ
#define E0_ENABLE_READ stepperE0.isEnabled()
#endif
#if ENABLED(E1_IS_TMC)
extern TMC26XStepper stepperE1;
#undef E1_ENABLE_INIT
#define E1_ENABLE_INIT ((void)0)
#undef E1_ENABLE_WRITE
#define E1_ENABLE_WRITE(STATE) stepperE1.setEnabled(STATE)
#undef E1_ENABLE_READ
#define E1_ENABLE_READ stepperE1.isEnabled()
#endif
#if ENABLED(E2_IS_TMC)
extern TMC26XStepper stepperE2;
#undef E2_ENABLE_INIT
#define E2_ENABLE_INIT ((void)0)
#undef E2_ENABLE_WRITE
#define E2_ENABLE_WRITE(STATE) stepperE2.setEnabled(STATE)
#undef E2_ENABLE_READ
#define E2_ENABLE_READ stepperE2.isEnabled()
#endif
#if ENABLED(E3_IS_TMC)
extern TMC26XStepper stepperE3;
#undef E3_ENABLE_INIT
#define E3_ENABLE_INIT ((void)0)
#undef E3_ENABLE_WRITE
#define E3_ENABLE_WRITE(STATE) stepperE3.setEnabled(STATE)
#undef E3_ENABLE_READ
#define E3_ENABLE_READ stepperE3.isEnabled()
#endif
#if ENABLED(X_IS_TMC)
extern TMC26XStepper stepperX;
#undef X_ENABLE_INIT
#define X_ENABLE_INIT ((void)0)
#undef X_ENABLE_WRITE
#define X_ENABLE_WRITE(STATE) stepperX.setEnabled(STATE)
#undef X_ENABLE_READ
#define X_ENABLE_READ stepperX.isEnabled()
#endif
#if ENABLED(X2_IS_TMC)
extern TMC26XStepper stepperX2;
#undef X2_ENABLE_INIT
#define X2_ENABLE_INIT ((void)0)
#undef X2_ENABLE_WRITE
#define X2_ENABLE_WRITE(STATE) stepperX2.setEnabled(STATE)
#undef X2_ENABLE_READ
#define X2_ENABLE_READ stepperX2.isEnabled()
#endif
#if ENABLED(Y_IS_TMC)
extern TMC26XStepper stepperY;
#undef Y_ENABLE_INIT
#define Y_ENABLE_INIT ((void)0)
#undef Y_ENABLE_WRITE
#define Y_ENABLE_WRITE(STATE) stepperY.setEnabled(STATE)
#undef Y_ENABLE_READ
#define Y_ENABLE_READ stepperY.isEnabled()
#endif
#if ENABLED(Y2_IS_TMC)
extern TMC26XStepper stepperY2;
#undef Y2_ENABLE_INIT
#define Y2_ENABLE_INIT ((void)0)
#undef Y2_ENABLE_WRITE
#define Y2_ENABLE_WRITE(STATE) stepperY2.setEnabled(STATE)
#undef Y2_ENABLE_READ
#define Y2_ENABLE_READ stepperY2.isEnabled()
#endif
#if ENABLED(Z_IS_TMC)
extern TMC26XStepper stepperZ;
#undef Z_ENABLE_INIT
#define Z_ENABLE_INIT ((void)0)
#undef Z_ENABLE_WRITE
#define Z_ENABLE_WRITE(STATE) stepperZ.setEnabled(STATE)
#undef Z_ENABLE_READ
#define Z_ENABLE_READ stepperZ.isEnabled()
#endif
#if ENABLED(Z2_IS_TMC)
extern TMC26XStepper stepperZ2;
#undef Z2_ENABLE_INIT
#define Z2_ENABLE_INIT ((void)0)
#undef Z2_ENABLE_WRITE
#define Z2_ENABLE_WRITE(STATE) stepperZ2.setEnabled(STATE)
#undef Z2_ENABLE_READ
#define Z2_ENABLE_READ stepperZ2.isEnabled()
#endif
#if ENABLED(E0_IS_TMC)
extern TMC26XStepper stepperE0;
#undef E0_ENABLE_INIT
#define E0_ENABLE_INIT ((void)0)
#undef E0_ENABLE_WRITE
#define E0_ENABLE_WRITE(STATE) stepperE0.setEnabled(STATE)
#undef E0_ENABLE_READ
#define E0_ENABLE_READ stepperE0.isEnabled()
#endif
#if ENABLED(E1_IS_TMC)
extern TMC26XStepper stepperE1;
#undef E1_ENABLE_INIT
#define E1_ENABLE_INIT ((void)0)
#undef E1_ENABLE_WRITE
#define E1_ENABLE_WRITE(STATE) stepperE1.setEnabled(STATE)
#undef E1_ENABLE_READ
#define E1_ENABLE_READ stepperE1.isEnabled()
#endif
#if ENABLED(E2_IS_TMC)
extern TMC26XStepper stepperE2;
#undef E2_ENABLE_INIT
#define E2_ENABLE_INIT ((void)0)
#undef E2_ENABLE_WRITE
#define E2_ENABLE_WRITE(STATE) stepperE2.setEnabled(STATE)
#undef E2_ENABLE_READ
#define E2_ENABLE_READ stepperE2.isEnabled()
#endif
#if ENABLED(E3_IS_TMC)
extern TMC26XStepper stepperE3;
#undef E3_ENABLE_INIT
#define E3_ENABLE_INIT ((void)0)
#undef E3_ENABLE_WRITE
#define E3_ENABLE_WRITE(STATE) stepperE3.setEnabled(STATE)
#undef E3_ENABLE_READ
#define E3_ENABLE_READ stepperE3.isEnabled()
#endif
#endif // HAVE_TMCDRIVER
//////////////////////////////////
// Pin redefines for L6470 drivers.
// Pin redefines for L6470 drivers.
// L640 drivers have step on normal pins, but dir and everything else via SPI
//////////////////////////////////
#if ENABLED(HAVE_L6470DRIVER)
#include <SPI.h>
#include <L6470.h>
#include <SPI.h>
#include <L6470.h>
void L6470_init();
#if ENABLED(X_IS_L6470)
extern L6470 stepperX;
#undef X_ENABLE_INIT
#define X_ENABLE_INIT ((void)0)
#undef X_ENABLE_WRITE
#define X_ENABLE_WRITE(STATE) {if(STATE) stepperX.Step_Clock(stepperX.getStatus() & STATUS_HIZ); else stepperX.softFree();}
#undef X_ENABLE_READ
#define X_ENABLE_READ (stepperX.getStatus() & STATUS_HIZ)
#undef X_DIR_INIT
#define X_DIR_INIT ((void)0)
#undef X_DIR_WRITE
#define X_DIR_WRITE(STATE) stepperX.Step_Clock(STATE)
#undef X_DIR_READ
#define X_DIR_READ (stepperX.getStatus() & STATUS_DIR)
#endif
#if ENABLED(X2_IS_L6470)
extern L6470 stepperX2;
#undef X2_ENABLE_INIT
#define X2_ENABLE_INIT ((void)0)
#undef X2_ENABLE_WRITE
#define X2_ENABLE_WRITE(STATE) (if(STATE) stepperX2.Step_Clock(stepperX2.getStatus() & STATUS_HIZ); else stepperX2.softFree();)
#undef X2_ENABLE_READ
#define X2_ENABLE_READ (stepperX2.getStatus() & STATUS_HIZ)
#undef X2_DIR_INIT
#define X2_DIR_INIT ((void)0)
#undef X2_DIR_WRITE
#define X2_DIR_WRITE(STATE) stepperX2.Step_Clock(STATE)
#undef X2_DIR_READ
#define X2_DIR_READ (stepperX2.getStatus() & STATUS_DIR)
#endif
#if ENABLED(Y_IS_L6470)
extern L6470 stepperY;
#undef Y_ENABLE_INIT
#define Y_ENABLE_INIT ((void)0)
#undef Y_ENABLE_WRITE
#define Y_ENABLE_WRITE(STATE) (if(STATE) stepperY.Step_Clock(stepperY.getStatus() & STATUS_HIZ); else stepperY.softFree();)
#undef Y_ENABLE_READ
#define Y_ENABLE_READ (stepperY.getStatus() & STATUS_HIZ)
#undef Y_DIR_INIT
#define Y_DIR_INIT ((void)0)
#undef Y_DIR_WRITE
#define Y_DIR_WRITE(STATE) stepperY.Step_Clock(STATE)
#undef Y_DIR_READ
#define Y_DIR_READ (stepperY.getStatus() & STATUS_DIR)
#endif
#if ENABLED(Y2_IS_L6470)
extern L6470 stepperY2;
#undef Y2_ENABLE_INIT
#define Y2_ENABLE_INIT ((void)0)
#undef Y2_ENABLE_WRITE
#define Y2_ENABLE_WRITE(STATE) (if(STATE) stepperY2.Step_Clock(stepperY2.getStatus() & STATUS_HIZ); else stepperY2.softFree();)
#undef Y2_ENABLE_READ
#define Y2_ENABLE_READ (stepperY2.getStatus() & STATUS_HIZ)
#undef Y2_DIR_INIT
#define Y2_DIR_INIT ((void)0)
#undef Y2_DIR_WRITE
#define Y2_DIR_WRITE(STATE) stepperY2.Step_Clock(STATE)
#undef Y2_DIR_READ
#define Y2_DIR_READ (stepperY2.getStatus() & STATUS_DIR)
#endif
#if ENABLED(Z_IS_L6470)
extern L6470 stepperZ;
#undef Z_ENABLE_INIT
#define Z_ENABLE_INIT ((void)0)
#undef Z_ENABLE_WRITE
#define Z_ENABLE_WRITE(STATE) (if(STATE) stepperZ.Step_Clock(stepperZ.getStatus() & STATUS_HIZ); else stepperZ.softFree();)
#undef Z_ENABLE_READ
#define Z_ENABLE_READ (stepperZ.getStatus() & STATUS_HIZ)
#undef Z_DIR_INIT
#define Z_DIR_INIT ((void)0)
#undef Z_DIR_WRITE
#define Z_DIR_WRITE(STATE) stepperZ.Step_Clock(STATE)
#undef Y_DIR_READ
#define Y_DIR_READ (stepperZ.getStatus() & STATUS_DIR)
#endif
#if ENABLED(Z2_IS_L6470)
extern L6470 stepperZ2;
#undef Z2_ENABLE_INIT
#define Z2_ENABLE_INIT ((void)0)
#undef Z2_ENABLE_WRITE
#define Z2_ENABLE_WRITE(STATE) (if(STATE) stepperZ2.Step_Clock(stepperZ2.getStatus() & STATUS_HIZ); else stepperZ2.softFree();)
#undef Z2_ENABLE_READ
#define Z2_ENABLE_READ (stepperZ2.getStatus() & STATUS_HIZ)
#undef Z2_DIR_INIT
#define Z2_DIR_INIT ((void)0)
#undef Z2_DIR_WRITE
#define Z2_DIR_WRITE(STATE) stepperZ2.Step_Clock(STATE)
#undef Y2_DIR_READ
#define Y2_DIR_READ (stepperZ2.getStatus() & STATUS_DIR)
#endif
#if ENABLED(E0_IS_L6470)
extern L6470 stepperE0;
#undef E0_ENABLE_INIT
#define E0_ENABLE_INIT ((void)0)
#undef E0_ENABLE_WRITE
#define E0_ENABLE_WRITE(STATE) (if(STATE) stepperE0.Step_Clock(stepperE0.getStatus() & STATUS_HIZ); else stepperE0.softFree();)
#undef E0_ENABLE_READ
#define E0_ENABLE_READ (stepperE0.getStatus() & STATUS_HIZ)
#undef E0_DIR_INIT
#define E0_DIR_INIT ((void)0)
#undef E0_DIR_WRITE
#define E0_DIR_WRITE(STATE) stepperE0.Step_Clock(STATE)
#undef E0_DIR_READ
#define E0_DIR_READ (stepperE0.getStatus() & STATUS_DIR)
#endif
#if ENABLED(E1_IS_L6470)
extern L6470 stepperE1;
#undef E1_ENABLE_INIT
#define E1_ENABLE_INIT ((void)0)
#undef E1_ENABLE_WRITE
#define E1_ENABLE_WRITE(STATE) (if(STATE) stepperE1.Step_Clock(stepperE1.getStatus() & STATUS_HIZ); else stepperE1.softFree();)
#undef E1_ENABLE_READ
#define E1_ENABLE_READ (stepperE1.getStatus() & STATUS_HIZ)
#undef E1_DIR_INIT
#define E1_DIR_INIT ((void)0)
#undef E1_DIR_WRITE
#define E1_DIR_WRITE(STATE) stepperE1.Step_Clock(STATE)
#undef E1_DIR_READ
#define E1_DIR_READ (stepperE1.getStatus() & STATUS_DIR)
#endif
#if ENABLED(E2_IS_L6470)
extern L6470 stepperE2;
#undef E2_ENABLE_INIT
#define E2_ENABLE_INIT ((void)0)
#undef E2_ENABLE_WRITE
#define E2_ENABLE_WRITE(STATE) (if(STATE) stepperE2.Step_Clock(stepperE2.getStatus() & STATUS_HIZ); else stepperE2.softFree();)
#undef E2_ENABLE_READ
#define E2_ENABLE_READ (stepperE2.getStatus() & STATUS_HIZ)
#undef E2_DIR_INIT
#define E2_DIR_INIT ((void)0)
#undef E2_DIR_WRITE
#define E2_DIR_WRITE(STATE) stepperE2.Step_Clock(STATE)
#undef E2_DIR_READ
#define E2_DIR_READ (stepperE2.getStatus() & STATUS_DIR)
#endif
#if ENABLED(E3_IS_L6470)
extern L6470 stepperE3;
#undef E3_ENABLE_INIT
#define E3_ENABLE_INIT ((void)0)
#undef E3_ENABLE_WRITE
#define E3_ENABLE_WRITE(STATE) (if(STATE) stepperE3.Step_Clock(stepperE3.getStatus() & STATUS_HIZ); else stepperE3.softFree();)
#undef E3_ENABLE_READ
#define E3_ENABLE_READ (stepperE3.getStatus() & STATUS_HIZ)
#undef E3_DIR_INIT
#define E3_DIR_INIT ((void)0)
#undef E3_DIR_WRITE
#define E3_DIR_WRITE(STATE) stepperE3.Step_Clock(STATE)
#undef E3_DIR_READ
#define E3_DIR_READ (stepperE3.getStatus() & STATUS_DIR)
#endif
#if ENABLED(X_IS_L6470)
extern L6470 stepperX;
#undef X_ENABLE_INIT
#define X_ENABLE_INIT ((void)0)
#undef X_ENABLE_WRITE
#define X_ENABLE_WRITE(STATE) {if(STATE) stepperX.Step_Clock(stepperX.getStatus() & STATUS_HIZ); else stepperX.softFree();}
#undef X_ENABLE_READ
#define X_ENABLE_READ (stepperX.getStatus() & STATUS_HIZ)
#undef X_DIR_INIT
#define X_DIR_INIT ((void)0)
#undef X_DIR_WRITE
#define X_DIR_WRITE(STATE) stepperX.Step_Clock(STATE)
#undef X_DIR_READ
#define X_DIR_READ (stepperX.getStatus() & STATUS_DIR)
#endif
#if ENABLED(X2_IS_L6470)
extern L6470 stepperX2;
#undef X2_ENABLE_INIT
#define X2_ENABLE_INIT ((void)0)
#undef X2_ENABLE_WRITE
#define X2_ENABLE_WRITE(STATE) (if(STATE) stepperX2.Step_Clock(stepperX2.getStatus() & STATUS_HIZ); else stepperX2.softFree();)
#undef X2_ENABLE_READ
#define X2_ENABLE_READ (stepperX2.getStatus() & STATUS_HIZ)
#undef X2_DIR_INIT
#define X2_DIR_INIT ((void)0)
#undef X2_DIR_WRITE
#define X2_DIR_WRITE(STATE) stepperX2.Step_Clock(STATE)
#undef X2_DIR_READ
#define X2_DIR_READ (stepperX2.getStatus() & STATUS_DIR)
#endif
#if ENABLED(Y_IS_L6470)
extern L6470 stepperY;
#undef Y_ENABLE_INIT
#define Y_ENABLE_INIT ((void)0)
#undef Y_ENABLE_WRITE
#define Y_ENABLE_WRITE(STATE) (if(STATE) stepperY.Step_Clock(stepperY.getStatus() & STATUS_HIZ); else stepperY.softFree();)
#undef Y_ENABLE_READ
#define Y_ENABLE_READ (stepperY.getStatus() & STATUS_HIZ)
#undef Y_DIR_INIT
#define Y_DIR_INIT ((void)0)
#undef Y_DIR_WRITE
#define Y_DIR_WRITE(STATE) stepperY.Step_Clock(STATE)
#undef Y_DIR_READ
#define Y_DIR_READ (stepperY.getStatus() & STATUS_DIR)
#endif
#if ENABLED(Y2_IS_L6470)
extern L6470 stepperY2;
#undef Y2_ENABLE_INIT
#define Y2_ENABLE_INIT ((void)0)
#undef Y2_ENABLE_WRITE
#define Y2_ENABLE_WRITE(STATE) (if(STATE) stepperY2.Step_Clock(stepperY2.getStatus() & STATUS_HIZ); else stepperY2.softFree();)
#undef Y2_ENABLE_READ
#define Y2_ENABLE_READ (stepperY2.getStatus() & STATUS_HIZ)
#undef Y2_DIR_INIT
#define Y2_DIR_INIT ((void)0)
#undef Y2_DIR_WRITE
#define Y2_DIR_WRITE(STATE) stepperY2.Step_Clock(STATE)
#undef Y2_DIR_READ
#define Y2_DIR_READ (stepperY2.getStatus() & STATUS_DIR)
#endif
#if ENABLED(Z_IS_L6470)
extern L6470 stepperZ;
#undef Z_ENABLE_INIT
#define Z_ENABLE_INIT ((void)0)
#undef Z_ENABLE_WRITE
#define Z_ENABLE_WRITE(STATE) (if(STATE) stepperZ.Step_Clock(stepperZ.getStatus() & STATUS_HIZ); else stepperZ.softFree();)
#undef Z_ENABLE_READ
#define Z_ENABLE_READ (stepperZ.getStatus() & STATUS_HIZ)
#undef Z_DIR_INIT
#define Z_DIR_INIT ((void)0)
#undef Z_DIR_WRITE
#define Z_DIR_WRITE(STATE) stepperZ.Step_Clock(STATE)
#undef Y_DIR_READ
#define Y_DIR_READ (stepperZ.getStatus() & STATUS_DIR)
#endif
#if ENABLED(Z2_IS_L6470)
extern L6470 stepperZ2;
#undef Z2_ENABLE_INIT
#define Z2_ENABLE_INIT ((void)0)
#undef Z2_ENABLE_WRITE
#define Z2_ENABLE_WRITE(STATE) (if(STATE) stepperZ2.Step_Clock(stepperZ2.getStatus() & STATUS_HIZ); else stepperZ2.softFree();)
#undef Z2_ENABLE_READ
#define Z2_ENABLE_READ (stepperZ2.getStatus() & STATUS_HIZ)
#undef Z2_DIR_INIT
#define Z2_DIR_INIT ((void)0)
#undef Z2_DIR_WRITE
#define Z2_DIR_WRITE(STATE) stepperZ2.Step_Clock(STATE)
#undef Y2_DIR_READ
#define Y2_DIR_READ (stepperZ2.getStatus() & STATUS_DIR)
#endif
#if ENABLED(E0_IS_L6470)
extern L6470 stepperE0;
#undef E0_ENABLE_INIT
#define E0_ENABLE_INIT ((void)0)
#undef E0_ENABLE_WRITE
#define E0_ENABLE_WRITE(STATE) (if(STATE) stepperE0.Step_Clock(stepperE0.getStatus() & STATUS_HIZ); else stepperE0.softFree();)
#undef E0_ENABLE_READ
#define E0_ENABLE_READ (stepperE0.getStatus() & STATUS_HIZ)
#undef E0_DIR_INIT
#define E0_DIR_INIT ((void)0)
#undef E0_DIR_WRITE
#define E0_DIR_WRITE(STATE) stepperE0.Step_Clock(STATE)
#undef E0_DIR_READ
#define E0_DIR_READ (stepperE0.getStatus() & STATUS_DIR)
#endif
#if ENABLED(E1_IS_L6470)
extern L6470 stepperE1;
#undef E1_ENABLE_INIT
#define E1_ENABLE_INIT ((void)0)
#undef E1_ENABLE_WRITE
#define E1_ENABLE_WRITE(STATE) (if(STATE) stepperE1.Step_Clock(stepperE1.getStatus() & STATUS_HIZ); else stepperE1.softFree();)
#undef E1_ENABLE_READ
#define E1_ENABLE_READ (stepperE1.getStatus() & STATUS_HIZ)
#undef E1_DIR_INIT
#define E1_DIR_INIT ((void)0)
#undef E1_DIR_WRITE
#define E1_DIR_WRITE(STATE) stepperE1.Step_Clock(STATE)
#undef E1_DIR_READ
#define E1_DIR_READ (stepperE1.getStatus() & STATUS_DIR)
#endif
#if ENABLED(E2_IS_L6470)
extern L6470 stepperE2;
#undef E2_ENABLE_INIT
#define E2_ENABLE_INIT ((void)0)
#undef E2_ENABLE_WRITE
#define E2_ENABLE_WRITE(STATE) (if(STATE) stepperE2.Step_Clock(stepperE2.getStatus() & STATUS_HIZ); else stepperE2.softFree();)
#undef E2_ENABLE_READ
#define E2_ENABLE_READ (stepperE2.getStatus() & STATUS_HIZ)
#undef E2_DIR_INIT
#define E2_DIR_INIT ((void)0)
#undef E2_DIR_WRITE
#define E2_DIR_WRITE(STATE) stepperE2.Step_Clock(STATE)
#undef E2_DIR_READ
#define E2_DIR_READ (stepperE2.getStatus() & STATUS_DIR)
#endif
#if ENABLED(E3_IS_L6470)
extern L6470 stepperE3;
#undef E3_ENABLE_INIT
#define E3_ENABLE_INIT ((void)0)
#undef E3_ENABLE_WRITE
#define E3_ENABLE_WRITE(STATE) (if(STATE) stepperE3.Step_Clock(stepperE3.getStatus() & STATUS_HIZ); else stepperE3.softFree();)
#undef E3_ENABLE_READ
#define E3_ENABLE_READ (stepperE3.getStatus() & STATUS_HIZ)
#undef E3_DIR_INIT
#define E3_DIR_INIT ((void)0)
#undef E3_DIR_WRITE
#define E3_DIR_WRITE(STATE) stepperE3.Step_Clock(STATE)
#undef E3_DIR_READ
#define E3_DIR_READ (stepperE3.getStatus() & STATUS_DIR)
#endif
#endif //HAVE_L6470DRIVER

View File

@ -1,19 +1,19 @@
/*
temperature.cpp - temperature control
Part of Marlin
Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
@ -54,28 +54,28 @@ float current_temperature_bed = 0.0;
#endif
#if ENABLED(PIDTEMPBED)
float bedKp=DEFAULT_bedKp;
float bedKi=(DEFAULT_bedKi*PID_dT);
float bedKd=(DEFAULT_bedKd/PID_dT);
float bedKp = DEFAULT_bedKp;
float bedKi = (DEFAULT_bedKi* PID_dT);
float bedKd = (DEFAULT_bedKd / PID_dT);
#endif //PIDTEMPBED
#if ENABLED(FAN_SOFT_PWM)
unsigned char fanSpeedSoftPwm;
#endif
unsigned char soft_pwm_bed;
#if ENABLED(BABYSTEPPING)
volatile int babystepsTodo[3] = { 0 };
#endif
#if ENABLED(FILAMENT_SENSOR)
int current_raw_filwidth = 0; //Holds measured filament diameter - one extruder only
#endif
#endif
#if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED)
enum TRState { TRReset, TRInactive, TRFirstHeating, TRStable, TRRunaway };
void thermal_runaway_protection(TRState *state, millis_t *timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc);
void thermal_runaway_protection(TRState* state, millis_t* timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc);
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
static TRState thermal_runaway_state_machine[4] = { TRReset, TRReset, TRReset, TRReset };
static millis_t thermal_runaway_timer[4]; // = {0,0,0,0};
@ -125,19 +125,19 @@ static volatile bool temp_meas_ready = false;
#else //PIDTEMPBED
static millis_t next_bed_check_ms;
#endif //PIDTEMPBED
static unsigned char soft_pwm[EXTRUDERS];
static unsigned char soft_pwm[EXTRUDERS];
#if ENABLED(FAN_SOFT_PWM)
static unsigned char soft_pwm_fan;
#endif
#if HAS_AUTO_FAN
static millis_t next_auto_fan_check_ms;
#endif
#endif
#if ENABLED(PIDTEMP)
#if ENABLED(PID_PARAMS_PER_EXTRUDER)
float Kp[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Kp);
float Ki[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Ki*PID_dT);
float Ki[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Ki* PID_dT);
float Kd[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Kd / PID_dT);
#if ENABLED(PID_ADD_EXTRUSION_RATE)
float Kc[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Kc);
@ -153,23 +153,23 @@ static volatile bool temp_meas_ready = false;
#endif //PIDTEMP
// Init min and max temp with extreme values to prevent false errors during startup
static int minttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_LO_TEMP , HEATER_1_RAW_LO_TEMP , HEATER_2_RAW_LO_TEMP, HEATER_3_RAW_LO_TEMP);
static int maxttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_HI_TEMP , HEATER_1_RAW_HI_TEMP , HEATER_2_RAW_HI_TEMP, HEATER_3_RAW_HI_TEMP);
static int minttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS(HEATER_0_RAW_LO_TEMP , HEATER_1_RAW_LO_TEMP , HEATER_2_RAW_LO_TEMP, HEATER_3_RAW_LO_TEMP);
static int maxttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS(HEATER_0_RAW_HI_TEMP , HEATER_1_RAW_HI_TEMP , HEATER_2_RAW_HI_TEMP, HEATER_3_RAW_HI_TEMP);
static int minttemp[EXTRUDERS] = { 0 };
static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(16383);
#ifdef BED_MINTEMP
static int bed_minttemp_raw = HEATER_BED_RAW_LO_TEMP;
static int bed_minttemp_raw = HEATER_BED_RAW_LO_TEMP;
#endif
#ifdef BED_MAXTEMP
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
#endif
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
static void *heater_ttbl_map[2] = {(void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE };
static void* heater_ttbl_map[2] = {(void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE };
static uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN };
#else
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE, (void *)HEATER_3_TEMPTABLE );
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN, HEATER_3_TEMPTABLE_LEN );
static void* heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS((void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE, (void*)HEATER_2_TEMPTABLE, (void*)HEATER_3_TEMPTABLE);
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS(HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN, HEATER_3_TEMPTABLE_LEN);
#endif
static float analog2temp(int raw, uint8_t e);
@ -222,7 +222,7 @@ void PID_autotune(float temp, int extruder, int ncycles) {
SERIAL_ECHOLN(MSG_PID_BAD_EXTRUDER_NUM);
return;
}
SERIAL_ECHOLN(MSG_PID_AUTOTUNE_START);
disable_all_heaters(); // switch off all heaters.
@ -240,7 +240,7 @@ void PID_autotune(float temp, int extruder, int ncycles) {
if (temp_meas_ready) { // temp sample ready
updateTemperaturesFromRawValues();
input = (extruder<0)?current_temperature_bed:current_temperature[extruder];
input = (extruder < 0) ? current_temperature_bed : current_temperature[extruder];
max = max(max, input);
min = min(min, input);
@ -272,7 +272,7 @@ void PID_autotune(float temp, int extruder, int ncycles) {
t_low = t2 - t1;
if (cycles > 0) {
long max_pow = extruder < 0 ? MAX_BED_POWER : PID_MAX;
bias += (d*(t_high - t_low))/(t_low + t_high);
bias += (d * (t_high - t_low)) / (t_low + t_high);
bias = constrain(bias, 20, max_pow - 20);
d = (bias > max_pow / 2) ? max_pow - 1 - bias : bias;
@ -317,7 +317,7 @@ void PID_autotune(float temp, int extruder, int ncycles) {
cycles++;
min = temp;
}
}
}
}
#define MAX_OVERSHOOT_PID_AUTOTUNE 20
if (input > temp + MAX_OVERSHOOT_PID_AUTOTUNE) {
@ -343,13 +343,13 @@ void PID_autotune(float temp, int extruder, int ncycles) {
temp_ms = ms;
} // every 2 seconds
// Over 2 minutes?
if (((ms - t1) + (ms - t2)) > (10L*60L*1000L*2L)) {
if (((ms - t1) + (ms - t2)) > (10L * 60L * 1000L * 2L)) {
SERIAL_PROTOCOLLNPGM(MSG_PID_TIMEOUT);
return;
}
if (cycles > ncycles) {
SERIAL_PROTOCOLLNPGM(MSG_PID_AUTOTUNE_FINISHED);
const char *estring = extruder < 0 ? "bed" : "";
const char* estring = extruder < 0 ? "bed" : "";
SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Kp "); SERIAL_PROTOCOLLN(Kp);
SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Ki "); SERIAL_PROTOCOLLN(Ki);
SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Kd "); SERIAL_PROTOCOLLN(Kd);
@ -389,14 +389,13 @@ void setExtruderAutoFanState(int pin, bool state) {
void checkExtruderAutoFans() {
uint8_t fanState = 0;
// which fan pins need to be turned on?
// which fan pins need to be turned on?
#if HAS_AUTO_FAN_0
if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)
if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)
fanState |= 1;
#endif
#if HAS_AUTO_FAN_1
if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE)
{
if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) {
if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
fanState |= 1;
else
@ -404,30 +403,28 @@ void checkExtruderAutoFans() {
}
#endif
#if HAS_AUTO_FAN_2
if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE)
{
if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE) {
if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
fanState |= 1;
else if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN)
else if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN)
fanState |= 2;
else
fanState |= 4;
}
#endif
#if HAS_AUTO_FAN_3
if (current_temperature[3] > EXTRUDER_AUTO_FAN_TEMPERATURE)
{
if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
if (current_temperature[3] > EXTRUDER_AUTO_FAN_TEMPERATURE) {
if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
fanState |= 1;
else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN)
else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN)
fanState |= 2;
else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN)
else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN)
fanState |= 4;
else
fanState |= 8;
}
#endif
// update extruder auto fan states
#if HAS_AUTO_FAN_0
setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0);
@ -454,7 +451,7 @@ void checkExtruderAutoFans() {
//
// Temperature Error Handlers
//
inline void _temp_error(int e, const char *serial_msg, const char *lcd_msg) {
inline void _temp_error(int e, const char* serial_msg, const char* lcd_msg) {
static bool killed = false;
if (IsRunning()) {
SERIAL_ERROR_START;
@ -485,7 +482,7 @@ float get_pid_output(int e) {
#if ENABLED(PIDTEMP)
#if DISABLED(PID_OPENLOOP)
pid_error[e] = target_temperature[e] - current_temperature[e];
dTerm[e] = K2 * PID_PARAM(Kd,e) * (current_temperature[e] - temp_dState[e]) + K1 * dTerm[e];
dTerm[e] = K2 * PID_PARAM(Kd, e) * (current_temperature[e] - temp_dState[e]) + K1 * dTerm[e];
temp_dState[e] = current_temperature[e];
if (pid_error[e] > PID_FUNCTIONAL_RANGE) {
pid_output = BANG_MAX;
@ -500,10 +497,10 @@ float get_pid_output(int e) {
temp_iState[e] = 0.0;
pid_reset[e] = false;
}
pTerm[e] = PID_PARAM(Kp,e) * pid_error[e];
pTerm[e] = PID_PARAM(Kp, e) * pid_error[e];
temp_iState[e] += pid_error[e];
temp_iState[e] = constrain(temp_iState[e], temp_iState_min[e], temp_iState_max[e]);
iTerm[e] = PID_PARAM(Ki,e) * temp_iState[e];
iTerm[e] = PID_PARAM(Ki, e) * temp_iState[e];
pid_output = pTerm[e] + iTerm[e] - dTerm[e];
@ -669,14 +666,14 @@ void manage_heater() {
checkExtruderAutoFans();
next_auto_fan_check_ms = ms + 2500;
}
#endif
#endif
// Control the extruder rate based on the width sensor
#if ENABLED(FILAMENT_SENSOR)
if (filament_sensor) {
meas_shift_index = delay_index1 - meas_delay_cm;
if (meas_shift_index < 0) meas_shift_index += MAX_MEASUREMENT_DELAY + 1; //loop around buffer if needed
// Get the delayed info and add 100 to reconstitute to a percent of
// the nominal filament diameter then square it to get an area
meas_shift_index = constrain(meas_shift_index, 0, MAX_MEASUREMENT_DELAY);
@ -692,7 +689,7 @@ void manage_heater() {
#endif
#if TEMP_SENSOR_BED != 0
#if ENABLED(THERMAL_PROTECTION_BED)
thermal_runaway_protection(&thermal_runaway_bed_state_machine, &thermal_runaway_bed_timer, current_temperature_bed, target_temperature_bed, -1, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS);
#endif
@ -742,7 +739,7 @@ static float analog2temp(int raw, uint8_t e) {
SERIAL_ERRORLNPGM(MSG_INVALID_EXTRUDER_NUM);
kill(PSTR(MSG_KILLED));
return 0.0;
}
}
#if ENABLED(HEATER_0_USES_MAX6675)
if (e == 0) return 0.25 * raw;
@ -751,20 +748,20 @@ static float analog2temp(int raw, uint8_t e) {
if (heater_ttbl_map[e] != NULL) {
float celsius = 0;
uint8_t i;
short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
short(*tt)[][2] = (short(*)[][2])(heater_ttbl_map[e]);
for (i = 1; i < heater_ttbllen_map[e]; i++) {
if (PGM_RD_W((*tt)[i][0]) > raw) {
celsius = PGM_RD_W((*tt)[i-1][1]) +
(raw - PGM_RD_W((*tt)[i-1][0])) *
(float)(PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i-1][1])) /
(float)(PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i-1][0]));
celsius = PGM_RD_W((*tt)[i - 1][1]) +
(raw - PGM_RD_W((*tt)[i - 1][0])) *
(float)(PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i - 1][1])) /
(float)(PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i - 1][0]));
break;
}
}
// Overflow: Set to last value in the table
if (i == heater_ttbllen_map[e]) celsius = PGM_RD_W((*tt)[i-1][1]);
if (i == heater_ttbllen_map[e]) celsius = PGM_RD_W((*tt)[i - 1][1]);
return celsius;
}
@ -780,22 +777,27 @@ static float analog2tempBed(int raw) {
for (i = 1; i < BEDTEMPTABLE_LEN; i++) {
if (PGM_RD_W(BEDTEMPTABLE[i][0]) > raw) {
celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]) +
(raw - PGM_RD_W(BEDTEMPTABLE[i-1][0])) *
(float)(PGM_RD_W(BEDTEMPTABLE[i][1]) - PGM_RD_W(BEDTEMPTABLE[i-1][1])) /
(float)(PGM_RD_W(BEDTEMPTABLE[i][0]) - PGM_RD_W(BEDTEMPTABLE[i-1][0]));
celsius = PGM_RD_W(BEDTEMPTABLE[i - 1][1]) +
(raw - PGM_RD_W(BEDTEMPTABLE[i - 1][0])) *
(float)(PGM_RD_W(BEDTEMPTABLE[i][1]) - PGM_RD_W(BEDTEMPTABLE[i - 1][1])) /
(float)(PGM_RD_W(BEDTEMPTABLE[i][0]) - PGM_RD_W(BEDTEMPTABLE[i - 1][0]));
break;
}
}
// Overflow: Set to last value in the table
if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]);
if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i - 1][1]);
return celsius;
#elif defined BED_USES_AD595
#elif defined(BED_USES_AD595)
return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
#else
return 0;
#endif
}
@ -838,7 +840,7 @@ static void updateTemperaturesFromRawValues() {
if (temp < MEASURED_LOWER_LIMIT) temp = filament_width_nominal; //assume sensor cut out
else if (temp > MEASURED_UPPER_LIMIT) temp = MEASURED_UPPER_LIMIT;
return filament_width_nominal / temp * 100;
}
}
#endif
@ -850,17 +852,17 @@ static void updateTemperaturesFromRawValues() {
void tp_init() {
#if MB(RUMBA) && ((TEMP_SENSOR_0==-1)||(TEMP_SENSOR_1==-1)||(TEMP_SENSOR_2==-1)||(TEMP_SENSOR_BED==-1))
//disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector
MCUCR=BIT(JTD);
MCUCR=BIT(JTD);
MCUCR = BIT(JTD);
MCUCR = BIT(JTD);
#endif
// Finish init of mult extruder arrays
// Finish init of mult extruder arrays
for (int e = 0; e < EXTRUDERS; e++) {
// populate with the first value
// populate with the first value
maxttemp[e] = maxttemp[0];
#if ENABLED(PIDTEMP)
temp_iState_min[e] = 0.0;
temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / PID_PARAM(Ki,e);
temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / PID_PARAM(Ki, e);
#if ENABLED(PID_ADD_EXTRUSION_RATE)
last_position[e] = 0;
#endif
@ -885,7 +887,7 @@ void tp_init() {
#endif
#if HAS_HEATER_BED
SET_OUTPUT(HEATER_BED_PIN);
#endif
#endif
#if HAS_FAN
SET_OUTPUT(FAN_PIN);
#if ENABLED(FAST_PWM_FAN)
@ -906,8 +908,8 @@ void tp_init() {
pinMode(SS_PIN, OUTPUT);
digitalWrite(SS_PIN, HIGH);
#endif
OUT_WRITE(MAX6675_SS,HIGH);
OUT_WRITE(MAX6675_SS, HIGH);
#endif //HEATER_0_USES_MAX6675
@ -958,8 +960,8 @@ void tp_init() {
// Use timer0 for temperature measurement
// Interleave temperature interrupt with millies interrupt
OCR0B = 128;
TIMSK0 |= BIT(OCIE0B);
TIMSK0 |= BIT(OCIE0B);
// Wait for temperature measurement to settle
delay(250);
@ -1021,7 +1023,7 @@ void tp_init() {
}
#endif //BED_MINTEMP
#ifdef BED_MAXTEMP
while(analog2tempBed(bed_maxttemp_raw) > BED_MAXTEMP) {
while (analog2tempBed(bed_maxttemp_raw) > BED_MAXTEMP) {
#if HEATER_BED_RAW_LO_TEMP < HEATER_BED_RAW_HI_TEMP
bed_maxttemp_raw -= OVERSAMPLENR;
#else
@ -1049,9 +1051,9 @@ void tp_init() {
#if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED)
void thermal_runaway_protection(TRState *state, millis_t *timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc) {
void thermal_runaway_protection(TRState* state, millis_t* timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc) {
static float tr_target_temperature[EXTRUDERS+1] = { 0.0 };
static float tr_target_temperature[EXTRUDERS + 1] = { 0.0 };
/*
SERIAL_ECHO_START;
@ -1094,7 +1096,7 @@ void tp_init() {
// If the temperature is over the target (-hysteresis) restart the timer
if (temperature >= tr_target_temperature[heater_index] - hysteresis_degc)
*timer = millis();
// If the timer goes too long without a reset, trigger shutdown
// If the timer goes too long without a reset, trigger shutdown
else if (millis() > *timer + period_seconds * 1000UL)
*state = TRRunaway;
break;
@ -1106,7 +1108,7 @@ void tp_init() {
#endif // THERMAL_PROTECTION_HOTENDS || THERMAL_PROTECTION_BED
void disable_all_heaters() {
for (int i=0; i<EXTRUDERS; i++) setTargetHotend(0, i);
for (int i = 0; i < EXTRUDERS; i++) setTargetHotend(0, i);
setTargetBed(0);
#define DISABLE_HEATER(NR) { \
@ -1153,7 +1155,7 @@ void disable_all_heaters() {
if (ms < next_max6675_ms)
return max6675_temp;
next_max6675_ms = ms + MAX6675_HEAT_INTERVAL;
max6675_temp = 0;
@ -1175,13 +1177,13 @@ void disable_all_heaters() {
// read MSB
SPDR = 0;
for (;(SPSR & BIT(SPIF)) == 0;);
for (; (SPSR & BIT(SPIF)) == 0;);
max6675_temp = SPDR;
max6675_temp <<= 8;
// read LSB
SPDR = 0;
for (;(SPSR & BIT(SPIF)) == 0;);
for (; (SPSR & BIT(SPIF)) == 0;);
max6675_temp |= SPDR;
// disable TT_MAX6675
@ -1285,7 +1287,7 @@ ISR(TIMER0_COMPB_vect) {
#if HAS_FILAMENT_SENSOR
static unsigned long raw_filwidth_value = 0;
#endif
#if DISABLED(SLOW_PWM_HEATERS)
/**
* standard PWM modulation
@ -1320,7 +1322,7 @@ ISR(TIMER0_COMPB_vect) {
#endif
}
if (soft_pwm_0 < pwm_count) { WRITE_HEATER_0(0); }
if (soft_pwm_0 < pwm_count) WRITE_HEATER_0(0);
#if EXTRUDERS > 1
if (soft_pwm_1 < pwm_count) WRITE_HEATER_1(0);
#if EXTRUDERS > 2
@ -1338,11 +1340,12 @@ ISR(TIMER0_COMPB_vect) {
#if ENABLED(FAN_SOFT_PWM)
if (soft_pwm_fan < pwm_count) WRITE_FAN(0);
#endif
pwm_count += BIT(SOFT_PWM_SCALE);
pwm_count &= 0x7f;
#else // SLOW_PWM_HEATERS
/*
* SLOW PWM HEATERS
*
@ -1427,9 +1430,9 @@ ISR(TIMER0_COMPB_vect) {
if ((pwm_count % 64) == 0) {
slow_pwm_count++;
slow_pwm_count &= 0x7f;
// EXTRUDER 0
if (state_timer_heater_0 > 0) state_timer_heater_0--;
if (state_timer_heater_0 > 0) state_timer_heater_0--;
#if EXTRUDERS > 1 // EXTRUDER 1
if (state_timer_heater_1 > 0) state_timer_heater_1--;
#if EXTRUDERS > 2 // EXTRUDER 2
@ -1443,7 +1446,7 @@ ISR(TIMER0_COMPB_vect) {
if (state_timer_heater_BED > 0) state_timer_heater_BED--;
#endif
} // (pwm_count % 64) == 0
#endif // SLOW_PWM_HEATERS
#define SET_ADMUX_ADCSRA(pin) ADMUX = BIT(REFS0) | (pin & 0x07); ADCSRA |= BIT(ADSC)
@ -1454,7 +1457,7 @@ ISR(TIMER0_COMPB_vect) {
#endif
// Prepare or measure a sensor, each one every 12th frame
switch(temp_state) {
switch (temp_state) {
case PrepareTemp_0:
#if HAS_TEMP_0
START_ADC(TEMP_0_PIN);
@ -1536,8 +1539,8 @@ ISR(TIMER0_COMPB_vect) {
#if HAS_FILAMENT_SENSOR
// raw_filwidth_value += ADC; //remove to use an IIR filter approach
if (ADC > 102) { //check that ADC is reading a voltage > 0.5 volts, otherwise don't take in the data.
raw_filwidth_value -= (raw_filwidth_value>>7); //multiply raw_filwidth_value by 127/128
raw_filwidth_value += ((unsigned long)ADC<<7); //add new ADC reading
raw_filwidth_value -= (raw_filwidth_value >> 7); //multiply raw_filwidth_value by 127/128
raw_filwidth_value += ((unsigned long)ADC << 7); //add new ADC reading
}
#endif
temp_state = PrepareTemp_0;
@ -1622,7 +1625,7 @@ ISR(TIMER0_COMPB_vect) {
#if ENABLED(BABYSTEPPING)
for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) {
int curTodo = babystepsTodo[axis]; //get rid of volatile for performance
if (curTodo > 0) {
babystep(axis,/*fwd*/true);
babystepsTodo[axis]--; //fewer to do next time

View File

@ -19,7 +19,7 @@
*/
#ifndef TEMPERATURE_H
#define TEMPERATURE_H
#define TEMPERATURE_H
#include "Marlin.h"
#include "planner.h"
@ -32,16 +32,16 @@ void tp_init(); //initialize the heating
void manage_heater(); //it is critical that this is called periodically.
#if ENABLED(FILAMENT_SENSOR)
// For converting raw Filament Width to milimeters
float analog2widthFil();
// For converting raw Filament Width to an extrusion ratio
int widthFil_to_size_ratio();
// For converting raw Filament Width to milimeters
float analog2widthFil();
// For converting raw Filament Width to an extrusion ratio
int widthFil_to_size_ratio();
#endif
// low level conversion routines
// do not use these routines and variables outside of temperature.cpp
extern int target_temperature[4];
extern int target_temperature[4];
extern float current_temperature[4];
#if ENABLED(SHOW_TEMP_ADC_VALUES)
extern int current_temperature_raw[4];
@ -65,7 +65,7 @@ extern float current_temperature_bed;
#else
extern float Kp, Ki, Kd, Kc; // one param per extruder - saves 20 or 36 bytes of ram (inc array pointer)
#define PID_PARAM(param, e) param // use macro to point directly to value
#endif // PID_PARAMS_PER_EXTRUDER
#endif // PID_PARAMS_PER_EXTRUDER
float scalePID_i(float i);
float scalePID_d(float d);
float unscalePID_i(float i);
@ -74,13 +74,13 @@ extern float current_temperature_bed;
#endif
#if ENABLED(PIDTEMPBED)
extern float bedKp,bedKi,bedKd;
extern float bedKp, bedKi, bedKd;
#endif
#if ENABLED(BABYSTEPPING)
extern volatile int babystepsTodo[3];
#endif
//high level conversion routines, for use outside of temperature.cpp
//inline so that there is no performance decrease.
//deg=degreeCelsius
@ -89,24 +89,24 @@ FORCE_INLINE float degHotend(uint8_t extruder) { return current_temperature[extr
FORCE_INLINE float degBed() { return current_temperature_bed; }
#if ENABLED(SHOW_TEMP_ADC_VALUES)
FORCE_INLINE float rawHotendTemp(uint8_t extruder) { return current_temperature_raw[extruder]; }
FORCE_INLINE float rawBedTemp() { return current_temperature_bed_raw; }
FORCE_INLINE float rawHotendTemp(uint8_t extruder) { return current_temperature_raw[extruder]; }
FORCE_INLINE float rawBedTemp() { return current_temperature_bed_raw; }
#endif
FORCE_INLINE float degTargetHotend(uint8_t extruder) { return target_temperature[extruder]; }
FORCE_INLINE float degTargetBed() { return target_temperature_bed; }
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
void start_watching_heater(int e=0);
void start_watching_heater(int e = 0);
#endif
FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {
FORCE_INLINE void setTargetHotend(const float& celsius, uint8_t extruder) {
target_temperature[extruder] = celsius;
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
start_watching_heater(extruder);
#endif
}
FORCE_INLINE void setTargetBed(const float &celsius) { target_temperature_bed = celsius; }
FORCE_INLINE void setTargetBed(const float& celsius) { target_temperature_bed = celsius; }
FORCE_INLINE bool isHeatingHotend(uint8_t extruder) { return target_temperature[extruder] > current_temperature[extruder]; }
FORCE_INLINE bool isHeatingBed() { return target_temperature_bed > current_temperature_bed; }

File diff suppressed because it is too large Load Diff

View File

@ -28,7 +28,7 @@ int absPreheatFanSpeed;
typedef void (*menuFunc_t)();
uint8_t lcd_status_message_level;
char lcd_status_message[3*LCD_WIDTH+1] = WELCOME_MSG; // worst case is kana with up to 3*LCD_WIDTH+1
char lcd_status_message[3 * LCD_WIDTH + 1] = WELCOME_MSG; // worst case is kana with up to 3*LCD_WIDTH+1
#if ENABLED(DOGLCD)
#include "dogm_lcd_implementation.h"
@ -218,7 +218,7 @@ static void lcd_status_screen();
#if ENABLED(REPRAPWORLD_KEYPAD)
volatile uint8_t buttons_reprapworld_keypad; // to store the keypad shift register values
#endif
#if ENABLED(LCD_HAS_SLOW_BUTTONS)
volatile uint8_t slow_buttons; // Bits of the pressed buttons.
#endif
@ -254,7 +254,7 @@ float raw_Ki, raw_Kd;
/**
* General function to go directly to a menu
*/
static void lcd_goto_menu(menuFunc_t menu, const bool feedback=false, const uint32_t encoder=0) {
static void lcd_goto_menu(menuFunc_t menu, const bool feedback = false, const uint32_t encoder = 0) {
if (currentMenu != menu) {
currentMenu = menu;
#if ENABLED(NEWPANEL)
@ -276,7 +276,7 @@ static void lcd_goto_menu(menuFunc_t menu, const bool feedback=false, const uint
*/
static void lcd_status_screen() {
encoderRateMultiplierEnabled = false;
encoderRateMultiplierEnabled = false;
#if ENABLED(LCD_PROGRESS_BAR)
millis_t ms = millis();
@ -346,7 +346,7 @@ static void lcd_status_screen() {
#if ENABLED(ULTIPANEL_FEEDMULTIPLY)
// Dead zone at 100% feedrate
if ((feedrate_multiplier < 100 && (feedrate_multiplier + int(encoderPosition)) > 100) ||
(feedrate_multiplier > 100 && (feedrate_multiplier + int(encoderPosition)) < 100)) {
(feedrate_multiplier > 100 && (feedrate_multiplier + int(encoderPosition)) < 100)) {
encoderPosition = 0;
feedrate_multiplier = 100;
}
@ -459,7 +459,7 @@ void lcd_set_home_offsets() {
#if ENABLED(BABYSTEPPING)
static void _lcd_babystep(int axis, const char *msg) {
static void _lcd_babystep(int axis, const char* msg) {
if (encoderPosition != 0) {
babystepsTodo[axis] += (int)encoderPosition;
encoderPosition = 0;
@ -800,7 +800,7 @@ inline void line_to_current(AxisEnum axis) {
float move_menu_scale;
static void lcd_move_menu_axis();
static void _lcd_move(const char *name, AxisEnum axis, int min, int max) {
static void _lcd_move(const char* name, AxisEnum axis, int min, int max) {
if (encoderPosition != 0) {
refresh_cmd_timeout();
current_position[axis] += float((int)encoderPosition) * move_menu_scale;
@ -1179,8 +1179,8 @@ static void lcd_control_motion_menu() {
MENU_ITEM_EDIT(bool, MSG_ENDSTOP_ABORT, &abort_on_endstop_hit);
#endif
#if ENABLED(SCARA)
MENU_ITEM_EDIT(float74, MSG_XSCALE, &axis_scaling[X_AXIS],0.5,2);
MENU_ITEM_EDIT(float74, MSG_YSCALE, &axis_scaling[Y_AXIS],0.5,2);
MENU_ITEM_EDIT(float74, MSG_XSCALE, &axis_scaling[X_AXIS], 0.5, 2);
MENU_ITEM_EDIT(float74, MSG_YSCALE, &axis_scaling[Y_AXIS], 0.5, 2);
#endif
END_MENU();
}
@ -1289,7 +1289,7 @@ static void lcd_control_volumetric_menu() {
*
*/
void lcd_sdcard_menu() {
if (lcdDrawUpdate == 0 && LCD_CLICKED == 0) return; // nothing to do (so don't thrash the SD card)
if (lcdDrawUpdate == 0 && LCD_CLICKED == 0) return; // nothing to do (so don't thrash the SD card)
uint16_t fileCnt = card.getnrfilenames();
START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
@ -1323,7 +1323,7 @@ static void lcd_control_volumetric_menu() {
END_MENU();
}
#endif //SDSUPPORT
#endif //SDSUPPORT
/**
*
@ -1336,7 +1336,7 @@ static void lcd_control_volumetric_menu() {
if ((int32_t)encoderPosition < 0) encoderPosition = 0; \
if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \
if (lcdDrawUpdate) \
lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) / scale)); \
lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) / scale)); \
if (isClicked) { \
*((_type*)editValue) = ((_type)((int32_t)encoderPosition + minEditValue)) / scale; \
lcd_goto_menu(prevMenu, prevEncoderPosition); \
@ -1348,10 +1348,10 @@ static void lcd_control_volumetric_menu() {
static void _menu_action_setting_edit_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue) { \
prevMenu = currentMenu; \
prevEncoderPosition = encoderPosition; \
\
\
lcdDrawUpdate = 2; \
currentMenu = menu_edit_ ## _name; \
\
\
editLabel = pstr; \
editValue = ptr; \
minEditValue = minValue * scale; \
@ -1433,14 +1433,14 @@ menu_edit_type(unsigned long, long5, ftostr5, 0.01)
void lcd_quick_feedback() {
lcdDrawUpdate = 2;
next_button_update_ms = millis() + 500;
#if ENABLED(LCD_USE_I2C_BUZZER)
#ifndef LCD_FEEDBACK_FREQUENCY_HZ
#define LCD_FEEDBACK_FREQUENCY_HZ 100
#endif
#ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS (1000/6)
#endif
#endif
lcd.buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ);
#elif PIN_EXISTS(BEEPER)
#ifndef LCD_FEEDBACK_FREQUENCY_HZ
@ -1474,7 +1474,7 @@ static void menu_action_function(menuFunc_t func) { (*func)(); }
char cmd[30];
char* c;
sprintf_P(cmd, PSTR("M23 %s"), filename);
for(c = &cmd[4]; *c; c++) *c = tolower(*c);
for (c = &cmd[4]; *c; c++) *c = tolower(*c);
enqueuecommand(cmd);
enqueuecommands_P(PSTR("M24"));
lcd_return_to_status();
@ -1497,39 +1497,45 @@ static void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr,
/** LCD API **/
void lcd_init() {
lcd_implementation_init();
#if ENABLED(NEWPANEL)
SET_INPUT(BTN_EN1);
SET_INPUT(BTN_EN2);
WRITE(BTN_EN1,HIGH);
WRITE(BTN_EN2,HIGH);
#if BTN_ENC > 0
SET_INPUT(BTN_ENC);
WRITE(BTN_ENC,HIGH);
#endif
#if ENABLED(REPRAPWORLD_KEYPAD)
pinMode(SHIFT_CLK,OUTPUT);
pinMode(SHIFT_LD,OUTPUT);
pinMode(SHIFT_OUT,INPUT);
WRITE(SHIFT_OUT,HIGH);
WRITE(SHIFT_LD,HIGH);
#endif
#else // Not NEWPANEL
#if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register
pinMode (SR_DATA_PIN, OUTPUT);
pinMode (SR_CLK_PIN, OUTPUT);
#elif defined(SHIFT_CLK)
pinMode(SHIFT_CLK,OUTPUT);
pinMode(SHIFT_LD,OUTPUT);
pinMode(SHIFT_EN,OUTPUT);
pinMode(SHIFT_OUT,INPUT);
WRITE(SHIFT_OUT,HIGH);
WRITE(SHIFT_LD,HIGH);
WRITE(SHIFT_EN,LOW);
#endif // SR_LCD_2W_NL
#endif//!NEWPANEL
WRITE(BTN_EN1, HIGH);
WRITE(BTN_EN2, HIGH);
#if BTN_ENC > 0
SET_INPUT(BTN_ENC);
WRITE(BTN_ENC, HIGH);
#endif
#if ENABLED(REPRAPWORLD_KEYPAD)
pinMode(SHIFT_CLK, OUTPUT);
pinMode(SHIFT_LD, OUTPUT);
pinMode(SHIFT_OUT, INPUT);
WRITE(SHIFT_OUT, HIGH);
WRITE(SHIFT_LD, HIGH);
#endif
#else // Not NEWPANEL
#if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register
pinMode(SR_DATA_PIN, OUTPUT);
pinMode(SR_CLK_PIN, OUTPUT);
#elif defined(SHIFT_CLK)
pinMode(SHIFT_CLK, OUTPUT);
pinMode(SHIFT_LD, OUTPUT);
pinMode(SHIFT_EN, OUTPUT);
pinMode(SHIFT_OUT, INPUT);
WRITE(SHIFT_OUT, HIGH);
WRITE(SHIFT_LD, HIGH);
WRITE(SHIFT_EN, LOW);
#endif // SR_LCD_2W_NL
#endif//!NEWPANEL
#if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT)
pinMode(SD_DETECT_PIN, INPUT);
@ -1548,7 +1554,7 @@ void lcd_init() {
#endif
}
int lcd_strlen(char *s) {
int lcd_strlen(char* s) {
int i = 0, j = 0;
while (s[i]) {
if ((s[i] & 0xc0) != 0x80) j++;
@ -1557,7 +1563,7 @@ int lcd_strlen(char *s) {
return j;
}
int lcd_strlen_P(const char *s) {
int lcd_strlen_P(const char* s) {
int j = 0;
while (pgm_read_byte(s)) {
if ((pgm_read_byte(s) & 0xc0) != 0x80) j++;
@ -1614,7 +1620,7 @@ void lcd_update() {
}
#endif //SDSUPPORT && SD_DETECT_PIN
millis_t ms = millis();
if (ms > next_lcd_update_ms) {
@ -1683,18 +1689,18 @@ void lcd_update() {
}
}
#if ENABLED(DOGLCD) // Changes due to different driver architecture of the DOGM display
if (lcdDrawUpdate) {
blink++; // Variable for fan animation and alive dot
u8g.firstPage();
do {
lcd_setFont(FONT_MENU);
u8g.setPrintPos(125, 0);
if (blink % 2) u8g.setColorIndex(1); else u8g.setColorIndex(0); // Set color for the alive dot
u8g.drawPixel(127, 63); // draw alive dot
u8g.setColorIndex(1); // black on white
(*currentMenu)();
} while( u8g.nextPage() );
}
if (lcdDrawUpdate) {
blink++; // Variable for fan animation and alive dot
u8g.firstPage();
do {
lcd_setFont(FONT_MENU);
u8g.setPrintPos(125, 0);
if (blink % 2) u8g.setColorIndex(1); else u8g.setColorIndex(0); // Set color for the alive dot
u8g.drawPixel(127, 63); // draw alive dot
u8g.setColorIndex(1); // black on white
(*currentMenu)();
} while (u8g.nextPage());
}
#else
if (lcdDrawUpdate)
(*currentMenu)();
@ -1749,7 +1755,7 @@ void lcd_finishstatus(bool persist=false) {
void dontExpireStatus() { expire_status_ms = 0; }
#endif
void set_utf_strlen(char *s, uint8_t n) {
void set_utf_strlen(char* s, uint8_t n) {
uint8_t i = 0, j = 0;
while (s[i] && (j < n)) {
if ((s[i] & 0xc0u) != 0x80u) j++;
@ -1763,14 +1769,14 @@ bool lcd_hasstatus() { return (lcd_status_message[0] != '\0'); }
void lcd_setstatus(const char* message, bool persist) {
if (lcd_status_message_level > 0) return;
strncpy(lcd_status_message, message, 3*LCD_WIDTH);
strncpy(lcd_status_message, message, 3 * LCD_WIDTH);
set_utf_strlen(lcd_status_message, LCD_WIDTH);
lcd_finishstatus(persist);
}
void lcd_setstatuspgm(const char* message, uint8_t level) {
if (level >= lcd_status_message_level) {
strncpy_P(lcd_status_message, message, 3*LCD_WIDTH);
strncpy_P(lcd_status_message, message, 3 * LCD_WIDTH);
set_utf_strlen(lcd_status_message, LCD_WIDTH);
lcd_status_message_level = level;
lcd_finishstatus(level > 0);
@ -1825,23 +1831,23 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; }
#endif
#if ENABLED(REPRAPWORLD_KEYPAD)
// for the reprapworld_keypad
uint8_t newbutton_reprapworld_keypad=0;
uint8_t newbutton_reprapworld_keypad = 0;
WRITE(SHIFT_LD, LOW);
WRITE(SHIFT_LD, HIGH);
for(int8_t i = 0; i < 8; i++) {
for (int8_t i = 0; i < 8; i++) {
newbutton_reprapworld_keypad >>= 1;
if (READ(SHIFT_OUT)) newbutton_reprapworld_keypad |= BIT(7);
WRITE(SHIFT_CLK, HIGH);
WRITE(SHIFT_CLK, LOW);
}
buttons_reprapworld_keypad=~newbutton_reprapworld_keypad; //invert it, because a pressed switch produces a logical 0
buttons_reprapworld_keypad = ~newbutton_reprapworld_keypad; //invert it, because a pressed switch produces a logical 0
#endif
#else //read it from the shift register
uint8_t newbutton = 0;
WRITE(SHIFT_LD, LOW);
WRITE(SHIFT_LD, HIGH);
unsigned char tmp_buttons = 0;
for(int8_t i=0; i<8; i++) {
for (int8_t i = 0; i < 8; i++) {
newbutton >>= 1;
if (READ(SHIFT_OUT)) newbutton |= BIT(7);
WRITE(SHIFT_CLK, HIGH);
@ -1851,26 +1857,26 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; }
#endif //!NEWPANEL
//manage encoder rotation
uint8_t enc=0;
uint8_t enc = 0;
if (buttons & EN_A) enc |= B01;
if (buttons & EN_B) enc |= B10;
if (enc != lastEncoderBits) {
switch(enc) {
switch (enc) {
case encrot0:
if (lastEncoderBits==encrot3) encoderDiff++;
else if (lastEncoderBits==encrot1) encoderDiff--;
if (lastEncoderBits == encrot3) encoderDiff++;
else if (lastEncoderBits == encrot1) encoderDiff--;
break;
case encrot1:
if (lastEncoderBits==encrot0) encoderDiff++;
else if (lastEncoderBits==encrot2) encoderDiff--;
if (lastEncoderBits == encrot0) encoderDiff++;
else if (lastEncoderBits == encrot2) encoderDiff--;
break;
case encrot2:
if (lastEncoderBits==encrot1) encoderDiff++;
else if (lastEncoderBits==encrot3) encoderDiff--;
if (lastEncoderBits == encrot1) encoderDiff++;
else if (lastEncoderBits == encrot3) encoderDiff--;
break;
case encrot3:
if (lastEncoderBits==encrot2) encoderDiff++;
else if (lastEncoderBits==encrot0) encoderDiff--;
if (lastEncoderBits == encrot2) encoderDiff++;
else if (lastEncoderBits == encrot0) encoderDiff--;
break;
}
}
@ -1896,12 +1902,12 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; }
char conv[8];
// Convert float to string with +123.4 format
char *ftostr3(const float &x) {
char* ftostr3(const float& x) {
return itostr3((int)x);
}
// Convert int to string with 12 format
char *itostr2(const uint8_t &x) {
char* itostr2(const uint8_t& x) {
//sprintf(conv,"%5.1f",x);
int xx = x;
conv[0] = (xx / 10) % 10 + '0';
@ -1911,7 +1917,7 @@ char *itostr2(const uint8_t &x) {
}
// Convert float to string with +123.4 format
char *ftostr31(const float &x) {
char* ftostr31(const float& x) {
int xx = abs(x * 10);
conv[0] = (x >= 0) ? '+' : '-';
conv[1] = (xx / 1000) % 10 + '0';
@ -1924,7 +1930,7 @@ char *ftostr31(const float &x) {
}
// Convert float to string with 123.4 format, dropping sign
char *ftostr31ns(const float &x) {
char* ftostr31ns(const float& x) {
int xx = abs(x * 10);
conv[0] = (xx / 1000) % 10 + '0';
conv[1] = (xx / 100) % 10 + '0';
@ -1936,7 +1942,7 @@ char *ftostr31ns(const float &x) {
}
// Convert float to string with 123.4 format
char *ftostr32(const float &x) {
char* ftostr32(const float& x) {
long xx = abs(x * 100);
conv[0] = x >= 0 ? (xx / 10000) % 10 + '0' : '-';
conv[1] = (xx / 1000) % 10 + '0';
@ -1949,39 +1955,37 @@ char *ftostr32(const float &x) {
}
// Convert float to string with 1.234 format
char *ftostr43(const float &x) {
long xx = x * 1000;
if (xx >= 0)
conv[0] = (xx / 1000) % 10 + '0';
else
conv[0] = '-';
xx = abs(xx);
conv[1] = '.';
conv[2] = (xx / 100) % 10 + '0';
conv[3] = (xx / 10) % 10 + '0';
conv[4] = (xx) % 10 + '0';
conv[5] = 0;
return conv;
char* ftostr43(const float& x) {
long xx = x * 1000;
if (xx >= 0)
conv[0] = (xx / 1000) % 10 + '0';
else
conv[0] = '-';
xx = abs(xx);
conv[1] = '.';
conv[2] = (xx / 100) % 10 + '0';
conv[3] = (xx / 10) % 10 + '0';
conv[4] = (xx) % 10 + '0';
conv[5] = 0;
return conv;
}
// Convert 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;
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;
}
// Convert float to space-padded string with -_23.4_ format
char *ftostr32sp(const float &x) {
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;
@ -2024,7 +2028,7 @@ char *ftostr32sp(const float &x) {
}
// Convert int to lj string with +123.0 format
char *itostr31(const int &x) {
char* itostr31(const int& x) {
conv[0] = x >= 0 ? '+' : '-';
int xx = abs(x);
conv[1] = (xx / 100) % 10 + '0';
@ -2037,11 +2041,11 @@ char *itostr31(const int &x) {
}
// Convert int to rj string with 123 or -12 format
char *itostr3(const int &x) {
char* itostr3(const int& x) {
int xx = x;
if (xx < 0) {
conv[0] = '-';
xx = -xx;
conv[0] = '-';
xx = -xx;
}
else
conv[0] = xx >= 100 ? (xx / 100) % 10 + '0' : ' ';
@ -2053,7 +2057,7 @@ char *itostr3(const int &x) {
}
// Convert int to lj string with 123 format
char *itostr3left(const int &xx) {
char* itostr3left(const int& xx) {
if (xx >= 100) {
conv[0] = (xx / 100) % 10 + '0';
conv[1] = (xx / 10) % 10 + '0';
@ -2073,7 +2077,7 @@ char *itostr3left(const int &xx) {
}
// Convert int to rj string with 1234 format
char *itostr4(const int &xx) {
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' : ' ';
@ -2083,7 +2087,7 @@ char *itostr4(const int &xx) {
}
// Convert float to rj string with 12345 format
char *ftostr5(const float &x) {
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' : ' ';
@ -2095,7 +2099,7 @@ char *ftostr5(const float &x) {
}
// Convert float to string with +1234.5 format
char *ftostr51(const float &x) {
char* ftostr51(const float& x) {
long xx = abs(x * 10);
conv[0] = (x >= 0) ? '+' : '-';
conv[1] = (xx / 10000) % 10 + '0';
@ -2109,7 +2113,7 @@ char *ftostr51(const float &x) {
}
// Convert float to string with +123.45 format
char *ftostr52(const float &x) {
char* ftostr52(const float& x) {
conv[0] = (x >= 0) ? '+' : '-';
long xx = abs(x * 100);
conv[1] = (xx / 10000) % 10 + '0';
@ -2151,7 +2155,7 @@ char *ftostr52(const float &x) {
if (iy & 1) ix = (MESH_NUM_X_POINTS - 1) - ix; // Zig zag
mbl.set_z(ix, iy, current_position[Z_AXIS]);
_lcd_level_bed_position++;
if (_lcd_level_bed_position == MESH_NUM_X_POINTS*MESH_NUM_Y_POINTS) {
if (_lcd_level_bed_position == MESH_NUM_X_POINTS * MESH_NUM_Y_POINTS) {
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
line_to_current(Z_AXIS);
mbl.active = 1;

View File

@ -5,8 +5,8 @@
#if ENABLED(ULTRA_LCD)
#include "buzzer.h"
int lcd_strlen(char *s);
int lcd_strlen_P(const char *s);
int lcd_strlen(char* s);
int lcd_strlen_P(const char* s);
void lcd_update();
void lcd_init();
bool lcd_hasstatus();
@ -53,7 +53,7 @@
extern int absPreheatFanSpeed;
extern bool cancel_heatup;
#if ENABLED(FILAMENT_LCD_DISPLAY)
extern millis_t previous_lcd_status_ms;
#endif
@ -69,23 +69,23 @@
#define LCD_CLICKED (buttons&EN_C)
#if ENABLED(REPRAPWORLD_KEYPAD)
#define EN_REPRAPWORLD_KEYPAD_F3 (BIT(BLEN_REPRAPWORLD_KEYPAD_F3))
#define EN_REPRAPWORLD_KEYPAD_F2 (BIT(BLEN_REPRAPWORLD_KEYPAD_F2))
#define EN_REPRAPWORLD_KEYPAD_F1 (BIT(BLEN_REPRAPWORLD_KEYPAD_F1))
#define EN_REPRAPWORLD_KEYPAD_UP (BIT(BLEN_REPRAPWORLD_KEYPAD_UP))
#define EN_REPRAPWORLD_KEYPAD_RIGHT (BIT(BLEN_REPRAPWORLD_KEYPAD_RIGHT))
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (BIT(BLEN_REPRAPWORLD_KEYPAD_MIDDLE))
#define EN_REPRAPWORLD_KEYPAD_DOWN (BIT(BLEN_REPRAPWORLD_KEYPAD_DOWN))
#define EN_REPRAPWORLD_KEYPAD_LEFT (BIT(BLEN_REPRAPWORLD_KEYPAD_LEFT))
#define EN_REPRAPWORLD_KEYPAD_F3 (BIT(BLEN_REPRAPWORLD_KEYPAD_F3))
#define EN_REPRAPWORLD_KEYPAD_F2 (BIT(BLEN_REPRAPWORLD_KEYPAD_F2))
#define EN_REPRAPWORLD_KEYPAD_F1 (BIT(BLEN_REPRAPWORLD_KEYPAD_F1))
#define EN_REPRAPWORLD_KEYPAD_UP (BIT(BLEN_REPRAPWORLD_KEYPAD_UP))
#define EN_REPRAPWORLD_KEYPAD_RIGHT (BIT(BLEN_REPRAPWORLD_KEYPAD_RIGHT))
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (BIT(BLEN_REPRAPWORLD_KEYPAD_MIDDLE))
#define EN_REPRAPWORLD_KEYPAD_DOWN (BIT(BLEN_REPRAPWORLD_KEYPAD_DOWN))
#define EN_REPRAPWORLD_KEYPAD_LEFT (BIT(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)
#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
@ -97,7 +97,7 @@
#define B_ST BIT(BL_ST)
#define EN_B BIT(BLEN_B)
#define EN_A BIT(BLEN_A)
#define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST))
#endif//NEWPANEL
@ -116,21 +116,21 @@
#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* 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 *ftostr43(const float &x);
char *ftostr12ns(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);
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* ftostr43(const float& x);
char* ftostr12ns(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 //ULTRALCD_H

View File

@ -20,59 +20,59 @@
// via a shift/i2c register.
#if ENABLED(ULTIPANEL)
// All UltiPanels might have an encoder - so this is always be mapped onto first two bits
#define BLEN_B 1
#define BLEN_A 0
// All UltiPanels might have an encoder - so this is always be mapped onto first two bits
#define BLEN_B 1
#define BLEN_A 0
#define EN_B BIT(BLEN_B) // The two encoder pins are connected through BTN_EN1 and BTN_EN2
#define EN_A BIT(BLEN_A)
#if defined(BTN_ENC) && BTN_ENC > -1
// encoder click is directly connected
#define BLEN_C 2
#define EN_C BIT(BLEN_C)
#endif
//
// Setup other button mappings of each panel
//
#if ENABLED(LCD_I2C_VIKI)
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
// button and encoder bit positions within 'buttons'
#define B_LE (BUTTON_LEFT<<B_I2C_BTN_OFFSET) // The remaining normalized buttons are all read via I2C
#define B_UP (BUTTON_UP<<B_I2C_BTN_OFFSET)
#define B_MI (BUTTON_SELECT<<B_I2C_BTN_OFFSET)
#define B_DW (BUTTON_DOWN<<B_I2C_BTN_OFFSET)
#define B_RI (BUTTON_RIGHT<<B_I2C_BTN_OFFSET)
#define EN_B BIT(BLEN_B) // The two encoder pins are connected through BTN_EN1 and BTN_EN2
#define EN_A BIT(BLEN_A)
#if defined(BTN_ENC) && BTN_ENC > -1
// the pause/stop/restart button is connected to BTN_ENC when used
#define B_ST (EN_C) // Map the pause/stop/resume button into its normalized functional name
#define LCD_CLICKED (buttons&(B_MI|B_RI|B_ST)) // pause/stop button also acts as click until we implement proper pause/stop.
#else
#define LCD_CLICKED (buttons&(B_MI|B_RI))
// encoder click is directly connected
#define BLEN_C 2
#define EN_C BIT(BLEN_C)
#endif
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
#define LCD_HAS_SLOW_BUTTONS
#elif ENABLED(LCD_I2C_PANELOLU2)
// encoder click can be read through I2C if not directly connected
#if BTN_ENC <= 0
//
// Setup other button mappings of each panel
//
#if ENABLED(LCD_I2C_VIKI)
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
#define B_MI (PANELOLU2_ENCODER_C<<B_I2C_BTN_OFFSET) // requires LiquidTWI2 library v1.2.3 or later
// button and encoder bit positions within 'buttons'
#define B_LE (BUTTON_LEFT<<B_I2C_BTN_OFFSET) // The remaining normalized buttons are all read via I2C
#define B_UP (BUTTON_UP<<B_I2C_BTN_OFFSET)
#define B_MI (BUTTON_SELECT<<B_I2C_BTN_OFFSET)
#define B_DW (BUTTON_DOWN<<B_I2C_BTN_OFFSET)
#define B_RI (BUTTON_RIGHT<<B_I2C_BTN_OFFSET)
#define LCD_CLICKED (buttons&B_MI)
#if defined(BTN_ENC) && BTN_ENC > -1
// the pause/stop/restart button is connected to BTN_ENC when used
#define B_ST (EN_C) // Map the pause/stop/resume button into its normalized functional name
#define LCD_CLICKED (buttons&(B_MI|B_RI|B_ST)) // pause/stop button also acts as click until we implement proper pause/stop.
#else
#define LCD_CLICKED (buttons&(B_MI|B_RI))
#endif
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
#define LCD_HAS_SLOW_BUTTONS
#else
#define LCD_CLICKED (buttons&EN_C)
#endif
#elif ENABLED(REPRAPWORLD_KEYPAD)
#elif ENABLED(LCD_I2C_PANELOLU2)
// encoder click can be read through I2C if not directly connected
#if BTN_ENC <= 0
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
#define B_MI (PANELOLU2_ENCODER_C<<B_I2C_BTN_OFFSET) // requires LiquidTWI2 library v1.2.3 or later
#define LCD_CLICKED (buttons&B_MI)
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
#define LCD_HAS_SLOW_BUTTONS
#else
#define LCD_CLICKED (buttons&EN_C)
#endif
#elif ENABLED(REPRAPWORLD_KEYPAD)
// define register bit values, don't change it
#define BLEN_REPRAPWORLD_KEYPAD_F3 0
#define BLEN_REPRAPWORLD_KEYPAD_F2 1
@ -82,7 +82,7 @@
#define BLEN_REPRAPWORLD_KEYPAD_MIDDLE 5
#define BLEN_REPRAPWORLD_KEYPAD_DOWN 3
#define BLEN_REPRAPWORLD_KEYPAD_LEFT 7
#define REPRAPWORLD_BTN_OFFSET 0 // bit offset into buttons for shift register values
#define EN_REPRAPWORLD_KEYPAD_F3 BIT((BLEN_REPRAPWORLD_KEYPAD_F3+REPRAPWORLD_BTN_OFFSET))
@ -99,29 +99,29 @@
//#define REPRAPWORLD_KEYPAD_MOVE_Y_UP (buttons&EN_REPRAPWORLD_KEYPAD_UP)
//#define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons&EN_REPRAPWORLD_KEYPAD_MIDDLE)
#elif ENABLED(NEWPANEL)
#define LCD_CLICKED (buttons&EN_C)
#elif ENABLED(NEWPANEL)
#define LCD_CLICKED (buttons&EN_C)
#else // old style ULTIPANEL
//bits in the shift register that carry the buttons for:
// left up center down right red(stop)
#define BL_LE 7
#define BL_UP 6
#define BL_MI 5
#define BL_DW 4
#define BL_RI 3
#define BL_ST 2
#else // old style ULTIPANEL
//bits in the shift register that carry the buttons for:
// left up center down right red(stop)
#define BL_LE 7
#define BL_UP 6
#define BL_MI 5
#define BL_DW 4
#define BL_RI 3
#define BL_ST 2
//automatic, do not change
#define B_LE BIT(BL_LE)
#define B_UP BIT(BL_UP)
#define B_MI BIT(BL_MI)
#define B_DW BIT(BL_DW)
#define B_RI BIT(BL_RI)
#define B_ST BIT(BL_ST)
#define LCD_CLICKED (buttons&(B_MI|B_ST))
#endif
//automatic, do not change
#define B_LE BIT(BL_LE)
#define B_UP BIT(BL_UP)
#define B_MI BIT(BL_MI)
#define B_DW BIT(BL_DW)
#define B_RI BIT(BL_RI)
#define B_ST BIT(BL_ST)
#define LCD_CLICKED (buttons&(B_MI|B_ST))
#endif
#endif //ULTIPANEL
@ -137,12 +137,12 @@
#define LCD_I2C_PIN_D5 5
#define LCD_I2C_PIN_D6 6
#define LCD_I2C_PIN_D7 7
#include <Wire.h>
#include <LCD.h>
#include <LiquidCrystal_I2C.h>
#define LCD_CLASS LiquidCrystal_I2C
LCD_CLASS lcd(LCD_I2C_ADDRESS,LCD_I2C_PIN_EN,LCD_I2C_PIN_RW,LCD_I2C_PIN_RS,LCD_I2C_PIN_D4,LCD_I2C_PIN_D5,LCD_I2C_PIN_D6,LCD_I2C_PIN_D7);
LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_I2C_PIN_EN, LCD_I2C_PIN_RW, LCD_I2C_PIN_RS, LCD_I2C_PIN_D4, LCD_I2C_PIN_D5, LCD_I2C_PIN_D6, LCD_I2C_PIN_D7);
#elif ENABLED(LCD_I2C_TYPE_MCP23017)
//for the LED indicators (which maybe mapped to different things in lcd_implementation_update_indicators())
@ -172,9 +172,9 @@
#endif
#elif ENABLED(LCD_I2C_TYPE_PCA8574)
#include <LiquidCrystal_I2C.h>
#define LCD_CLASS LiquidCrystal_I2C
LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_WIDTH, LCD_HEIGHT);
#include <LiquidCrystal_I2C.h>
#define LCD_CLASS LiquidCrystal_I2C
LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_WIDTH, LCD_HEIGHT);
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
@ -188,7 +188,7 @@
// Standard directly connected LCD implementations
#include <LiquidCrystal.h>
#define LCD_CLASS LiquidCrystal
LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5, LCD_PINS_D6, LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
#endif
#include "utf_mapper.h"
@ -208,7 +208,7 @@
static void lcd_set_custom_characters(
#if ENABLED(LCD_PROGRESS_BAR)
bool progress_bar_set=true
bool progress_bar_set = true
#endif
) {
byte bedTemp[8] = {
@ -331,7 +331,7 @@ static void lcd_set_custom_characters(
lcd.createChar(LCD_STR_CLOCK[0], clock);
if (progress_bar_set) {
// Progress bar characters for info screen
for (int i=3; i--;) lcd.createChar(LCD_STR_PROGRESS[i], progress[i]);
for (int i = 3; i--;) lcd.createChar(LCD_STR_PROGRESS[i], progress[i]);
}
else {
// Custom characters for submenus
@ -354,7 +354,7 @@ static void lcd_set_custom_characters(
static void lcd_implementation_init(
#if ENABLED(LCD_PROGRESS_BAR)
bool progress_bar_set=true
bool progress_bar_set = true
#endif
) {
@ -416,16 +416,16 @@ unsigned lcd_print(char c) { return charset_mapper(c); }
#if ENABLED(SHOW_BOOTSCREEN)
void lcd_erase_line(int line) {
lcd.setCursor(0, 3);
for (int i=0; i < LCD_WIDTH; i++)
for (int i = 0; i < LCD_WIDTH; i++)
lcd_print(' ');
}
// scrol the PSTR'text' in a 'len' wide field for 'time' milliseconds at position col,line
void lcd_scroll(int col, int line, const char * text, int len, int time) {
char tmp[LCD_WIDTH+1] = {0};
// Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line
void lcd_scroll(int col, int line, const char* text, int len, int time) {
char tmp[LCD_WIDTH + 1] = {0};
int n = max(lcd_strlen_P(text) - len, 0);
for (int i = 0; i <= n; i++) {
strncpy_P(tmp, text+i, min(len, LCD_WIDTH));
strncpy_P(tmp, text + i, min(len, LCD_WIDTH));
lcd.setCursor(col, line);
lcd_print(tmp);
delay(time / max(n, 1));
@ -667,10 +667,10 @@ static void lcd_implementation_status_screen() {
lcd.setCursor(LCD_WIDTH - 6, 2);
lcd.print(LCD_STR_CLOCK[0]);
if (print_job_start_ms != 0) {
uint16_t time = millis()/60000 - print_job_start_ms/60000;
lcd.print(itostr2(time/60));
uint16_t time = millis() / 60000 - print_job_start_ms / 60000;
lcd.print(itostr2(time / 60));
lcd.print(':');
lcd.print(itostr2(time%60));
lcd.print(itostr2(time % 60));
}
else {
lcd_printPGM(PSTR("--:--"));
@ -693,13 +693,13 @@ static void lcd_implementation_status_screen() {
if (millis() >= progress_bar_ms + PROGRESS_BAR_MSG_TIME || !lcd_status_message[0]) {
int tix = (int)(card.percentDone() * LCD_WIDTH * 3) / 100,
cel = tix / 3, rem = tix % 3, i = LCD_WIDTH;
char msg[LCD_WIDTH+1], b = ' ';
char msg[LCD_WIDTH + 1], b = ' ';
msg[i] = '\0';
while (i--) {
if (i == cel - 1)
b = LCD_STR_PROGRESS[2];
else if (i == cel && rem != 0)
b = LCD_STR_PROGRESS[rem-1];
b = LCD_STR_PROGRESS[rem - 1];
msg[i] = b;
}
lcd.print(msg);
@ -715,7 +715,7 @@ static void lcd_implementation_status_screen() {
lcd_printPGM(PSTR("Dia "));
lcd.print(ftostr12ns(filament_width_meas));
lcd_printPGM(PSTR(" V"));
lcd.print(itostr3(100.0*volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM]));
lcd.print(itostr3(100.0 * volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM]));
lcd.print('%');
return;
}
@ -734,7 +734,7 @@ static void lcd_implementation_drawmenu_generic(bool sel, uint8_t row, const cha
n -= lcd_print(c);
pstr++;
}
while(n--) lcd.print(' ');
while (n--) lcd.print(' ');
lcd.print(post_char);
}
@ -859,10 +859,10 @@ void lcd_implementation_drawedit(const char* pstr, char* value) {
uint8_t slow_buttons;
// Reading these buttons this is likely to be too slow to call inside interrupt context
// so they are called during normal lcd_update
slow_buttons = lcd.readButtons() << B_I2C_BTN_OFFSET;
slow_buttons = lcd.readButtons() << B_I2C_BTN_OFFSET;
#if ENABLED(LCD_I2C_VIKI)
if ((slow_buttons & (B_MI|B_RI)) && millis() < next_button_update_ms) // LCD clicked
slow_buttons &= ~(B_MI|B_RI); // Disable LCD clicked buttons if screen is updated
if ((slow_buttons & (B_MI | B_RI)) && millis() < next_button_update_ms) // LCD clicked
slow_buttons &= ~(B_MI | B_RI); // Disable LCD clicked buttons if screen is updated
#endif
return slow_buttons;
#endif

View File

@ -21,20 +21,18 @@
#include <U8glib.h>
static void ST7920_SWSPI_SND_8BIT(uint8_t val)
{
static void ST7920_SWSPI_SND_8BIT(uint8_t val) {
uint8_t i;
for( i=0; i<8; i++ )
{
for (i = 0; i < 8; i++) {
WRITE(ST7920_CLK_PIN,0);
#if F_CPU == 20000000
__asm__("nop\n\t");
__asm__("nop\n\t");
#endif
WRITE(ST7920_DAT_PIN,val&0x80);
WRITE(ST7920_DAT_PIN,val&0x80);
val<<=1;
WRITE(ST7920_CLK_PIN,1);
#if F_CPU == 20000000
__asm__("nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t");
#endif
}
}
@ -46,69 +44,59 @@ static void ST7920_SWSPI_SND_8BIT(uint8_t val)
#define ST7920_WRITE_BYTE(a) {ST7920_SWSPI_SND_8BIT((uint8_t)((a)&0xf0u));ST7920_SWSPI_SND_8BIT((uint8_t)((a)<<4u));u8g_10MicroDelay();}
#define ST7920_WRITE_BYTES(p,l) {uint8_t i;for(i=0;i<l;i++){ST7920_SWSPI_SND_8BIT(*p&0xf0);ST7920_SWSPI_SND_8BIT(*p<<4);p++;}u8g_10MicroDelay();}
uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg)
{
uint8_t i,y;
switch(msg)
{
case U8G_DEV_MSG_INIT:
{
OUT_WRITE(ST7920_CS_PIN,LOW);
OUT_WRITE(ST7920_DAT_PIN,LOW);
OUT_WRITE(ST7920_CLK_PIN,HIGH);
uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) {
uint8_t i, y;
switch (msg) {
case U8G_DEV_MSG_INIT: {
OUT_WRITE(ST7920_CS_PIN, LOW);
OUT_WRITE(ST7920_DAT_PIN, LOW);
OUT_WRITE(ST7920_CLK_PIN, HIGH);
ST7920_CS();
u8g_Delay(120); //initial delay for boot up
ST7920_CS();
u8g_Delay(120); //initial delay for boot up
ST7920_SET_CMD();
ST7920_WRITE_BYTE(0x08); //display off, cursor+blink off
ST7920_WRITE_BYTE(0x01); //clear CGRAM ram
u8g_Delay(15); //delay for CGRAM clear
ST7920_WRITE_BYTE(0x3E); //extended mode + GDRAM active
for (y = 0; y < LCD_PIXEL_HEIGHT / 2; y++) { //clear GDRAM
ST7920_WRITE_BYTE(0x80 | y); //set y
ST7920_WRITE_BYTE(0x80); //set x = 0
ST7920_SET_DAT();
for (i = 0; i < 2 * LCD_PIXEL_WIDTH / 8; i++) //2x width clears both segments
ST7920_WRITE_BYTE(0);
ST7920_SET_CMD();
ST7920_WRITE_BYTE(0x08); //display off, cursor+blink off
ST7920_WRITE_BYTE(0x01); //clear CGRAM ram
u8g_Delay(15); //delay for CGRAM clear
ST7920_WRITE_BYTE(0x3E); //extended mode + GDRAM active
for(y=0;y<LCD_PIXEL_HEIGHT/2;y++) //clear GDRAM
{
ST7920_WRITE_BYTE(0x80|y); //set y
ST7920_WRITE_BYTE(0x80); //set x = 0
ST7920_SET_DAT();
for(i=0;i<2*LCD_PIXEL_WIDTH/8;i++) //2x width clears both segments
ST7920_WRITE_BYTE(0);
ST7920_SET_CMD();
}
ST7920_WRITE_BYTE(0x0C); //display on, cursor+blink off
ST7920_NCS();
}
break;
ST7920_WRITE_BYTE(0x0C); //display on, cursor+blink off
ST7920_NCS();
}
break;
case U8G_DEV_MSG_STOP:
break;
case U8G_DEV_MSG_PAGE_NEXT:
{
uint8_t *ptr;
u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem);
y = pb->p.page_y0;
ptr = (uint8_t*)pb->buf;
case U8G_DEV_MSG_PAGE_NEXT: {
uint8_t* ptr;
u8g_pb_t* pb = (u8g_pb_t*)(dev->dev_mem);
y = pb->p.page_y0;
ptr = (uint8_t*)pb->buf;
ST7920_CS();
for( i = 0; i < PAGE_HEIGHT; i ++ )
{
ST7920_SET_CMD();
if ( y < 32 )
{
ST7920_WRITE_BYTE(0x80 | y); //y
ST7920_WRITE_BYTE(0x80); //x=0
}
else
{
ST7920_WRITE_BYTE(0x80 | (y-32)); //y
ST7920_WRITE_BYTE(0x80 | 8); //x=64
}
ST7920_SET_DAT();
ST7920_WRITE_BYTES(ptr,LCD_PIXEL_WIDTH/8); //ptr is incremented inside of macro
y++;
ST7920_CS();
for (i = 0; i < PAGE_HEIGHT; i ++) {
ST7920_SET_CMD();
if (y < 32) {
ST7920_WRITE_BYTE(0x80 | y); //y
ST7920_WRITE_BYTE(0x80); //x=0
}
ST7920_NCS();
else {
ST7920_WRITE_BYTE(0x80 | (y - 32)); //y
ST7920_WRITE_BYTE(0x80 | 8); //x=64
}
ST7920_SET_DAT();
ST7920_WRITE_BYTES(ptr, LCD_PIXEL_WIDTH / 8); //ptr is incremented inside of macro
y++;
}
break;
ST7920_NCS();
}
break;
}
#if PAGE_HEIGHT == 8
return u8g_dev_pb8h1_base_fn(u8g, dev, msg, arg);
@ -119,14 +107,13 @@ uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, vo
#endif
}
uint8_t u8g_dev_st7920_128x64_rrd_buf[LCD_PIXEL_WIDTH*(PAGE_HEIGHT/8)] U8G_NOCOMMON;
u8g_pb_t u8g_dev_st7920_128x64_rrd_pb = {{PAGE_HEIGHT,LCD_PIXEL_HEIGHT,0,0,0},LCD_PIXEL_WIDTH,u8g_dev_st7920_128x64_rrd_buf};
u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = {u8g_dev_rrd_st7920_128x64_fn,&u8g_dev_st7920_128x64_rrd_pb,&u8g_com_null_fn};
uint8_t u8g_dev_st7920_128x64_rrd_buf[LCD_PIXEL_WIDTH * (PAGE_HEIGHT / 8)] U8G_NOCOMMON;
u8g_pb_t u8g_dev_st7920_128x64_rrd_pb = {{PAGE_HEIGHT, LCD_PIXEL_HEIGHT, 0, 0, 0}, LCD_PIXEL_WIDTH, u8g_dev_st7920_128x64_rrd_buf};
u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = {u8g_dev_rrd_st7920_128x64_fn, &u8g_dev_st7920_128x64_rrd_pb, &u8g_com_null_fn};
class U8GLIB_ST7920_128X64_RRD : public U8GLIB
{
public:
U8GLIB_ST7920_128X64_RRD(uint8_t dummy) : U8GLIB(&u8g_dev_st7920_128x64_rrd_sw_spi) {}
class U8GLIB_ST7920_128X64_RRD : public U8GLIB {
public:
U8GLIB_ST7920_128X64_RRD(uint8_t dummy) : U8GLIB(&u8g_dev_st7920_128x64_rrd_sw_spi) {}
};

View File

@ -67,7 +67,7 @@
// À Á Â Ã Ä Å Æ Ç È É Ê Ë Ì Í Î Ï
0xd0,0xd1,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,0xdb,0xdc,0xdd,0xde,0xdf, // c39 ÐÑÓÔÕÖ×ØÙÚÛÜÝÞß
// Ð Ñ Ò Ó Ô Õ Ö × Ø Ù Ú Û Ü Ý Þ ß
0xe0,0xe1,0xe2,0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xeb,0xec,0xed,0xee,0xef, // c3a àáãäåæçèéêëìíîï
0xe0,0xe1,0xe2,0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xeb,0xec,0xed,0xee,0xef, // c3a àáãäåæçèéêëìíîï
// à á â ã ä å æ ç è é ê ë ì í î ï
0xf0,0xf1,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa,0xfb,0xfc,0xfd,0xfe,0xff // c3b ðñóôõö÷øùúûüýþÿ
// ð ñ ò ó ô õ ö ÷ ø ù ú û ü ý þ ÿ
@ -190,7 +190,7 @@
#elif ENABLED(MAPPER_D0D1)
uint8_t utf_hi_char; // UTF-8 high part
bool seen_d5 = false;
char charset_mapper(char c){
char charset_mapper(char c) {
uint8_t d = c;
if ( d >= 0x80u ) { // UTF-8 handling
if ((d >= 0xd0u) && (!seen_d5)) {
@ -218,7 +218,7 @@
bool seen_e3 = false;
bool seen_82_83 = false;
char charset_mapper(char c){
uint8_t d = c;
uint8_t d = c;
if ( d >= 0x80 ) { // UTF-8 handling
if ( (d == 0xe3) && (seen_e3 == false)) {
seen_e3 = true;

View File

@ -27,78 +27,78 @@ vector_3::vector_3() : x(0), y(0), z(0) { }
vector_3::vector_3(float x_, float y_, float z_) : x(x_), y(y_), z(z_) { }
vector_3 vector_3::cross(vector_3 left, vector_3 right) {
return vector_3(left.y * right.z - left.z * right.y,
left.z * right.x - left.x * right.z,
left.x * right.y - left.y * right.x);
return vector_3(left.y * right.z - left.z * right.y,
left.z * right.x - left.x * right.z,
left.x * right.y - left.y * right.x);
}
vector_3 vector_3::operator+(vector_3 v) { return vector_3((x + v.x), (y + v.y), (z + v.z)); }
vector_3 vector_3::operator-(vector_3 v) { return vector_3((x - v.x), (y - v.y), (z - v.z)); }
vector_3 vector_3::get_normal() {
vector_3 normalized = vector_3(x, y, z);
normalized.normalize();
return normalized;
vector_3 normalized = vector_3(x, y, z);
normalized.normalize();
return normalized;
}
float vector_3::get_length() { return sqrt((x * x) + (y * y) + (z * z)); }
void vector_3::normalize() {
float length = get_length();
x /= length;
y /= length;
z /= length;
float length = get_length();
x /= length;
y /= length;
z /= length;
}
void vector_3::apply_rotation(matrix_3x3 matrix) {
float resultX = x * matrix.matrix[3*0+0] + y * matrix.matrix[3*1+0] + z * matrix.matrix[3*2+0];
float resultY = x * matrix.matrix[3*0+1] + y * matrix.matrix[3*1+1] + z * matrix.matrix[3*2+1];
float resultZ = x * matrix.matrix[3*0+2] + y * matrix.matrix[3*1+2] + z * matrix.matrix[3*2+2];
x = resultX;
y = resultY;
z = resultZ;
float resultX = x * matrix.matrix[3 * 0 + 0] + y * matrix.matrix[3 * 1 + 0] + z * matrix.matrix[3 * 2 + 0];
float resultY = x * matrix.matrix[3 * 0 + 1] + y * matrix.matrix[3 * 1 + 1] + z * matrix.matrix[3 * 2 + 1];
float resultZ = x * matrix.matrix[3 * 0 + 2] + y * matrix.matrix[3 * 1 + 2] + z * matrix.matrix[3 * 2 + 2];
x = resultX;
y = resultY;
z = resultZ;
}
void vector_3::debug(const char title[]) {
SERIAL_PROTOCOL(title);
SERIAL_PROTOCOLPGM(" x: ");
SERIAL_PROTOCOL_F(x, 6);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL_F(y, 6);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL_F(z, 6);
SERIAL_EOL;
SERIAL_PROTOCOL(title);
SERIAL_PROTOCOLPGM(" x: ");
SERIAL_PROTOCOL_F(x, 6);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL_F(y, 6);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL_F(z, 6);
SERIAL_EOL;
}
void apply_rotation_xyz(matrix_3x3 matrix, float &x, float& y, float& z) {
vector_3 vector = vector_3(x, y, z);
vector.apply_rotation(matrix);
x = vector.x;
y = vector.y;
z = vector.z;
void apply_rotation_xyz(matrix_3x3 matrix, float& x, float& y, float& z) {
vector_3 vector = vector_3(x, y, z);
vector.apply_rotation(matrix);
x = vector.x;
y = vector.y;
z = vector.z;
}
matrix_3x3 matrix_3x3::create_from_rows(vector_3 row_0, vector_3 row_1, vector_3 row_2) {
//row_0.debug("row_0");
//row_1.debug("row_1");
//row_2.debug("row_2");
matrix_3x3 new_matrix;
new_matrix.matrix[0] = row_0.x; new_matrix.matrix[1] = row_0.y; new_matrix.matrix[2] = row_0.z;
new_matrix.matrix[3] = row_1.x; new_matrix.matrix[4] = row_1.y; new_matrix.matrix[5] = row_1.z;
new_matrix.matrix[6] = row_2.x; new_matrix.matrix[7] = row_2.y; new_matrix.matrix[8] = row_2.z;
matrix_3x3 new_matrix;
new_matrix.matrix[0] = row_0.x; new_matrix.matrix[1] = row_0.y; new_matrix.matrix[2] = row_0.z;
new_matrix.matrix[3] = row_1.x; new_matrix.matrix[4] = row_1.y; new_matrix.matrix[5] = row_1.z;
new_matrix.matrix[6] = row_2.x; new_matrix.matrix[7] = row_2.y; new_matrix.matrix[8] = row_2.z;
//new_matrix.debug("new_matrix");
return new_matrix;
return new_matrix;
}
void matrix_3x3::set_to_identity() {
matrix[0] = 1; matrix[1] = 0; matrix[2] = 0;
matrix[3] = 0; matrix[4] = 1; matrix[5] = 0;
matrix[6] = 0; matrix[7] = 0; matrix[8] = 1;
matrix[0] = 1; matrix[1] = 0; matrix[2] = 0;
matrix[3] = 0; matrix[4] = 1; matrix[5] = 0;
matrix[6] = 0; matrix[7] = 0; matrix[8] = 1;
}
matrix_3x3 matrix_3x3::create_look_at(vector_3 target) {
vector_3 z_row = target.get_normal();
vector_3 x_row = vector_3(1, 0, -target.x/target.z).get_normal();
vector_3 x_row = vector_3(1, 0, -target.x / target.z).get_normal();
vector_3 y_row = vector_3::cross(z_row, x_row).get_normal();
// x_row.debug("x_row");
@ -114,8 +114,8 @@ matrix_3x3 matrix_3x3::create_look_at(vector_3 target) {
matrix_3x3 matrix_3x3::transpose(matrix_3x3 original) {
matrix_3x3 new_matrix;
new_matrix.matrix[0] = original.matrix[0]; new_matrix.matrix[1] = original.matrix[3]; new_matrix.matrix[2] = original.matrix[6];
new_matrix.matrix[3] = original.matrix[1]; new_matrix.matrix[4] = original.matrix[4]; new_matrix.matrix[5] = original.matrix[7];
new_matrix.matrix[0] = original.matrix[0]; new_matrix.matrix[1] = original.matrix[3]; new_matrix.matrix[2] = original.matrix[6];
new_matrix.matrix[3] = original.matrix[1]; new_matrix.matrix[4] = original.matrix[4]; new_matrix.matrix[5] = original.matrix[7];
new_matrix.matrix[6] = original.matrix[2]; new_matrix.matrix[7] = original.matrix[5]; new_matrix.matrix[8] = original.matrix[8];
return new_matrix;
}
@ -123,8 +123,8 @@ matrix_3x3 matrix_3x3::transpose(matrix_3x3 original) {
void matrix_3x3::debug(const char title[]) {
SERIAL_PROTOCOLLN(title);
int count = 0;
for(int i=0; i<3; i++) {
for(int j=0; j<3; j++) {
for (int i = 0; i < 3; i++) {
for (int j = 0; j < 3; j++) {
if (matrix[count] >= 0.0) SERIAL_PROTOCOLCHAR('+');
SERIAL_PROTOCOL_F(matrix[count], 6);
SERIAL_PROTOCOLCHAR(' ');

View File

@ -22,41 +22,39 @@
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
class matrix_3x3;
struct vector_3
{
float x, y, z;
struct vector_3 {
float x, y, z;
vector_3();
vector_3(float x, float y, float z);
vector_3();
vector_3(float x, float y, float z);
static vector_3 cross(vector_3 a, vector_3 b);
static vector_3 cross(vector_3 a, vector_3 b);
vector_3 operator+(vector_3 v);
vector_3 operator-(vector_3 v);
void normalize();
float get_length();
vector_3 get_normal();
vector_3 operator+(vector_3 v);
vector_3 operator-(vector_3 v);
void normalize();
float get_length();
vector_3 get_normal();
void debug(const char title[]);
void apply_rotation(matrix_3x3 matrix);
void debug(const char title[]);
void apply_rotation(matrix_3x3 matrix);
};
struct matrix_3x3
{
float matrix[9];
struct matrix_3x3 {
float matrix[9];
static matrix_3x3 create_from_rows(vector_3 row_0, vector_3 row_1, vector_3 row_2);
static matrix_3x3 create_look_at(vector_3 target);
static matrix_3x3 transpose(matrix_3x3 original);
static matrix_3x3 create_from_rows(vector_3 row_0, vector_3 row_1, vector_3 row_2);
static matrix_3x3 create_look_at(vector_3 target);
static matrix_3x3 transpose(matrix_3x3 original);
void set_to_identity();
void set_to_identity();
void debug(const char title[]);
void debug(const char title[]);
};
void apply_rotation_xyz(matrix_3x3 rotationMatrix, float &x, float& y, float& z);
void apply_rotation_xyz(matrix_3x3 rotationMatrix, float& x, float& y, float& z);
#endif // AUTO_BED_LEVELING_FEATURE
#endif // VECTOR_3_H

View File

@ -16,8 +16,7 @@
/// intialise watch dog with a 4 sec interrupt time
void watchdog_init()
{
void watchdog_init() {
#if ENABLED(WATCHDOG_RESET_MANUAL)
//We enable the watchdog timer, but only for the interrupt.
//Take care, as this requires the correct order of operation, with interrupts disabled. See the datasheet of any AVR chip for details.
@ -30,9 +29,8 @@ void watchdog_init()
}
/// reset watchdog. MUST be called every 1s after init or avr will reset.
void watchdog_reset()
{
wdt_reset();
void watchdog_reset() {
wdt_reset();
}
//===========================================================================
@ -41,12 +39,11 @@ void watchdog_reset()
//Watchdog timer interrupt, called if main program blocks >1sec and manual reset is enabled.
#if ENABLED(WATCHDOG_RESET_MANUAL)
ISR(WDT_vect)
{
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Something is wrong, please turn off the printer.");
kill(PSTR("ERR:Please Reset")); //kill blocks //16 characters so it fits on a 16x2 display
while(1); //wait for user or serial reset
ISR(WDT_vect) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Something is wrong, please turn off the printer.");
kill(PSTR("ERR:Please Reset")); //kill blocks //16 characters so it fits on a 16x2 display
while (1); //wait for user or serial reset
}
#endif//RESET_MANUAL