Commit 1c459e31 authored by MagoKimbra's avatar MagoKimbra

Start on GitHub

Start on GitHub
parent 973b7c69
# Auto detect text files and perform LF normalization
* text=auto
# Custom for Visual Studio
*.cs diff=csharp
*.sln merge=union
*.csproj merge=union
*.vbproj merge=union
*.fsproj merge=union
*.dbproj merge=union
# Standard to msysgit
*.doc diff=astextplain
*.DOC diff=astextplain
*.docx diff=astextplain
*.DOCX diff=astextplain
*.dot diff=astextplain
*.DOT diff=astextplain
*.pdf diff=astextplain
*.PDF diff=astextplain
*.rtf diff=astextplain
*.RTF diff=astextplain
/*
BlinkM.cpp - Library for controlling a BlinkM over i2c
Created by Tim Koster, August 21 2013.
*/
#include "Marlin.h"
#ifdef BLINKM
#if (ARDUINO >= 100)
# include "Arduino.h"
#else
# include "WProgram.h"
#endif
#include "BlinkM.h"
void SendColors(byte red, byte grn, byte blu)
{
Wire.begin();
Wire.beginTransmission(0x09);
Wire.write('o'); //to disable ongoing script, only needs to be used once
Wire.write('n');
Wire.write(red);
Wire.write(grn);
Wire.write(blu);
Wire.endTransmission();
}
#endif //BLINKM
/*
BlinkM.h
Library header file for BlinkM library
*/
#if (ARDUINO >= 100)
# include "Arduino.h"
#else
# include "WProgram.h"
#endif
#include "Wire.h"
void SendColors(byte red, byte grn, byte blu);
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
#ifndef CONFIG_STORE_H
#define CONFIG_STORE_H
#include "Configuration.h"
void Config_ResetDefault();
#ifndef DISABLE_M503
void Config_PrintSettings();
#else
FORCE_INLINE void Config_PrintSettings() {}
#endif
#ifdef EEPROM_SETTINGS
void Config_StoreSettings();
void Config_RetrieveSettings();
#else
FORCE_INLINE void Config_StoreSettings() {}
FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); }
#endif
#endif//CONFIG_STORE_H
This diff is collapsed.
This diff is collapsed.
// Define this to set a custom name for your generic Mendel,
#define CUSTOM_MENDEL_NAME "Delta"
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
// #define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
//===========================================================================
//============================== Delta Settings =============================
//===========================================================================
// Make delta curves from many straight lines (linear interpolation).
// This is a trade-off between visible corners (not enough segments)
// and processor overload (too many expensive sqrt calls).
#define DELTA_SEGMENTS_PER_SECOND 200
// Center-to-center distance of the holes in the diagonal push rods.
#define DEFAULT_DELTA_DIAGONAL_ROD 217 // mm
// Horizontal offset from middle of printer to smooth rod center.
#define DELTA_SMOOTH_ROD_OFFSET 145 // mm
// Horizontal offset of the universal joints on the end effector.
#define DELTA_EFFECTOR_OFFSET 20 // mm
// Horizontal offset of the universal joints on the carriages.
#define DELTA_CARRIAGE_OFFSET 20 // mm
// Printer radius
#define PRINTER_RADIUS 70
// Effective horizontal distance bridged by diagonal push rods.
#define DEFAULT_DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET-DELTA_EFFECTOR_OFFSET-DELTA_CARRIAGE_OFFSET)
//Uncomment to enable autocalibration debug messages
#define DEBUG_MESSAGES
// Precision for G30 delta autocalibration function
#define AUTOCALIBRATION_PRECISION 0.1 // mm
// Diameter of print bed - this is used to set the distance that autocalibration probes the bed at.
#define BED_DIAMETER 140 // mm
// Z-Probe variables
// Start and end location values are used to deploy/retract the probe (will move from start to end and back again)
#define PROBING_FEEDRATE 600 // Speed for individual probe Use: G30 A F600
#define Z_PROBE_OFFSET {0, -10, -11.5, 0} // X, Y, Z, E distance between hotend nozzle and deployed bed leveling probe.
#define Z_PROBE_DEPLOY_START_LOCATION {0, 0, 30, 0} // X, Y, Z, E start location for z-probe deployment sequence
#define Z_PROBE_DEPLOY_END_LOCATION {0, 0, 30, 0} // X, Y, Z, E end location for z-probe deployment sequence
#define Z_PROBE_RETRACT_START_LOCATION {0, 0, 30, 0} // X, Y, Z, E start location for z-probe retract sequence
#define Z_PROBE_RETRACT_END_LOCATION {0, 0, 30, 0} // X, Y, Z, E end location for z-probe retract sequence
#define AUTOLEVEL_GRID 30 // Distance between autolevel Z probing points, should be less than print surface radius/3.
//===========================================================================
//=============================Mechanical Settings===========================
//===========================================================================
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
#ifdef ENDSTOPPULLUPS
#define ENDSTOPPULLUP_XMAX
#define ENDSTOPPULLUP_YMAX
#define ENDSTOPPULLUP_ZMAX
#define ENDSTOPPULLUP_XMIN
#define ENDSTOPPULLUP_YMIN
#define ENDSTOPPULLUP_ZMIN
#endif
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
#define DISABLE_E false // For all extruders
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
#define INVERT_X_DIR false
#define INVERT_Y_DIR false
#define INVERT_Z_DIR false
#define INVERT_E0_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E1_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E2_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
#define X_HOME_DIR 1
#define Y_HOME_DIR 1
#define Z_HOME_DIR 1
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
// Travel limits after homing
#define X_MAX_POS PRINTER_RADIUS
#define X_MIN_POS -PRINTER_RADIUS
#define Y_MAX_POS PRINTER_RADIUS
#define Y_MIN_POS -PRINTER_RADIUS
#define Z_MAX_POS MANUAL_Z_HOME_POS
#define Z_MIN_POS 0
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
// The position of the homing switches
#define MANUAL_HOME_POSITIONS // If defined, MANUAL_*_HOME_POS below will be used
#define BED_CENTER_AT_0_0 // If defined, the center of the bed is at (X=0, Y=0)
//Manual homing switch locations:
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 202 // Distance between nozzle and print surface after homing.
//// MOVEMENT SETTINGS
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {100*60, 100*60, 100*60, 0} // set the homing speeds (mm/min)
// default settings
// delta speeds must be the same on xyz
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,80,451,451,451,451} // X, Y, Z, E0, E1, E2, E3
#define DEFAULT_MAX_FEEDRATE {300,300,300,45,45,45,45} // X, Y, Z, E0, E1, E2, E3 (mm/sec)
#define DEFAULT_RETRACTION_MAX_FEEDRATE {80,80,80,80} // E0, E1, E2, E3 (mm/sec)
#define DEFAULT_MAX_ACCELERATION {2000,2000,2000,2000} // X, Y, Z, E maximum start speed for accelerated moves.
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 4000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 20.0 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
This diff is collapsed.
This diff is collapsed.
#define START_BMPWIDTH 60 //Width in pixels
#define START_BMPHEIGHT 64 //Height in pixels
#define START_BMPBYTEWIDTH 8 //Width in bytes
const unsigned char start_bmp[574] PROGMEM = { //AVR-GCC, WinAVR
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xF9,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xF0,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xE0,0x7F,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xC0,0x3F,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0x80,0x1F,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0x00,0x0F,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFE,0x00,0x07,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFC,0x00,0x03,0xFF,0xFF,0xF0,
0xFF,0xFF,0xF8,0x00,0x01,0xFF,0xFF,0xF0,
0xFF,0xFF,0xF0,0x00,0x00,0xFF,0xFF,0xF0,
0xFF,0xFF,0xE0,0x00,0x00,0x7F,0xFF,0xF0,
0xFF,0xFF,0xC0,0x00,0x00,0x3F,0xFF,0xF0,
0xFF,0xFF,0x80,0x00,0x00,0x3F,0xFF,0xF0,
0xFF,0xFF,0x00,0x00,0x00,0x1F,0xFF,0xF0,
0xFF,0xFE,0x00,0x00,0x00,0x0F,0xFF,0xF0,
0xFF,0xFE,0x00,0x00,0x00,0x07,0xFF,0xF0,
0xFF,0xFC,0x00,0x00,0x00,0x07,0xFF,0xF0,
0xFF,0xFC,0x00,0x00,0x00,0x03,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x03,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x03,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x03,0xFF,0xF0,
0xFF,0xF8,0x00,0x00,0x00,0x03,0xFF,0xF0,
0xFF,0xFC,0x00,0x00,0x00,0x03,0xFF,0xF0,
0xFF,0xFC,0x00,0x00,0x00,0x07,0xFF,0xF0,
0xFF,0xFE,0x00,0x00,0x00,0x07,0xFF,0xF0,
0xFF,0xFE,0x00,0x00,0x00,0x0F,0xFF,0xF0,
0xFF,0xFF,0x00,0x00,0x00,0x1F,0xFF,0xF0,
0xFF,0xFF,0x80,0x00,0x00,0x1F,0xFF,0xF0,
0xFF,0xFF,0xC0,0x00,0x00,0x3F,0xFF,0xF0,
0xFF,0xFF,0xE0,0x00,0x00,0x7F,0xFF,0xF0,
0xFF,0xFF,0xF0,0x00,0x01,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFC,0x00,0x03,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0x00,0x1F,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0,
0x83,0xFF,0xFF,0xFE,0x0F,0xFF,0xFF,0xF0,
0x80,0xFF,0xFF,0xFE,0x03,0xFF,0xFF,0xF0,
0x88,0x7F,0xFF,0xFE,0x23,0xFF,0xFF,0xF0,
0x8C,0x70,0x38,0x0E,0x71,0x81,0xC0,0x70,
0x8C,0x60,0x38,0x0E,0x63,0x80,0xC0,0x30,
0x80,0xE3,0x19,0xC6,0x07,0xF8,0xC7,0x30,
0x80,0xE0,0x19,0xC6,0x03,0x80,0xC7,0x10,
0x8C,0x62,0x79,0xC6,0x63,0x9C,0xC7,0x30,
0x8C,0x63,0xF8,0xC6,0x71,0x18,0xC6,0x30,
0x8E,0x30,0x18,0x0E,0x71,0x80,0xC0,0x30,
0x9E,0x38,0x39,0x1E,0x79,0xC4,0xC4,0xF0,
0xFF,0xFF,0xF9,0xFF,0xFF,0xFF,0xC7,0xF0,
0xFF,0xFF,0xF9,0xFF,0xFF,0xFF,0xC7,0xF0,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0
};
#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
};
This diff is collapsed.
//
// based on LiquidCrystal library from ArduinoIDE, see http://arduino.cc
// modified 27 Jul 2011
// by Ilya V. Danilov http://mk90.ru/
//
#ifndef LiquidCrystalRus_h
#define LiquidCrystalRus_h
#include <inttypes.h>
#include "Print.h"
// commands
#define LCD_CLEARDISPLAY 0x01
#define LCD_RETURNHOME 0x02
#define LCD_ENTRYMODESET 0x04
#define LCD_DISPLAYCONTROL 0x08
#define LCD_CURSORSHIFT 0x10
#define LCD_FUNCTIONSET 0x20
#define LCD_SETCGRAMADDR 0x40
#define LCD_SETDDRAMADDR 0x80
// flags for display entry mode
#define LCD_ENTRYRIGHT 0x00
#define LCD_ENTRYLEFT 0x02
#define LCD_ENTRYSHIFTINCREMENT 0x01
#define LCD_ENTRYSHIFTDECREMENT 0x00
// flags for display on/off control
#define LCD_DISPLAYON 0x04
#define LCD_DISPLAYOFF 0x00
#define LCD_CURSORON 0x02
#define LCD_CURSOROFF 0x00
#define LCD_BLINKON 0x01
#define LCD_BLINKOFF 0x00
// flags for display/cursor shift
#define LCD_DISPLAYMOVE 0x08
#define LCD_CURSORMOVE 0x00
#define LCD_MOVERIGHT 0x04
#define LCD_MOVELEFT 0x00
// flags for function set
#define LCD_8BITMODE 0x10
#define LCD_4BITMODE 0x00
#define LCD_2LINE 0x08
#define LCD_1LINE 0x00
#define LCD_5x10DOTS 0x04
#define LCD_5x8DOTS 0x00
// enum for
#define LCD_DRAM_Normal 0x00
#define LCD_DRAM_WH1601 0x01
class LiquidCrystalRus : public Print {
public:
LiquidCrystalRus(uint8_t rs, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7);
LiquidCrystalRus(uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7);
LiquidCrystalRus(uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3);
LiquidCrystalRus(uint8_t rs, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3);
void init(uint8_t fourbitmode, uint8_t rs, uint8_t rw, uint8_t enable,
uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3,
uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7);
void begin(uint8_t cols, uint8_t rows, uint8_t charsize = LCD_5x8DOTS);
void clear();
void home();
void noDisplay();
void display();
void noBlink();
void blink();
void noCursor();
void cursor();
void scrollDisplayLeft();
void scrollDisplayRight();
void leftToRight();
void rightToLeft();
void autoscroll();
void noAutoscroll();
void createChar(uint8_t, uint8_t[]);
void setCursor(uint8_t, uint8_t);
#if defined(ARDUINO) && ARDUINO >= 100
virtual size_t write(uint8_t);
using Print::write;
#else
virtual void write(uint8_t);
#endif
void command(uint8_t);
void setDRAMModel(uint8_t);
private:
void send(uint8_t, uint8_t);
void writeNbits(uint8_t, uint8_t);
uint8_t recv(uint8_t);
uint8_t readNbits(uint8_t);
void pulseEnable();
uint8_t _rs_pin; // LOW: command. HIGH: character.
uint8_t _rw_pin; // LOW: write to LCD. HIGH: read from LCD.
uint8_t _enable_pin; // activated by a HIGH pulse.
uint8_t _data_pins[8];
uint8_t _displayfunction;
uint8_t _displaycontrol;
uint8_t _displaymode;
uint8_t _initialized;
uint8_t _numlines,_currline;
uint8_t _dram_model;
uint8_t utf_hi_char; // UTF-8 high part
};
#endif
This diff is collapsed.
// Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
// License: GPL
#ifndef MARLIN_H
#define MARLIN_H
#define FORCE_INLINE __attribute__((always_inline)) inline
#include <math.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <inttypes.h>
#include <util/delay.h>
#include <avr/pgmspace.h>
#include <avr/eeprom.h>
#include <avr/interrupt.h>
#include "fastio.h"
#include "Configuration.h"
#include "pins.h"
#ifndef AT90USB
#define HardwareSerial_h // trick to disable the standard HWserial
#endif
#if (ARDUINO >= 100)
# include "Arduino.h"
#else
# include "WProgram.h"
//Arduino < 1.0.0 does not define this, so we need to do it ourselves
# define analogInputToDigitalPin(p) ((p) + A0)
#endif
#ifdef AT90USB
#include "HardwareSerial.h"
#endif
#include "MarlinSerial.h"
#ifndef cbi
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
#endif
#ifndef sbi
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
#endif
#include "WString.h"
#ifdef AT90USB
#ifdef BTENABLED
#define MYSERIAL bt
#else
#define MYSERIAL Serial
#endif // BTENABLED
#else
#define MYSERIAL MSerial
#endif
#define SERIAL_PROTOCOL(x) (MYSERIAL.print(x))
#define SERIAL_PROTOCOL_F(x,y) (MYSERIAL.print(x,y))
#define SERIAL_PROTOCOLPGM(x) (serialprintPGM(PSTR(x)))
#define SERIAL_PROTOCOLLN(x) (MYSERIAL.print(x),MYSERIAL.write('\n'))
#define SERIAL_PROTOCOLLNPGM(x) (serialprintPGM(PSTR(x)),MYSERIAL.write('\n'))
const char errormagic[] PROGMEM ="Error:";
const char echomagic[] PROGMEM ="echo:";
#define SERIAL_ERROR_START (serialprintPGM(errormagic))
#define SERIAL_ERROR(x) SERIAL_PROTOCOL(x)
#define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x)
#define SERIAL_ERRORLN(x) SERIAL_PROTOCOLLN(x)
#define SERIAL_ERRORLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
#define SERIAL_ECHO_START (serialprintPGM(echomagic))
#define SERIAL_ECHO(x) SERIAL_PROTOCOL(x)
#define SERIAL_ECHOPGM(x) SERIAL_PROTOCOLPGM(x)
#define SERIAL_ECHOLN(x) SERIAL_PROTOCOLLN(x)
#define SERIAL_ECHOLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
#define SERIAL_ECHOPAIR(name,value) (serial_echopair_P(PSTR(name),(value)))
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)
{
char ch=pgm_read_byte(str);
while(ch)
{
MYSERIAL.write(ch);
ch=pgm_read_byte(++str);
}
}
void get_command();
void process_commands();
void manage_inactivity();
#if defined(DUAL_X_CARRIAGE) && defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1 \
&& defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
#define enable_x() do { WRITE(X_ENABLE_PIN, X_ENABLE_ON); WRITE(X2_ENABLE_PIN, X_ENABLE_ON); } while (0)
#define disable_x() do { WRITE(X_ENABLE_PIN,!X_ENABLE_ON); WRITE(X2_ENABLE_PIN,!X_ENABLE_ON); axis_known_position[X_AXIS] = false; } while (0)
#elif defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
#define disable_x() { WRITE(X_ENABLE_PIN,!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }
#else
#define enable_x() ;
#define disable_x() ;
#endif
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
#ifdef Y_DUAL_STEPPER_DRIVERS
#define enable_y() { WRITE(Y_ENABLE_PIN, Y_ENABLE_ON); WRITE(Y2_ENABLE_PIN, Y_ENABLE_ON); }
#define disable_y() { WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON); WRITE(Y2_ENABLE_PIN, !Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
#else
#define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
#define disable_y() { WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }
#endif
#else
#define enable_y() ;
#define disable_y() ;
#endif
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
#ifdef Z_DUAL_STEPPER_DRIVERS
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#else
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
#endif
#else
#define enable_z() ;
#define disable_z() ;
#endif
#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
#define enable_e0() WRITE(E0_ENABLE_PIN, E_ENABLE_ON)
#define disable_e0() WRITE(E0_ENABLE_PIN,!E_ENABLE_ON)
#else
#define enable_e0() /* nothing */
#define disable_e0() /* nothing */
#endif
#if (DRIVER_EXTRUDERS > 1) && defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
#define enable_e1() WRITE(E1_ENABLE_PIN, E_ENABLE_ON)
#define disable_e1() WRITE(E1_ENABLE_PIN,!E_ENABLE_ON)
#else
#define enable_e1() /* nothing */
#define disable_e1() /* nothing */
#endif
#if (DRIVER_EXTRUDERS > 2) && defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
#define enable_e2() WRITE(E2_ENABLE_PIN, E_ENABLE_ON)
#define disable_e2() WRITE(E2_ENABLE_PIN,!E_ENABLE_ON)
#else
#define enable_e2() /* nothing */
#define disable_e2() /* nothing */
#endif
#if (DRIVER_EXTRUDERS > 3) && defined(E3_ENABLE_PIN) && (E3_ENABLE_PIN > -1)
#define enable_e3() WRITE(E3_ENABLE_PIN, E_ENABLE_ON)
#define disable_e3() WRITE(E3_ENABLE_PIN,!E_ENABLE_ON)
#else
#define enable_e3() /* nothing */
#define disable_e3() /* nothing */
#endif
enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3};
void FlushSerialRequestResend();
void ClearToSend();
void get_coordinates();
#ifdef DELTA
float probe_bed(float x, float y);
void set_delta_constants();
void home_delta_axis();
void calibration_report();
void bed_probe_all();
void set_default_z_probe_offset();
void set_delta_constants();
void save_carriage_positions(int position_num);
void calculate_delta(float cartesian[3]);
void adjust_delta(float cartesian[3]);
void prepare_move_raw();
extern float delta[3];
extern float delta_tmp[3];
extern float delta_tower1_x,delta_tower1_y;
extern float delta_tower2_x,delta_tower2_y;
extern float delta_tower3_x,delta_tower3_y;
#endif
#ifdef SCARA
void calculate_delta(float cartesian[3]);
void calculate_SCARA_forward_Transform(float f_scara[3]);
#endif
void prepare_move();
void kill();
void pause();
void Stop();
bool IsStopped();
void enquecommand(const char *cmd); //put an ASCII command at the end of the current buffer.
void enquecommand_P(const char *cmd); //put an ASCII command at the end of the current buffer, read from flash
void prepare_arc_move(char isclockwise);
void clamp_to_software_endstops(float target[3]);
void refresh_cmd_timeout(void);
#ifdef FAST_PWM_FAN
void setPwmFrequency(uint8_t pin, int val);
#endif
#ifndef CRITICAL_SECTION_START
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
#define CRITICAL_SECTION_END SREG = _sreg;
#endif //CRITICAL_SECTION_START
extern float homing_feedrate[];
extern bool axis_relative_modes[];
extern int feedmultiply;
extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders
extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
extern float current_position[NUM_AXIS] ;
extern float add_homing[3];
#ifdef NPR2
extern int old_color; // old color for system NPR2
#endif
#ifdef DELTA
extern float z_probe_offset[3];
extern float endstop_adj[3];
extern float tower_adj[6];
extern float delta_radius;
extern float delta_diagonal_rod;
//*extern float Z_MAX_POS;
//*extern float Z_MAX_LENGTH;
#endif
#ifdef SCARA
extern float axis_scaling[3]; // Build size scaling
#endif
extern float min_pos[3];
extern float max_pos[3];
extern bool axis_known_position[3];
extern float lastpos[4];
extern float zprobe_zoffset;
extern int fanSpeed;
#ifdef BARICUDA
extern int ValvePressure;
extern int EtoPPressure;
#endif
#ifdef FAN_SOFT_PWM
extern unsigned char fanSpeedSoftPwm;
#endif
#ifdef FWRETRACT
extern bool autoretract_enabled;
extern bool retracted[EXTRUDERS];
extern float retract_length, retract_length_swap, retract_feedrate, retract_zlift;
extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate;
#endif
extern unsigned long starttime;
extern unsigned long stoptime;
// Handling multiple extruders pins
extern uint8_t active_extruder;
extern uint8_t active_driver;
#ifdef DIGIPOT_I2C
extern void digipot_i2c_set_current( int channel, float current );
extern void digipot_i2c_init();
#endif
#endif
/* -*- c++ -*- */
/*
Reprap firmware based on Sprinter and grbl.
Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
This firmware is a mashup between Sprinter and grbl.
(https://github.com/kliment/Sprinter)
(https://github.com/simen/grbl/tree)
It has preliminary support for Matthew Roberts advance algorithm
http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
*/
/* All the implementation is done in *.cpp files to get better compatibility with avr-gcc without the Arduino IDE */
/* Use this file to help the Arduino IDE find which Arduino libraries are needed and to keep documentation on GCode */
#include "Configuration.h"
#include "pins.h"
#ifdef ULTRA_LCD
#if defined(LCD_I2C_TYPE_PCF8575)
#include <Wire.h>
#include <LiquidCrystal_I2C.h>
#elif defined(LCD_I2C_TYPE_MCP23017) || defined(LCD_I2C_TYPE_MCP23008)
#include <Wire.h>
#include <LiquidTWI2.h>
#elif defined(DOGLCD)
#include <U8glib.h> // library for graphics LCD by Oli Kraus (https://code.google.com/p/u8glib/)
#else
#include <LiquidCrystal.h> // library for character LCD
#endif
#endif
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
#include <SPI.h>
#endif
#if defined(DIGIPOT_I2C)
#include <Wire.h>
#endif
/*
HardwareSerial.cpp - Hardware serial library for Wiring
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library 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
Lesser General Public License for more details.
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
*/
#include "Marlin.h"
#include "MarlinSerial.h"
#ifndef AT90USB
// 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)
#if UART_PRESENT(SERIAL_PORT)
ring_buffer rx_buffer = { { 0 }, 0, 0 };
#endif
FORCE_INLINE void store_char(unsigned char c)
{
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
// if we should be storing the received character into the location
// just before the tail (meaning that the head would advance to the
// current location of the tail), we're about to overflow the buffer
// and so we don't write the character or advance the head.
if (i != rx_buffer.tail) {
rx_buffer.buffer[rx_buffer.head] = c;
rx_buffer.head = i;
}
}
//#elif defined(SIG_USART_RECV)
#if defined(M_USARTx_RX_vect)
// fixed by Mark Sproul this is on the 644/644p
//SIGNAL(SIG_USART_RECV)
SIGNAL(M_USARTx_RX_vect)
{
unsigned char c = M_UDRx;
store_char(c);
}
#endif
// Constructors ////////////////////////////////////////////////////////////////
MarlinSerial::MarlinSerial()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void MarlinSerial::begin(long baud)
{
uint16_t baud_setting;
bool useU2X = true;
#if F_CPU == 16000000UL && SERIAL_PORT == 0
// hard-coded exception for compatibility with the bootloader shipped
// with the Duemilanove and previous boards and the firmware on the 8U2
// on the Uno and Mega 2560.
if (baud == 57600) {
useU2X = false;
}
#endif
if (useU2X) {
M_UCSRxA = 1 << M_U2Xx;
baud_setting = (F_CPU / 4 / baud - 1) / 2;
} else {
M_UCSRxA = 0;
baud_setting = (F_CPU / 8 / baud - 1) / 2;
}
// assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register)
M_UBRRxH = baud_setting >> 8;
M_UBRRxL = baud_setting;
sbi(M_UCSRxB, M_RXENx);
sbi(M_UCSRxB, M_TXENx);
sbi(M_UCSRxB, M_RXCIEx);
}
void MarlinSerial::end()
{
cbi(M_UCSRxB, M_RXENx);
cbi(M_UCSRxB, M_TXENx);
cbi(M_UCSRxB, M_RXCIEx);
}
int MarlinSerial::peek(void)
{
if (rx_buffer.head == rx_buffer.tail) {
return -1;
} else {
return rx_buffer.buffer[rx_buffer.tail];
}
}
int MarlinSerial::read(void)
{
// if the head isn't ahead of the tail, we don't have any characters
if (rx_buffer.head == rx_buffer.tail) {
return -1;
} else {
unsigned char c = rx_buffer.buffer[rx_buffer.tail];
rx_buffer.tail = (unsigned int)(rx_buffer.tail + 1) % RX_BUFFER_SIZE;
return c;
}
}
void MarlinSerial::flush()
{
// don't reverse this or there may be problems if the RX interrupt
// occurs after reading the value of rx_buffer_head but before writing
// the value to rx_buffer_tail; the previous value of rx_buffer_head
// may be written to rx_buffer_tail, making it appear as if the buffer
// don't reverse this or there may be problems if the RX interrupt
// occurs after reading the value of rx_buffer_head but before writing
// the value to rx_buffer_tail; the previous value of rx_buffer_head
// may be written to rx_buffer_tail, making it appear as if the buffer
// were full, not empty.
rx_buffer.head = rx_buffer.tail;
}
/// imports from print.h
void MarlinSerial::print(char c, int base)
{
print((long) c, base);
}
void MarlinSerial::print(unsigned char b, int base)
{
print((unsigned long) b, base);
}
void MarlinSerial::print(int n, int base)
{
print((long) n, base);
}
void MarlinSerial::print(unsigned int n, int base)
{
print((unsigned long) n, base);
}
void MarlinSerial::print(long n, int base)
{
if (base == 0) {
write(n);
} else if (base == 10) {
if (n < 0) {
print('-');
n = -n;
}
printNumber(n, 10);
} else {
printNumber(n, base);
}
}
void MarlinSerial::print(unsigned long n, int base)
{
if (base == 0) write(n);
else printNumber(n, base);
}
void MarlinSerial::print(double n, int digits)
{
printFloat(n, digits);
}
void MarlinSerial::println(void)
{
print('\r');
print('\n');
}
void MarlinSerial::println(const String &s)
{
print(s);
println();
}
void MarlinSerial::println(const char c[])
{
print(c);
println();
}
void MarlinSerial::println(char c, int base)
{
print(c, base);
println();
}
void MarlinSerial::println(unsigned char b, int base)
{
print(b, base);
println();
}
void MarlinSerial::println(int n, int base)
{
print(n, base);
println();
}
void MarlinSerial::println(unsigned int n, int base)
{
print(n, base);
println();
}
void MarlinSerial::println(long n, int base)
{
print(n, base);
println();
}
void MarlinSerial::println(unsigned long n, int base)
{
print(n, base);
println();
}
void MarlinSerial::println(double n, int digits)
{
print(n, digits);
println();
}
// Private Methods /////////////////////////////////////////////////////////////
void MarlinSerial::printNumber(unsigned long n, uint8_t base)
{
unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars.
unsigned long i = 0;
if (n == 0) {
print('0');
return;
}
while (n > 0) {
buf[i++] = n % base;
n /= base;
}
for (; i > 0; i--)
print((char) (buf[i - 1] < 10 ?
'0' + buf[i - 1] :
'A' + buf[i - 1] - 10));
}
void MarlinSerial::printFloat(double number, uint8_t digits)
{
// Handle negative numbers
if (number < 0.0)
{
print('-');
number = -number;
}
// Round correctly so that print(1.999, 2) prints as "2.00"
double rounding = 0.5;
for (uint8_t i=0; i<digits; ++i)
rounding /= 10.0;
number += rounding;
// Extract the integer part of the number and print it
unsigned long int_part = (unsigned long)number;
double remainder = number - (double)int_part;
print(int_part);
// Print the decimal point, but only if there are digits beyond
if (digits > 0)
print(".");
// Extract digits from the remainder one at a time
while (digits-- > 0)
{
remainder *= 10.0;
int toPrint = int(remainder);
print(toPrint);
remainder -= toPrint;
}
}
// Preinstantiate Objects //////////////////////////////////////////////////////
MarlinSerial MSerial;
#endif // whole file
#endif // !AT90USB
// For AT90USB targets use the UART for BT interfacing
#if defined(AT90USB) && defined (BTENABLED)
HardwareSerial bt;
#endif
/*
HardwareSerial.h - Hardware serial library for Wiring
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library 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
Lesser General Public License for more details.
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 28 September 2010 by Mark Sproul
*/
#ifndef MarlinSerial_h
#define MarlinSerial_h
#include "Marlin.h"
#if !defined(SERIAL_PORT)
#define SERIAL_PORT 0
#endif
// 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)))
// 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)
#if SERIAL_PORT == 0 && (!defined(UBRR0H) || !defined(UDR0)) // use un-numbered registers if necessary
#define SERIAL_REGNAME_INTERNAL(registerbase,number,suffix) registerbase##suffix
#else
#define SERIAL_REGNAME_INTERNAL(registerbase,number,suffix) registerbase##number##suffix
#endif
// 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_UBRRxH SERIAL_REGNAME(UBRR,SERIAL_PORT,H)
#define M_UBRRxL SERIAL_REGNAME(UBRR,SERIAL_PORT,L)
#define M_RXCx SERIAL_REGNAME(RXC,SERIAL_PORT,)
#define M_USARTx_RX_vect SERIAL_REGNAME(USART,SERIAL_PORT,_RX_vect)
#define M_U2Xx SERIAL_REGNAME(U2X,SERIAL_PORT,)
#define DEC 10
#define HEX 16
#define OCT 8
#define BIN 2
#define BYTE 0
#ifndef AT90USB
// Define constants and variables for buffering incoming serial data. We're
// using a ring buffer (I think), in which rx_buffer_head is the index of the
// location to which to write the next incoming character and rx_buffer_tail
// is the index of the location from which to read.
#define RX_BUFFER_SIZE 128
struct ring_buffer
{
unsigned char buffer[RX_BUFFER_SIZE];
int head;
int tail;
};
#if UART_PRESENT(SERIAL_PORT)
extern ring_buffer rx_buffer;
#endif
class MarlinSerial //: public Stream
{
public:
MarlinSerial();
void begin(long);
void end();
int peek(void);
int read(void);
void flush(void);
FORCE_INLINE int available(void)
{
return (unsigned int)(RX_BUFFER_SIZE + rx_buffer.head - rx_buffer.tail) % RX_BUFFER_SIZE;
}
FORCE_INLINE void write(uint8_t c)
{
while (!((M_UCSRxA) & (1 << M_UDREx)))
;
M_UDRx = c;
}
FORCE_INLINE void checkRx(void)
{
if((M_UCSRxA & (1<<M_RXCx)) != 0) {
unsigned char c = M_UDRx;
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
// if we should be storing the received character into the location
// just before the tail (meaning that the head would advance to the
// current location of the tail), we're about to overflow the buffer
// and so we don't write the character or advance the head.
if (i != rx_buffer.tail) {
rx_buffer.buffer[rx_buffer.head] = c;
rx_buffer.head = i;
}
}
}
private:
void printNumber(unsigned long, uint8_t);
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);
}
void print(char, int = BYTE);
void print(unsigned char, int = BYTE);
void print(int, int = DEC);
void print(unsigned int, int = DEC);
void print(long, int = DEC);
void print(unsigned long, int = DEC);
void print(double, int = 2);
void println(const String &s);
void println(const char[]);
void println(char, int = BYTE);
void println(unsigned char, int = BYTE);
void println(int, int = DEC);
void println(unsigned int, int = DEC);
void println(long, int = DEC);
void println(unsigned long, int = DEC);
void println(double, int = 2);
void println(void);
};
extern MarlinSerial MSerial;
#endif // !AT90USB
// Use the UART for BT in AT90USB configurations
#if defined(AT90USB) && defined (BTENABLED)
extern HardwareSerial bt;
#endif
#endif
This diff is collapsed.
This diff is collapsed.
/* Arduino Sd2Card Library
* Copyright (C) 2009 by William Greiman
*
* This file is part of the Arduino Sd2Card Library
*
* This Library 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 Library 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 the Arduino Sd2Card Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include "Marlin.h"
#ifdef SDSUPPORT
#ifndef Sd2Card_h
#define Sd2Card_h
/**
* \file
* \brief Sd2Card class for V2 SD/SDHC cards
*/
#include "SdFatConfig.h"
#include "Sd2PinMap.h"
#include "SdInfo.h"
//------------------------------------------------------------------------------
// SPI speed is F_CPU/2^(1 + index), 0 <= index <= 6
/** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
uint8_t const SPI_FULL_SPEED = 0;
/** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
uint8_t const SPI_HALF_SPEED = 1;
/** Set SCK rate to F_CPU/8. See Sd2Card::setSckRate(). */
uint8_t const SPI_QUARTER_SPEED = 2;
/** Set SCK rate to F_CPU/16. See Sd2Card::setSckRate(). */
uint8_t const SPI_EIGHTH_SPEED = 3;
/** Set SCK rate to F_CPU/32. See Sd2Card::setSckRate(). */
uint8_t const SPI_SIXTEENTH_SPEED = 4;
//------------------------------------------------------------------------------
/** init timeout ms */
uint16_t const SD_INIT_TIMEOUT = 2000;
/** erase timeout ms */
uint16_t const SD_ERASE_TIMEOUT = 10000;
/** read timeout ms */
uint16_t const SD_READ_TIMEOUT = 300;
/** write time out ms */
uint16_t const SD_WRITE_TIMEOUT = 600;
//------------------------------------------------------------------------------
// SD card errors
/** timeout error for command CMD0 (initialize card in SPI mode) */
uint8_t const SD_CARD_ERROR_CMD0 = 0X1;
/** CMD8 was not accepted - not a valid SD card*/
uint8_t const SD_CARD_ERROR_CMD8 = 0X2;
/** card returned an error response for CMD12 (write stop) */
uint8_t const SD_CARD_ERROR_CMD12 = 0X3;
/** card returned an error response for CMD17 (read block) */
uint8_t const SD_CARD_ERROR_CMD17 = 0X4;
/** card returned an error response for CMD18 (read multiple block) */
uint8_t const SD_CARD_ERROR_CMD18 = 0X5;
/** card returned an error response for CMD24 (write block) */
uint8_t const SD_CARD_ERROR_CMD24 = 0X6;
/** WRITE_MULTIPLE_BLOCKS command failed */
uint8_t const SD_CARD_ERROR_CMD25 = 0X7;
/** card returned an error response for CMD58 (read OCR) */
uint8_t const SD_CARD_ERROR_CMD58 = 0X8;
/** SET_WR_BLK_ERASE_COUNT failed */
uint8_t const SD_CARD_ERROR_ACMD23 = 0X9;
/** ACMD41 initialization process timeout */
uint8_t const SD_CARD_ERROR_ACMD41 = 0XA;
/** card returned a bad CSR version field */
uint8_t const SD_CARD_ERROR_BAD_CSD = 0XB;
/** erase block group command failed */
uint8_t const SD_CARD_ERROR_ERASE = 0XC;
/** card not capable of single block erase */
uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD;
/** Erase sequence timed out */
uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0XE;
/** card returned an error token instead of read data */
uint8_t const SD_CARD_ERROR_READ = 0XF;
/** read CID or CSD failed */
uint8_t const SD_CARD_ERROR_READ_REG = 0X10;
/** timeout while waiting for start of read data */
uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X11;
/** card did not accept STOP_TRAN_TOKEN */
uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X12;
/** card returned an error token as a response to a write operation */
uint8_t const SD_CARD_ERROR_WRITE = 0X13;
/** attempt to write protected block zero */
uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X14; // REMOVE - not used
/** card did not go ready for a multiple block write */
uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X15;
/** card returned an error to a CMD13 status check after a write */
uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X16;
/** timeout occurred during write programming */
uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X17;
/** incorrect rate selected */
uint8_t const SD_CARD_ERROR_SCK_RATE = 0X18;
/** init() not called */
uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0X19;
/** crc check error */
uint8_t const SD_CARD_ERROR_CRC = 0X20;
//------------------------------------------------------------------------------
// card types
/** Standard capacity V1 SD card */
uint8_t const SD_CARD_TYPE_SD1 = 1;
/** Standard capacity V2 SD card */
uint8_t const SD_CARD_TYPE_SD2 = 2;
/** High Capacity SD card */
uint8_t const SD_CARD_TYPE_SDHC = 3;
/**
* define SOFTWARE_SPI to use bit-bang SPI
*/
//------------------------------------------------------------------------------
#if MEGA_SOFT_SPI && (defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__))
#define SOFTWARE_SPI
#elif USE_SOFTWARE_SPI
#define SOFTWARE_SPI
#endif // MEGA_SOFT_SPI
//------------------------------------------------------------------------------
// SPI pin definitions - do not edit here - change in SdFatConfig.h
//
#ifndef 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;
#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;
#endif // SOFTWARE_SPI
//------------------------------------------------------------------------------
/**
* \class Sd2Card
* \brief Raw access to SD and SDHC flash memory cards.
*/
class Sd2Card {
public:
/** Construct an instance of Sd2Card. */
Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {}
uint32_t cardSize();
bool erase(uint32_t firstBlock, uint32_t lastBlock);
bool eraseSingleBlockEnable();
/**
* Set SD error code.
* \param[in] code value for error code.
*/
void error(uint8_t code) {errorCode_ = code;}
/**
* \return error code for last error. See Sd2Card.h for a list of error codes.
*/
int errorCode() const {return errorCode_;}
/** \return error data for last error. */
int errorData() const {return status_;}
/**
* Initialize an SD flash memory card with default clock rate and chip
* select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
*
* \return true for success or false for failure.
*/
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
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.
*
* \param[out] cid pointer to area for returned data.
*
* \return true for success or false for failure.
*/
bool readCID(cid_t* cid) {
return readRegister(CMD10, cid);
}
/**
* Read a card's CSD register. The CSD contains Card-Specific Data that
* provides information regarding access to the card's contents.
*
* \param[out] csd pointer to area for returned data.
*
* \return true for success or false for failure.
*/
bool readCSD(csd_t* csd) {
return readRegister(CMD9, csd);
}
bool readData(uint8_t *dst);
bool readStart(uint32_t blockNumber);
bool readStop();
bool setSckRate(uint8_t sckRateID);
/** Return the card type: SD V1, SD V2 or SDHC
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
*/
int type() const {return type_;}
bool writeBlock(uint32_t blockNumber, const uint8_t* src);
bool writeData(const uint8_t* src);
bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
bool writeStop();
private:
//----------------------------------------------------------------------------
uint8_t chipSelectPin_;
uint8_t errorCode_;
uint8_t spiRate_;
uint8_t status_;
uint8_t type_;
// private functions
uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
cardCommand(CMD55, 0);
return cardCommand(cmd, arg);
}
uint8_t cardCommand(uint8_t cmd, uint32_t arg);
bool readData(uint8_t* dst, uint16_t count);
bool readRegister(uint8_t cmd, void* buf);
void chipSelectHigh();
void chipSelectLow();
void type(uint8_t value) {type_ = value;}
bool waitNotBusy(uint16_t timeoutMillis);
bool writeData(uint8_t token, const uint8_t* src);
};
#endif // Sd2Card_h
#endif
\ No newline at end of file
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
/*
motion_control.h - high level interface for issuing motion commands
Part of Grbl
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011 Sungeun K. Jeon
Grbl 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.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef motion_control_h
#define motion_control_h
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used
// for vector transformation direction.
void mc_arc(float *position, float *target, float *offset, unsigned char axis_0, unsigned char axis_1,
unsigned char axis_linear, float feed_rate, float radius, unsigned char isclockwise, uint8_t extruder, uint8_t driver);
#endif
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment