Browse Source

Added M42, M80 and M81

pull/1/head
Erik van der Zalm 13 years ago
parent
commit
d7c4f0780b
  1. 38
      Marlin/Marlin.pde
  2. 4
      Marlin/pins.h

38
Marlin/Marlin.pde

@ -69,7 +69,6 @@ char version_string[] = "1.0.0 Alpha 1";
// M114 - Display current position // M114 - Display current position
//Custom M Codes //Custom M Codes
// M80 - Turn on Power Supply
// M20 - List SD card // M20 - List SD card
// M21 - Init SD card // M21 - Init SD card
// M22 - Release SD card // M22 - Release SD card
@ -80,6 +79,8 @@ char version_string[] = "1.0.0 Alpha 1";
// M27 - Report SD print status // M27 - Report SD print status
// M28 - Start SD write (M28 filename.g) // M28 - Start SD write (M28 filename.g)
// M29 - Stop SD write // M29 - Stop SD write
// M42 - Change pin status via gcode
// M80 - Turn on Power Supply
// M81 - Turn off Power Supply // M81 - Turn off Power Supply
// M82 - Set E codes absolute (default) // M82 - Set E codes absolute (default)
// M83 - Set E codes relative while in Absolute Coordinates (G90) mode // M83 - Set E codes relative while in Absolute Coordinates (G90) mode
@ -142,6 +143,8 @@ extern float HeaterPower;
#include "EEPROM.h" #include "EEPROM.h"
const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
float tt = 0, bt = 0; float tt = 0, bt = 0;
#ifdef WATCHPERIOD #ifdef WATCHPERIOD
int watch_raw = -1000; int watch_raw = -1000;
@ -772,6 +775,31 @@ inline void process_commands()
} }
break; break;
#endif //SDSUPPORT #endif //SDSUPPORT
case 42: //M42 -Change pin status via gcode
if (code_seen('S'))
{
int pin_status = code_value();
if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
{
int pin_number = code_value();
for(int i = 0; i < sizeof(sensitive_pins); i++)
{
if (sensitive_pins[i] == pin_number)
{
pin_number = -1;
break;
}
}
if (pin_number > -1)
{
pinMode(pin_number, OUTPUT);
digitalWrite(pin_number, pin_status);
analogWrite(pin_number, pin_status);
}
}
}
break;
case 104: // M104 case 104: // M104
if (code_seen('S')) target_raw[0] = temp2analog(code_value()); if (code_seen('S')) target_raw[0] = temp2analog(code_value());
#ifdef PIDTEMP #ifdef PIDTEMP
@ -907,6 +935,14 @@ inline void process_commands()
WRITE(FAN_PIN,LOW); WRITE(FAN_PIN,LOW);
analogWrite(FAN_PIN, 0); analogWrite(FAN_PIN, 0);
break; break;
#endif
#if (PS_ON_PIN > -1)
case 80: // M80 - ATX Power On
SET_OUTPUT(PS_ON_PIN); //GND
break;
case 81: // M81 - ATX Power Off
SET_INPUT(PS_ON_PIN); //Floating
break;
#endif #endif
case 82: case 82:
axis_relative_modes[3] = false; axis_relative_modes[3] = false;

4
Marlin/pins.h

@ -563,4 +563,8 @@
#ifndef KNOWN_BOARD #ifndef KNOWN_BOARD
#error Unknown MOTHERBOARD value in configuration.h #error Unknown MOTHERBOARD value in configuration.h
#endif #endif
//List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those!
#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, E_STEP_PIN, E_DIR_PIN, E_ENABLE_PIN, LED_PIN, PS_ON_PIN, HEATER_0_PIN, HEATER_1_PIN, HEATER_2_PIN, FAN_PIN, TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN}
#endif #endif

Loading…
Cancel
Save