|
#include "Motion86.h"
#include "SD.h"
// Generate machine objects. You can use up to three machines, machine 0~2, each with three axes.
// This example uses machine 0 and machine 1。
Machine machine(0);
Machine slave_machine(1);
// Stepper Motor enable pin。
int EnablePin = 4;
// This gcode file is stored in the SD card。
char *filename = "auto.gcode";
File gfile;
char buf[256];
int ptr;
bool working;
void setup() {
while (!Serial);
pinMode(EnablePin, OUTPUT);
// If necessary, the direction of motion of the axis can be reversed.
// In this example, you need to reverse the direction of the x-axis and the y-axis.
machine.config_ReverseDirection(AXIS_X);
machine.config_ReverseDirection(AXIS_Y);
// PPU (pulse per unit) is a virtual unit of length, depending on different needs.
// In this example, the unit length of the x-axis is set to 80 pulses, which corresponds to 1 mm in actual application.
machine.config_PPU(AXIS_X, 80.0);
machine.config_PPU(AXIS_Y, 80.0);
machine.config_PPU(AXIS_Z, 1600.0);
// Set software limits for machine movement.
machine.config_PosLimit(AXIS_X, 0, 300);
machine.config_PosLimit(AXIS_Y, 0, 200);
machine.config_PosLimit(AXIS_Z, 0, 300);
// Set the pin used by the limit switch to set the home point.
machine.config_HomePins(2, 7, 8);
// In this case the slave_machine needs to reverse the direction of the y-axis.
slave_machine.config_ReverseDirection(AXIS_Y);
// Set the PPU (pulse per unit) of slave_machine.
slave_machine.config_PPU(AXIS_X, 80.0);
slave_machine.config_PPU(AXIS_Y, 80.0);
slave_machine.config_PPU(AXIS_Z, 3200.0);
// Sets the software limits for slave_machine motion.
slave_machine.config_PosLimit(AXIS_X, 0, 200);
slave_machine.config_PosLimit(AXIS_Y, 0, 200);
slave_machine.config_PosLimit(AXIS_Z, 0, 300);
// Set the pin used by slave_machine to set the limit switch of the home point.
slave_machine.config_HomePins(21, 22, 23);
// Set slave_machine to EGearSlave of machine, which means slave_machine will calculate and follow the movement of machine.
machine.config_EGearSlave(slave_machine, 1.5, 0.5, 1.0);
// Before controlling, the machine must be started.
machine.machineOn();
// Activate software limits.
machine.enableSoftLimit();
// Sets the feed rate to the home point.
machine.setHomeSpeed(1000, 1000, 200);
slave_machine.setHomeSpeed(1000, 1000, 100);
// Open the gcode file in the SD card
if (SD.exists(filename)) {
gfile = SD.open(filename);
working = true;
} else {
Serial.print("File not exists: ");
Serial.println(filename);
while (1);
}
// Start the stepper motor。
digitalWrite(EnablePin, LOW);
// Return to the home point defined by the limit switches.
machine.home();
}
void loop() {
// Read and parse gcode files.
// slave_machine is a scaled gcode path, width x1.5, height x0.5.
if (working && !machine.isCmdBufferFull()) {
ptr = 0;
while (gfile.available()) {
buf[ptr] = gfile.read();
if (buf[ptr] == '\n') {
buf[ptr + 1] = '\0';
machine.gcode(buf);
break;
} else {
ptr ++;
}
}
if (!gfile.available())
{
Serial.println("GCODE FINISH");
gfile.close();
working = false;
}
}
}
|